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 _THROTTLE_H_
00028 #define _THROTTLE_H_
00029 
00035 #include <ros/ros.h>
00036 #include <iostream>
00037 #include <boost/lexical_cast.hpp>
00038 
00039 #include <tcp_client/AsyncClient.h>
00040 
00041 #include <diagnostic_updater/diagnostic_updater.h>
00042 #include <diagnostic_updater/publisher.h>
00043 
00044 #include <atlascar_base/ThrottleStatus.h>
00045 #include <atlascar_base/ThrottleCommand.h>
00046 
00047 #include <topic_priority/topic_priority.h>
00048 
00049 #include <boost/thread/thread.hpp>
00050 #include <boost/format.hpp>
00051 #include <boost/spirit/include/qi.hpp>
00052 #include <boost/spirit/include/phoenix_core.hpp>
00053 #include <boost/spirit/include/phoenix_operator.hpp>
00054 
00055 using namespace std;
00056 
00057 namespace atlascar_base
00058 {
00059 
00066 class Throttle
00067 {
00068         public:
00091                 Throttle(const ros::NodeHandle& nh,std::string ip,std::string port):
00092                 nh_(nh),
00093                 current_mode_(MANUAL),
00094                 server_ip_(ip),
00095                 server_port_(port),     status_freq_("Throttle",updater_,diagnostic_updater::FrequencyStatusParam(&status_min_frequency_,&status_max_frequency_, 0.01, 10)),
00096                 status_max_frequency_(51.0),
00097                 status_min_frequency_(49.0),
00098                 comm_(io_service_,server_ip_,server_port_)
00099                 {}
00100                 
00104                 ~Throttle()
00105                 {}
00106                 
00115                 void init()
00116                 {
00117                         safety_command_.reset(new atlascar_base::ThrottleCommand);
00118                         
00119                         
00120                         safety_command_->lifetime=INFINITY;
00121                         safety_command_->priority=0;
00122                         safety_command_->throttle=0;
00123                         safety_command_->mode=MANUAL;
00124                         
00125                         
00126                         command_queue_.push_msg(safety_command_);
00127                         
00128                         
00129                         updater_.setHardwareID("throttle");
00130                         updater_.add("Throttle",this,&atlascar_base::Throttle::diagnostics);
00131                         
00132                         
00133                         comm_.readHandler.connect(boost::bind(&Throttle::newData,this,_1));
00134                         
00135                         
00136                         comm_.connectHandler.connect(boost::bind(&Throttle::connectHandler,this));
00137                 }
00138                 
00146                 void setupMessaging()
00147                 {
00148                         command_sub_ = nh_.subscribe("command", 1, &Throttle::commandCallback, this);
00149                         status_pub_ = nh_.advertise<atlascar_base::ThrottleStatus>("status", 1);
00150                 }
00151                 
00161                 void loop()
00162                 {
00163                         
00164                         boost::thread thread(boost::bind(&boost::asio::io_service::run, &io_service_));
00165                         
00166                         ros::Rate r(50);
00167                         
00168                         do
00169                         {
00170                                 updater_.update();
00171                                 
00172                                 
00173                                 command_=command_queue_.top_msg();
00174                                                                 
00175                                 
00176                                 if(status_.mode!=(int)command_->mode)
00177                                 {
00178                                         boost::format fmt("set mode %d\n");
00179                                         fmt % command_->mode;
00180 
00181                                         try
00182                                         {
00183                                                 comm_.write(fmt.str());
00184                                         }catch(std::exception& e)
00185                                         {
00186                                                 std::cout<<"Cannot set mode: "<<e.what()<<std::endl;
00187                                         }
00188                                 }
00189                                 
00190                                 
00191                                 if(status_.mode==AUTO)
00192                                 {
00193                                         boost::format fmt("set throttle %lf\n");
00194                                         fmt % command_->throttle;
00195                                         
00196                                         try
00197                                         {
00198                                                 comm_.write(fmt.str());
00199                                         }catch(std::exception& e)
00200                                         {
00201                                                 std::cout<<"Cannot set throttle: "<<e.what()<<std::endl;
00202                                         }
00203                                 }
00204                                 
00205                                 if( comm_.isConnected() &&  (ros::Time::now()-status_.header.stamp).toSec() > 1.0)
00206                                 {
00207                                         comm_.reconnect();
00208                                 }
00209                                 
00210                                 
00211                                 ros::spinOnce();
00212                                 r.sleep();
00213                         }while(ros::ok());
00214                         
00215                         
00216                         io_service_.stop();
00217                         
00218                         thread.join();
00219                 }
00220 
00224         private:
00225 
00226                 enum {MANUAL=0,AUTO=1};
00227                 
00234                 void diagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
00235                 {
00236                         if(!comm_.isConnected())
00237                         {
00238                                 stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No connection to hardware.");
00239                                 stat.add("Status",comm_.error_.message());
00240                                 stat.add("Trying to connect to",server_ip_);
00241                                 stat.add("Port number",server_port_);
00242                         }else
00243                         {
00244                                 stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "No problems.");
00245                                 stat.add("Connected with",server_ip_);
00246                                 stat.add("Port number",server_port_);
00247                                 
00248                                 boost::format fmt("%.4f");
00249                                 fmt % (ros::Time::now()-status_.header.stamp).toSec();
00250                         
00251                                 stat.add("Last message received", fmt.str()+" seconds ago" );
00252                         }
00253                 }
00254                 
00260                 void connectHandler(void)
00261                 {
00262                         try
00263                         {
00264                                 comm_.write("start");
00265                         }catch(std::exception& e)
00266                         {
00267                                 std::cout << "Exception: " << e.what() << "\n";
00268                         }
00269                         
00270                         status_.header.stamp=ros::Time::now();
00271                 }
00272                 
00278                 void commandCallback(const atlascar_base::ThrottleCommandPtr& command)
00279                 {
00280                         command_queue_.push_msg(command);
00281                 }
00282                 
00290                 void newData(string data)
00291                 {
00292                         namespace qi = boost::spirit::qi;
00293                         using qi::double_;
00294                         using qi::int_;
00295                         using qi::ascii::space;
00296                         using boost::spirit::ascii::string;
00297                         using qi::_1;
00298                         using boost::phoenix::ref;
00299                         
00300                         
00301                         qi::phrase_parse(data.begin(),data.end(), 
00302                                                                                         string("mode") >> int_[ref(status_.mode) = _1] >>
00303                                                                                         string("throttle") >> double_[ref(status_.throttle) = _1] >>
00304                                                                                         string("pedal") >> double_[ref(status_.footPedal) = _1]
00305                                                                                         ,space);
00306                         
00307                         status_.header.stamp = ros::Time::now();
00308                         status_.header.frame_id = "";
00309                         status_pub_.publish(status_);
00310                         status_freq_.tick();
00311                 }
00312                 
00314                 ros::NodeHandle nh_;
00316                 ros::Subscriber command_sub_;
00318                 ros::Publisher status_pub_;
00320                 TopicQueuePriority<atlascar_base::ThrottleCommandPtr> command_queue_;
00322                 atlascar_base::ThrottleCommandPtr command_;
00324                 atlascar_base::ThrottleCommandPtr safety_command_;
00326                 atlascar_base::ThrottleStatus status_;
00328                 int current_mode_;
00329                 
00331                 std::string server_ip_;
00333                 std::string server_port_;
00334                         
00336                 diagnostic_updater::Updater updater_;
00338                 diagnostic_updater::HeaderlessTopicDiagnostic status_freq_;
00340                 double status_max_frequency_;
00342                 double status_min_frequency_;
00343                 
00345                 boost::asio::io_service io_service_;
00347                 AsyncClient comm_;
00348 };
00349 
00350 }
00351 
00352 #endif