throttle.h
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 ***************************************************************************************************/
27 #ifndef _THROTTLE_H_
28 #define _THROTTLE_H_
29 
35 #include <ros/ros.h>
36 #include <iostream>
37 #include <boost/lexical_cast.hpp>
38 
39 #include <tcp_client/AsyncClient.h>
40 
41 #include <diagnostic_updater/diagnostic_updater.h>
42 #include <diagnostic_updater/publisher.h>
43 
44 #include <atlascar_base/ThrottleStatus.h>
45 #include <atlascar_base/ThrottleCommand.h>
46 
47 #include <topic_priority/topic_priority.h>
48 
49 #include <boost/thread/thread.hpp>
50 #include <boost/format.hpp>
51 #include <boost/spirit/include/qi.hpp>
52 #include <boost/spirit/include/phoenix_core.hpp>
53 #include <boost/spirit/include/phoenix_operator.hpp>
54 
55 using namespace std;
56 
57 namespace atlascar_base
58 {
59 
66 class Throttle
67 {
68  public:
91  Throttle(const ros::NodeHandle& nh,std::string ip,std::string port):
92  nh_(nh),
93  current_mode_(MANUAL),
94  server_ip_(ip),
95  server_port_(port), status_freq_("Throttle",updater_,diagnostic_updater::FrequencyStatusParam(&status_min_frequency_,&status_max_frequency_, 0.01, 10)),
96  status_max_frequency_(51.0),
97  status_min_frequency_(49.0),
98  comm_(io_service_,server_ip_,server_port_)
99  {}
100 
105  {}
106 
115  void init()
116  {
117  safety_command_.reset(new atlascar_base::ThrottleCommand);
118 
119  //Set the safety message default values, this messages will never be removed from the list
120  safety_command_->lifetime=INFINITY;
121  safety_command_->priority=0;
122  safety_command_->throttle=0;
123  safety_command_->mode=MANUAL;
124 
125  //Push the safety message into the queue
126  command_queue_.push_msg(safety_command_);
127 
128  //Set diagnostics
129  updater_.setHardwareID("throttle");
130  updater_.add("Throttle",this,&atlascar_base::Throttle::diagnostics);
131 
132  //Setup the new data handler
133  comm_.readHandler.connect(boost::bind(&Throttle::newData,this,_1));
134 
135  //Setup the on successful connection handler
136  comm_.connectHandler.connect(boost::bind(&Throttle::connectHandler,this));
137  }
138 
147  {
148  command_sub_ = nh_.subscribe("command", 1, &Throttle::commandCallback, this);
149  status_pub_ = nh_.advertise<atlascar_base::ThrottleStatus>("status", 1);
150  }
151 
161  void loop()
162  {
163  //Run io service on a different tread
164  boost::thread thread(boost::bind(&boost::asio::io_service::run, &io_service_));
165 
166  ros::Rate r(50);//Hz
167 
168  do
169  {
170  updater_.update();
171 
172  //Get top layer message, the command message that has the most priority and is still valid
173  command_=command_queue_.top_msg();
174 
175  //If the demanded mode is different from the current mode, set the mode
176  if(status_.mode!=(int)command_->mode)
177  {
178  boost::format fmt("set mode %d\n");
179  fmt % command_->mode;
180 
181  try
182  {
183  comm_.write(fmt.str());
184  }catch(std::exception& e)
185  {
186  std::cout<<"Cannot set mode: "<<e.what()<<std::endl;
187  }
188  }
189 
190  //If we are in auto mode send throttle
191  if(status_.mode==AUTO)
192  {
193  boost::format fmt("set throttle %lf\n");
194  fmt % command_->throttle;
195 
196  try
197  {
198  comm_.write(fmt.str());
199  }catch(std::exception& e)
200  {
201  std::cout<<"Cannot set throttle: "<<e.what()<<std::endl;
202  }
203  }
204 
205  if( comm_.isConnected() && (ros::Time::now()-status_.header.stamp).toSec() > 1.0)
206  {
207  comm_.reconnect();
208  }
209 
210  //Spin ros and sleep the desired amount
211  ros::spinOnce();
212  r.sleep();
213  }while(ros::ok());
214 
215  //Stop the io service running in a separate thread
216  io_service_.stop();
217  //Join the thread
218  thread.join();
219  }
220 
224  private:
225 
226  enum {MANUAL=0,AUTO=1};
227 
234  void diagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
235  {
236  if(!comm_.isConnected())
237  {
238  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No connection to hardware.");
239  stat.add("Status",comm_.error_.message());
240  stat.add("Trying to connect to",server_ip_);
241  stat.add("Port number",server_port_);
242  }else
243  {
244  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "No problems.");
245  stat.add("Connected with",server_ip_);
246  stat.add("Port number",server_port_);
247 
248  boost::format fmt("%.4f");
249  fmt % (ros::Time::now()-status_.header.stamp).toSec();
250 
251  stat.add("Last message received", fmt.str()+" seconds ago" );
252  }
253  }
254 
260  void connectHandler(void)
261  {
262  try
263  {
264  comm_.write("start");
265  }catch(std::exception& e)
266  {
267  std::cout << "Exception: " << e.what() << "\n";
268  }
269 
270  status_.header.stamp=ros::Time::now();
271  }
272 
278  void commandCallback(const atlascar_base::ThrottleCommandPtr& command)
279  {
280  command_queue_.push_msg(command);
281  }
282 
290  void newData(string data)
291  {
292  namespace qi = boost::spirit::qi;
293  using qi::double_;
294  using qi::int_;
295  using qi::ascii::space;
296  using boost::spirit::ascii::string;
297  using qi::_1;
298  using boost::phoenix::ref;
299 
300  //Parse the received data, the 3 strings must match exactly
301  qi::phrase_parse(data.begin(),data.end(),
302  string("mode") >> int_[ref(status_.mode) = _1] >>
303  string("throttle") >> double_[ref(status_.throttle) = _1] >>
304  string("pedal") >> double_[ref(status_.footPedal) = _1]
305  ,space);
306 
307  status_.header.stamp = ros::Time::now();
308  status_.header.frame_id = "";
309  status_pub_.publish(status_);
310  status_freq_.tick();
311  }
312 
314  ros::NodeHandle nh_;
316  ros::Subscriber command_sub_;
318  ros::Publisher status_pub_;
320  TopicQueuePriority<atlascar_base::ThrottleCommandPtr> command_queue_;
322  atlascar_base::ThrottleCommandPtr command_;
324  atlascar_base::ThrottleCommandPtr safety_command_;
326  atlascar_base::ThrottleStatus status_;
329 
331  std::string server_ip_;
333  std::string server_port_;
334 
336  diagnostic_updater::Updater updater_;
338  diagnostic_updater::HeaderlessTopicDiagnostic status_freq_;
343 
345  boost::asio::io_service io_service_;
347  AsyncClient comm_;
348 };
349 
350 }
351 
352 #endif
ros::Subscriber command_sub_
Ros command subscriber.
Definition: throttle.h:316
void newData(string data)
This function will be called (asynchronously) upon arrival of new data.
Definition: throttle.h:290
double status_min_frequency_
Minimum admissible frequency.
Definition: throttle.h:342
atlascar_base::ThrottleCommandPtr command_
Command message pointer.
Definition: throttle.h:322
diagnostic_updater::Updater updater_
Diagnostics class.
Definition: throttle.h:336
Throttle monitor and control class.
Definition: throttle.h:66
std::string server_port_
Throttle server port.
Definition: throttle.h:333
void setupMessaging()
Start ros message subscribing and advertising.
Definition: throttle.h:146
atlascar_base::ThrottleCommandPtr safety_command_
Safety command message pointer.
Definition: throttle.h:324
ros::NodeHandle nh_
Ros node handler.
Definition: throttle.h:314
Throttle(const ros::NodeHandle &nh, std::string ip, std::string port)
Class constructor.
Definition: throttle.h:91
boost::asio::io_service io_service_
Input/Output communication service.
Definition: throttle.h:345
int current_mode_
Current working mode.
Definition: throttle.h:328
atlascar_base::ThrottleStatus status_
Status message.
Definition: throttle.h:326
void commandCallback(const atlascar_base::ThrottleCommandPtr &command)
This function handles newly received commands.
Definition: throttle.h:278
TopicQueuePriority< atlascar_base::ThrottleCommandPtr > command_queue_
Command queue holding class.
Definition: throttle.h:320
~Throttle()
Class destructor.
Definition: throttle.h:104
void connectHandler(void)
This function will be called (asynchronously) on a successful connection.
Definition: throttle.h:260
void init()
Initialize the class.
Definition: throttle.h:115
diagnostic_updater::HeaderlessTopicDiagnostic status_freq_
Frequency diagnostics tool.
Definition: throttle.h:338
double status_max_frequency_
Maximum admissible frequency.
Definition: throttle.h:340
void loop()
Start main control loop.
Definition: throttle.h:161
ros::Publisher status_pub_
Ros status publisher.
Definition: throttle.h:318
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Diagnostics function handler.
Definition: throttle.h:234
std::string server_ip_
Throttle server ip.
Definition: throttle.h:331
AsyncClient comm_
Asynchronous tcp/ip communication object.
Definition: throttle.h:347


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