throttle_node.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
32 #include "throttle.h"
33 
34 int main(int argc,char**argv)
35 {
36  // Initialize ROS
37  ros::init(argc,argv,"throttle_base");
38 
39  ros::NodeHandle nh("~");
40 
41  //Ip of the Arduino server
42  std::string ip;
43  //Port of the Arduino server
44  std::string port;
45 
46  //Obtain the ip as a ros::parameter
47  nh.param("server_ip",ip,std::string("Not found"));
48  //Obtain the port as a ros::parameter
49  nh.param("server_port",port,std::string("Not found"));
50 
51  //Create the Throttle Class
52  atlascar_base::Throttle throttle_control(nh,ip,port);
53 
54  //Initialize the Throttle control class
55  throttle_control.init();
56 
57  //Setup message advertise and subscription
58  throttle_control.setupMessaging();
59 
60  //Main program loop
61  throttle_control.loop();
62 
63  return 0;
64 }
Throttle class declaration.
Throttle monitor and control class.
Definition: throttle.h:66
void setupMessaging()
Start ros message subscribing and advertising.
Definition: throttle.h:146
int main(int argc, char **argv)
void init()
Initialize the class.
Definition: throttle.h:115
void loop()
Start main control loop.
Definition: throttle.h:161


atlascar_base
Author(s): Jorge Almeida, Sérgio Pinho, Miguel Oliveira, Pedro Salvado, Andre Oliveira and Pedro Pinheiro
autogenerated on Mon Mar 2 2015 01:31:23