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 _GEARBOX_H_
00028 #define _GEARBOX_H_
00029 
00035 #include <ros/ros.h>
00036 #include <iostream>
00037 #include <boost/lexical_cast.hpp>
00038 #include <tcp_client/class_tcp.h>
00039 
00040 #include <atlascar_base/GearboxStatus.h>
00041 #include <atlascar_base/GearboxCommand.h>
00042 
00043 #include <topic_priority/topic_priority.h>
00044 
00045 #include <diagnostic_updater/diagnostic_updater.h>
00046 #include <diagnostic_updater/publisher.h>
00047 
00048 namespace atlascar_base
00049 {
00050 
00059 class Gearbox
00060 {
00061         public:
00081                 Gearbox(const ros::NodeHandle& nh);
00082                 
00086                 ~Gearbox();
00087                 
00094                 void init();
00095                 
00101                 void setupMessaging();
00102                 
00108                 void loop();
00112         private:
00113                 
00114                 void diagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
00115                 {
00116                         if(connection_status_==OFFLINE)
00117                         {
00118                                 stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No connection to hardware.");
00119                                 stat.add("Status","Check ethernet connection!");
00120                                 stat.add("Trying to connect to",ip_);
00121                         }else
00122                                 stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "No problems.");
00123                 }
00124                 
00131                 int maintainConnection();
00132                 
00139                 void commandCallback(const atlascar_base::GearboxCommandPtr& command);
00140                 
00141                 int receiveMessage(string& message);
00142                 
00143                 int interpreterMessage(string& message);
00144                 
00146                 enum {OFFLINE=0, ONLINE};
00147                 
00149                 ros::NodeHandle nh_;
00151                 ros::Subscriber command_sub_;
00153                 ros::Publisher status_pub_;
00155                 tcp_client* comm_;
00157                 TopicQueuePriority<atlascar_base::GearboxCommandPtr> command_queue_;
00159                 int connection_status_;
00161                 bool verbose_;
00163                 atlascar_base::GearboxCommandPtr command_;
00165                 atlascar_base::GearboxCommandPtr safety_command_;
00167                 atlascar_base::GearboxStatus status_;
00169                 std::string ip_;
00171                 int port_;
00172                 
00173                 
00174                 diagnostic_updater::Updater updater_;
00175                 diagnostic_updater::HeaderlessTopicDiagnostic status_freq_;
00176                 double status_max_frequency_;
00177                 double status_min_frequency_;
00178 };
00179 
00180 }
00181 
00182 #endif