00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #ifndef _ODOMETER_H_
00028 #define _ODOMETER_H_
00029
00035 #include <ros/ros.h>
00036 #include <iostream>
00037
00038 #include <odometer/OdometerStatus.h>
00039
00040 #include <topic_priority/topic_priority.h>
00041
00042 #include <diagnostic_updater/diagnostic_updater.h>
00043 #include <diagnostic_updater/publisher.h>
00044
00045 #include <boost/thread/thread.hpp>
00046 #include <boost/format.hpp>
00047 #include <boost/spirit/include/qi.hpp>
00048 #include <boost/spirit/include/phoenix_core.hpp>
00049 #include <boost/spirit/include/phoenix_operator.hpp>
00050
00051 #include <tcp_client/AsyncClient.h>
00052
00053 using namespace std;
00054
00055 namespace odometer
00056 {
00057
00064 class Odometer
00065 {
00066 public:
00089 Odometer(const ros::NodeHandle& nh,std::string ip,std::string port):
00090 server_ip_(ip),
00091 server_port_(port),
00092 nh_(nh), status_freq_("Odometer",updater_,diagnostic_updater::FrequencyStatusParam(&status_max_frequency_,&status_min_frequency_, 0.1, 10)),
00093 status_max_frequency_(8.0),
00094 status_min_frequency_(10.0),
00095 comm_(io_service_,server_ip_,server_port_)
00096 {
00097 }
00098
00099
00103 ~Odometer()
00104 {}
00105
00114 void init()
00115 {
00116
00117 updater_.setHardwareID("odometer");
00118 updater_.add("Odometer",this,&odometer::Odometer::diagnostics);
00119
00120
00121 comm_.readHandler.connect(boost::bind(&Odometer::newData,this,_1));
00122
00123
00124 comm_.connectHandler.connect(boost::bind(&Odometer::connectHandler,this));
00125 }
00126
00127
00135 void setupMessaging()
00136 {
00137 status_pub_ = nh_.advertise<odometer::OdometerStatus>("status", 1);
00138 }
00139
00140
00150 void loop()
00151 {
00152
00153 boost::thread thread(boost::bind(&boost::asio::io_service::run, &io_service_));
00154
00155 ros::Rate r(50);
00156
00157 do
00158 {
00159
00160 updater_.update();
00161
00162 ros::spinOnce();
00163 r.sleep();
00164 }while(ros::ok());
00165
00166
00167 io_service_.stop();
00168
00169 thread.join();
00170 }
00171
00176 private:
00177
00183 void connectHandler(void)
00184 {
00185 try
00186 {
00187 comm_.write("start");
00188 }catch(std::exception& e)
00189 {
00190 std::cout << "Exception: " << e.what() << "\n";
00191 }
00192 }
00193
00201 void newData(string data)
00202 {
00203 namespace qi = boost::spirit::qi;
00204 using qi::omit;
00205 using qi::double_;
00206 using qi::char_;
00207 using qi::ascii::space;
00208 using qi::_1;
00209 using boost::phoenix::ref;
00210
00211 data.erase(data.begin());
00212 data.erase(data.end()-2,data.end());
00213
00214 qi::phrase_parse(data.begin(),data.end(),
00215 omit[char_] >> double_[ref(status_.count) = _1] >>
00216 omit[char_] >> double_[ref(status_.pulses_sec) = _1] >>
00217 omit[char_] >> double_[ref(status_.revolutions_sec) = _1] >>
00218 omit[char_] >> double_[ref(status_.velocity) = _1]
00219 ,space);
00220 status_.header.stamp = ros::Time::now();
00221 status_.header.frame_id = "";
00222
00223 status_pub_.publish(status_);
00224 status_freq_.tick();
00225 }
00232 void diagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
00233 {
00234 if(!comm_.isConnected())
00235 {
00236 stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No connection to hardware.");
00237 stat.add("Status",comm_.error_.message());
00238 }else
00239 {
00240 stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "No problems.");
00241 stat.add("Connected with",server_ip_);
00242 stat.add("Port number",server_port_);
00243
00244 boost::format fmt("%.2f");
00245 fmt % (ros::Time::now()-status_.header.stamp).toSec();
00246
00247 stat.add("Last message sent", fmt.str()+" seconds ago" );
00248 }
00249 }
00250
00251
00253 std::string server_ip_;
00255 std::string server_port_;
00256
00258 ros::NodeHandle nh_;
00259
00261 ros::Publisher status_pub_;
00262
00264 odometer::OdometerStatus status_;
00265
00267 diagnostic_updater::Updater updater_;
00269 diagnostic_updater::HeaderlessTopicDiagnostic status_freq_;
00271 double status_max_frequency_;
00273 double status_min_frequency_;
00275 boost::asio::io_service io_service_;
00277 AsyncClient comm_;
00278 };
00279
00280 }
00281
00282 #endif