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
00032 #include "gearbox.h"
00033
00034 namespace atlascar_base
00035 {
00036
00037 Gearbox::Gearbox(const ros::NodeHandle& nh)
00038 :nh_(nh),
00039 ip_("192.168.1.123"),
00040 port_(120),
00041 status_freq_("Gearbox",updater_,diagnostic_updater::FrequencyStatusParam(&status_max_frequency_,&status_min_frequency_, 0.1, 10)),
00042 status_max_frequency_(8.0),
00043 status_min_frequency_(12.0)
00044 {
00045 comm_=NULL;
00046 }
00047
00048 Gearbox::~Gearbox()
00049 {
00050 }
00051
00052 void Gearbox::init()
00053 {
00054 safety_command_.reset(new atlascar_base::GearboxCommand);
00055
00056
00057 safety_command_->lifetime=INFINITY;
00058 safety_command_->priority=0;
00059 safety_command_->gear=0;
00060
00061
00062 command_queue_.push_msg(safety_command_);
00063
00064
00065 updater_.setHardwareID("gearbox");
00066 updater_.add("Gearbox",this,&atlascar_base::Gearbox::diagnostics);
00067 }
00068
00069 void Gearbox::setupMessaging()
00070 {
00071 command_sub_ = nh_.subscribe("command", 1, &Gearbox::commandCallback, this);
00072 status_pub_ = nh_.advertise<atlascar_base::GearboxStatus>("status", 1);
00073 }
00074
00075 void Gearbox::loop()
00076 {
00077
00078 string received_message;
00079
00080 char send[1024];
00081
00082 ros::Rate r(10);
00083
00084 do
00085 {
00086 updater_.update();
00087
00088
00089 command_=command_queue_.top_msg();
00090
00091
00092 maintainConnection();
00093
00094
00095
00096
00097
00098 if (command_->gear<7 && connection_status_==ONLINE)
00099 {
00100 sprintf(send,"sg %d",command_->gear);
00101 comm_->Send(send,strlen(send)+1);
00102 comm_->perr("Failed to send");
00103 }
00104
00105
00106 if(receiveMessage(received_message)==0)
00107 {
00108 interpreterMessage(received_message);
00109 }
00110
00111
00112 status_.header.stamp = ros::Time::now();
00113 status_.header.frame_id = "";
00114 status_pub_.publish(status_);
00115 status_freq_.tick();
00116
00117
00118 ros::spinOnce();
00119 r.sleep();
00120 }while(ros::ok());
00121 }
00122
00123 void Gearbox::commandCallback(const atlascar_base::GearboxCommandPtr& command)
00124 {
00125 command_queue_.push_msg(command);
00126 }
00127
00128 int Gearbox::maintainConnection()
00129 {
00130 if(connection_status_==ONLINE)
00131 return 0;
00132
00133 if(comm_)
00134 {
00135
00136 comm_->Disconnect();
00137
00138 delete comm_;
00139 }
00140
00141 comm_=new tcp_client(ip_.c_str(),port_);
00142
00143 errno=0;
00144
00145 struct timeval timeout = {1,0};
00146 setsockopt(comm_->GetSocket(),SOL_SOCKET,SO_SNDTIMEO,&timeout, sizeof(timeout));
00147 setsockopt(comm_->GetSocket(),SOL_SOCKET,SO_RCVTIMEO,&timeout, sizeof(timeout));
00148
00149 comm_->Connect();
00150 if(comm_->err<0)
00151 {
00152 std::cout<<"Cannot connect to gearbox: "<<comm_->err_msg<<" "<<strerror(errno)<<std::endl;
00153 comm_->Disconnect();
00154 connection_status_=OFFLINE;
00155 return -1;
00156 }
00157
00158 std::cout<<"reconnection sucessfull."<<std::endl;
00159
00160 connection_status_=ONLINE;
00161
00162 return 0;
00163 }
00164
00165 int Gearbox::interpreterMessage(string& message)
00166 {
00167 char opcode[100];
00168 char code;
00169 int current_gear;
00170 int next_gear;
00171 sscanf(message.c_str(),"%*c %s",opcode);
00172 if (opcode[0]=='u')
00173 {
00174 status_.status="command unknown";
00175 return -1;
00176 }
00177 sscanf(message.c_str(),"%*c %*s %c",&code);
00178 switch (code)
00179 {
00180 case 'i':
00181 status_.status="command invalid";
00182 break;
00183 case 'm':
00184 status_.status="manual mode";
00185 break;
00186 case 'c':
00187 sscanf(message.c_str(),"%*c %*s %*c %d %*c %d",¤t_gear,&next_gear);
00188 status_.gear=current_gear;
00189 status_.status="changing to "+boost::lexical_cast<std::string>(next_gear);
00190
00191 break;
00192 case 'a':
00193 sscanf(message.c_str(),"%*c %*s %*c %d",¤t_gear);
00194 status_.gear=current_gear;
00195 status_.status="ok";
00196 break;
00197 default:
00198 status_.status="unrecognised status";
00199 break;
00200
00201 }
00202
00203
00204
00205 return 0;
00206 }
00207
00208
00209
00210
00211
00212 int Gearbox::receiveMessage(string& message)
00213 {
00214 char rec_buf[1024];
00215 char recv_msg[1024];
00216 memset(recv_msg,0,sizeof(recv_msg));
00217
00218 while(rec_buf[0]!=2)
00219 {
00220 if(comm_->Receive(rec_buf,1)!=0)
00221 {
00222 comm_->Disconnect();
00223 comm_->perr("Cannot read");
00224 }
00225
00226 if(comm_->err<0)
00227 return -1;
00228 }
00229
00230 int i=0;
00231 while(rec_buf[0]!=3)
00232 {
00233 if(comm_->Receive(rec_buf,1)!=0)
00234 {
00235 comm_->Disconnect();
00236 comm_->perr("Cannot read");
00237 }
00238
00239 if(comm_->err<0)
00240 return -1;
00241 recv_msg[i++]=rec_buf[0];
00242 }
00243
00244 recv_msg[i-1]='\0';
00245 message=recv_msg;
00246
00247 return 0;
00248 }
00249
00250 }