odometer.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 _ODOMETER_H_
28 #define _ODOMETER_H_
29 
35 #include <ros/ros.h>
36 #include <iostream>
37 
38 #include <odometer/OdometerStatus.h>
39 
40 #include <topic_priority/topic_priority.h>
41 
42 #include <diagnostic_updater/diagnostic_updater.h>
43 #include <diagnostic_updater/publisher.h>
44 
45 #include <boost/thread/thread.hpp>
46 #include <boost/format.hpp>
47 #include <boost/spirit/include/qi.hpp>
48 #include <boost/spirit/include/phoenix_core.hpp>
49 #include <boost/spirit/include/phoenix_operator.hpp>
50 
51 #include <tcp_client/AsyncClient.h>
52 
53 using namespace std;
54 
55 namespace odometer
56 {
57 
64 class Odometer
65 {
66  public:
89  Odometer(const ros::NodeHandle& nh,std::string ip,std::string port):
90  server_ip_(ip),
91  server_port_(port),
92  nh_(nh), status_freq_("Odometer",updater_,diagnostic_updater::FrequencyStatusParam(&status_max_frequency_,&status_min_frequency_, 0.1, 10)),
93  status_max_frequency_(8.0),
94  status_min_frequency_(10.0),
95  comm_(io_service_,server_ip_,server_port_)
96  {
97  }
98 
99 
104  {}
105 
114  void init()
115  {
116  //Set diagnostics
117  updater_.setHardwareID("odometer");
118  updater_.add("Odometer",this,&odometer::Odometer::diagnostics);
119 
120  //Setup the new data handler
121  comm_.readHandler.connect(boost::bind(&Odometer::newData,this,_1));
122 
123  //Setup the on successful connection handler
124  comm_.connectHandler.connect(boost::bind(&Odometer::connectHandler,this));
125  }
126 
127 
136  {
137  status_pub_ = nh_.advertise<odometer::OdometerStatus>("status", 1);
138  }
139 
140 
150  void loop()
151  {
152  //Run io service on a different tread
153  boost::thread thread(boost::bind(&boost::asio::io_service::run, &io_service_));
154 
155  ros::Rate r(50);//Hz
156 
157  do
158  {
159  //Update the diagnostics tool
160  updater_.update();
161  //Spin ros and sleep the desired amount
162  ros::spinOnce();
163  r.sleep();
164  }while(ros::ok());
165 
166  //Stop the io service running in a separate thread
167  io_service_.stop();
168  //Join the thread
169  thread.join();
170  }
171 
176  private:
177 
183  void connectHandler(void)
184  {
185  try
186  {
187  comm_.write("start");
188  }catch(std::exception& e)
189  {
190  std::cout << "Exception: " << e.what() << "\n";
191  }
192  }
193 
201  void newData(string data)
202  {
203  namespace qi = boost::spirit::qi;
204  using qi::omit;
205  using qi::double_;
206  using qi::char_;
207  using qi::ascii::space;
208  using qi::_1;
209  using boost::phoenix::ref;
210 
211  data.erase(data.begin());
212  data.erase(data.end()-2,data.end());
213 
214  qi::phrase_parse(data.begin(),data.end(),
215  omit[char_] >> double_[ref(status_.count) = _1] >>
216  omit[char_] >> double_[ref(status_.pulses_sec) = _1] >>
217  omit[char_] >> double_[ref(status_.revolutions_sec) = _1] >>
218  omit[char_] >> double_[ref(status_.velocity) = _1]
219  ,space);
220  status_.header.stamp = ros::Time::now();
221  status_.header.frame_id = "";
222 
223  status_pub_.publish(status_);
224  status_freq_.tick();
225  }
232  void diagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
233  {
234  if(!comm_.isConnected())
235  {
236  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No connection to hardware.");
237  stat.add("Status",comm_.error_.message());
238  }else
239  {
240  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "No problems.");
241  stat.add("Connected with",server_ip_);
242  stat.add("Port number",server_port_);
243 
244  boost::format fmt("%.2f");
245  fmt % (ros::Time::now()-status_.header.stamp).toSec();
246 
247  stat.add("Last message sent", fmt.str()+" seconds ago" );
248  }
249  }
250 
251 
253  std::string server_ip_;
255  std::string server_port_;
256 
258  ros::NodeHandle nh_;
259 
261  ros::Publisher status_pub_;
262 
264  odometer::OdometerStatus status_;
265 
267  diagnostic_updater::Updater updater_;
269  diagnostic_updater::HeaderlessTopicDiagnostic status_freq_;
275  boost::asio::io_service io_service_;
277  AsyncClient comm_;
278 };
279 
280 }
281 
282 #endif
Odometer monitor class.
Definition: odometer.h:64
odometer::OdometerStatus status_
Status message.
Definition: odometer.h:264
ros::NodeHandle nh_
Ros node handler.
Definition: odometer.h:258
void loop()
Start main control loop.
Definition: odometer.h:150
diagnostic_updater::HeaderlessTopicDiagnostic status_freq_
Frequency diagnostics tool.
Definition: odometer.h:269
void connectHandler(void)
This function will be called (asynchronously) on a successful connection.
Definition: odometer.h:183
boost::asio::io_service io_service_
Input/Output communication service.
Definition: odometer.h:275
std::string server_ip_
Ip of the Arduino server.
Definition: odometer.h:253
void init()
Initialize the class.
Definition: odometer.h:114
ros::Publisher status_pub_
Ros status publisher.
Definition: odometer.h:261
double status_max_frequency_
Maximum admissible frequency.
Definition: odometer.h:271
void newData(string data)
This function will be called (asynchronously) upon arrival of new data.
Definition: odometer.h:201
double status_min_frequency_
Minimum admissible frequency.
Definition: odometer.h:273
diagnostic_updater::Updater updater_
Diagnostics class.
Definition: odometer.h:267
Odometer(const ros::NodeHandle &nh, std::string ip, std::string port)
Class constructor.
Definition: odometer.h:89
AsyncClient comm_
Asynchronous tcp/ip communication object.
Definition: odometer.h:277
~Odometer()
Class destructor.
Definition: odometer.h:103
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Diagnostics function handler.
Definition: odometer.h:232
std::string server_port_
Port of the Arduino server.
Definition: odometer.h:255
void setupMessaging()
Start ros message subscribing and advertising.
Definition: odometer.h:135


odometer
Author(s): Jorge Almeida
autogenerated on Mon Mar 2 2015 01:32:30