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 _HUMAN_DRIVER_MONITOR_H_
00028 #define _HUMAN_DRIVER_MONITOR_H_
00029
00035 #include <ros/ros.h>
00036 #include <iostream>
00037
00038 #include <human_driver_monitor/HumanDriverMonitorStatus.h>
00039
00040 #include <diagnostic_updater/diagnostic_updater.h>
00041 #include <diagnostic_updater/publisher.h>
00042 #include <boost/thread/thread.hpp>
00043
00044 #include <tcp_client/AsyncClient.h>
00045 #include <boost/format.hpp>
00046 #include <boost/thread/thread.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 using namespace std;
00052
00053 namespace human_driver_monitor
00054 {
00055
00062 class HumanDriverMonitor
00063 {
00064 public:
00083 HumanDriverMonitor(const ros::NodeHandle& nh,std::string ip,std::string port):
00084 server_ip_(ip),
00085 server_port_(port),
00086 nh_(nh),
00087 status_freq_("HumanDriverMonitor",updater_,diagnostic_updater::FrequencyStatusParam(&status_max_frequency_,&status_min_frequency_, 0.1, 10)),
00088 status_max_frequency_(50.0),
00089 status_min_frequency_(70.0),
00090 comm_(io_service_,server_ip_,server_port_)
00091 {}
00092
00096 ~HumanDriverMonitor()
00097 {}
00098
00107 void init()
00108 {
00109
00110 updater_.setHardwareID("human driver monitor");
00111 updater_.add("HumanDriverMonitor",this,&human_driver_monitor::HumanDriverMonitor::diagnostics);
00112
00113
00114 comm_.readHandler.connect(boost::bind(&HumanDriverMonitor::newData,this,_1));
00115
00116
00117 comm_.connectHandler.connect(boost::bind(&HumanDriverMonitor::connectHandler,this));
00118 }
00119
00127 void setupMessaging()
00128 {
00129 status_pub_ = nh_.advertise<human_driver_monitor::HumanDriverMonitorStatus>("status", 1);
00130 }
00131
00141 void loop()
00142 {
00143
00144 boost::thread thread(boost::bind(&boost::asio::io_service::run, &io_service_));
00145
00146 ros::Rate r(50);
00147
00148 do
00149 {
00150
00151 updater_.update();
00152
00153 ros::spinOnce();
00154 r.sleep();
00155 }while(ros::ok());
00156
00157
00158 io_service_.stop();
00159
00160 thread.join();
00161 }
00162
00167 protected:
00168
00174 void connectHandler(void)
00175 {
00176 try
00177 {
00178 comm_.write("start");
00179 }catch(std::exception& e)
00180 {
00181 std::cout << "Exception: " << e.what() << "\n";
00182 }
00183 }
00184
00191 void newData(string data)
00192 {
00193
00194 data.erase(0,1);
00195 data.erase(data.end()-2,data.end());
00196
00197
00198
00199 if(data[1]=='1')
00200 status_.lights_high=1;
00201 else
00202 status_.lights_high=0;
00203
00204 if(data[5]=='1')
00205 status_.lights_medium=1;
00206 else
00207 status_.lights_medium=0;
00208
00209 if(data[2]=='1')
00210 status_.ignition=1;
00211 else
00212 status_.ignition=0;
00213
00214 if(data[6]=='1')
00215 status_.horn=1;
00216 else
00217 status_.horn=0;
00218
00219 if(data[3]=='1')
00220 status_.lights_left=1;
00221 else
00222 status_.lights_left=0;
00223
00224 if(data[4]=='1')
00225 status_.lights_right=1;
00226 else
00227 status_.lights_right=0;
00228
00229 if(status_.lights_left && status_.lights_right)
00230 status_.lights_danger=1;
00231 else
00232 status_.lights_danger=0;
00233
00234 data.erase(0,7);
00235
00236
00237 namespace qi = boost::spirit::qi;
00238 using qi::omit;
00239 using qi::int_;
00240 using qi::char_;
00241 using qi::ascii::space;
00242 using qi::_1;
00243 using boost::phoenix::ref;
00244
00245 qi::phrase_parse(data.begin(),data.end(),
00246 omit[char_] >> int_[ref(status_.throttle_pressure) = _1] >>
00247 omit[char_] >> int_[ref(status_.brake_pressure) = _1] >>
00248 omit[char_] >> int_[ref(status_.clutch_pressure) = _1]
00249 ,space);
00250
00251 status_.header.stamp = ros::Time::now();
00252 status_.header.frame_id = "";
00253 status_pub_.publish(status_);
00254 status_freq_.tick();
00255 }
00256
00263 void diagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
00264 {
00265 if(!comm_.isConnected())
00266 {
00267 stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No connection to hardware.");
00268 stat.add("Status",comm_.error_.message());
00269 stat.add("Connecting to",server_ip_);
00270 stat.add("Port number",server_port_);
00271 }else
00272 {
00273 stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "No problems.");
00274 stat.add("Connected with",server_ip_);
00275 stat.add("Port number",server_port_);
00276
00277 boost::format fmt("%.2f");
00278 fmt % (ros::Time::now()-status_.header.stamp).toSec();
00279
00280 stat.add("Last message sent", fmt.str()+" seconds ago" );
00281 }
00282 }
00283
00285 std::string server_ip_;
00287 std::string server_port_;
00288
00290 ros::NodeHandle nh_;
00291
00293 ros::Publisher status_pub_;
00294
00296 human_driver_monitor::HumanDriverMonitorStatus status_;
00297
00299 diagnostic_updater::Updater updater_;
00301 diagnostic_updater::HeaderlessTopicDiagnostic status_freq_;
00303 double status_max_frequency_;
00305 double status_min_frequency_;
00307 boost::asio::io_service io_service_;
00309 AsyncClient comm_;
00310 };
00311
00312 }
00313
00314 #endif