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 "plc.h"
00033
00034 namespace atlascar_base
00035 {
00036
00037 Plc::Plc(const ros::NodeHandle& nh,std::string ip, std::string port)
00038 :
00039 server_ip_(ip),
00040 server_port_(port),
00041 nh_(nh),
00042 status_freq_("Plc",updater_,diagnostic_updater::FrequencyStatusParam(&status_max_frequency_,&status_min_frequency_, 0.1, 10)),
00043 status_max_frequency_(10.0),
00044 status_min_frequency_(20.0),
00045 comm_(io_service_,server_ip_,server_port_,std::string("\x03"))
00046 {
00047 verbose_=0;
00048 }
00049
00050 Plc::~Plc()
00051 {}
00052
00053 void Plc::init()
00054 {
00055 safety_command_.reset(new atlascar_base::PlcCommand);
00056
00057
00058 safety_command_->lifetime=INFINITY;
00059 safety_command_->priority=0;
00060 safety_command_->brake=0;
00061 safety_command_->clutch=0;
00062 safety_command_->steering_wheel=0;
00063
00064
00065 command_queue_.push_msg(safety_command_);
00066
00067
00068 updater_.setHardwareID("plc");
00069 updater_.add("Plc",this,&atlascar_base::Plc::diagnostics);
00070
00071
00072 comm_.readHandler.connect(boost::bind(&Plc::newData,this,_1));
00073
00074
00075 nh_.param("steering_wheel_from_plc_min",steering_wheel_calibration_.minimum_value_,-1.);
00076 nh_.param("steering_wheel_from_plc_max",steering_wheel_calibration_.maximum_value_,-1.);
00077
00078 nh_.param("steering_wheel_from_plc_rad_min",steering_wheel_calibration_.minimum_required_,-1.);
00079 nh_.param("steering_wheel_from_plc_rad_max",steering_wheel_calibration_.maximum_required_,-1.);
00080
00081 nh_.param("steering_wheel_to_plc_min",steering_wheel_to_plc_calibration_.minimum_required_,-1.);
00082 nh_.param("steering_wheel_to_plc_max",steering_wheel_to_plc_calibration_.maximum_required_,-1.);
00083
00084 nh_.param("steering_wheel_to_plc_rad_min",steering_wheel_to_plc_calibration_.minimum_value_,-1.);
00085 nh_.param("steering_wheel_to_plc_rad_max",steering_wheel_to_plc_calibration_.maximum_value_,-1.);
00086
00087 nh_.param("brake_plc_min",brake_calibration_.minimum_value_,-1.);
00088 nh_.param("brake_plc_max",brake_calibration_.maximum_value_,-1.);
00089
00090 brake_calibration_.minimum_required_=0;
00091 brake_calibration_.maximum_required_=1;
00092
00093 nh_.param("clutch_plc_min",clutch_calibration_.minimum_value_,-1.);
00094 nh_.param("clutch_plc_max",clutch_calibration_.maximum_value_,-1.);
00095
00096 clutch_calibration_.minimum_required_=0;
00097 clutch_calibration_.maximum_required_=1;
00098 }
00099
00100 void Plc::setupMessaging()
00101 {
00102 command_sub_ = nh_.subscribe("command", 1, &Plc::commandCallback, this);
00103 status_pub_ = nh_.advertise<atlascar_base::PlcStatus>("status", 1);
00104 }
00105
00106 void Plc::loop()
00107 {
00108
00109 boost::thread thread(boost::bind(&boost::asio::io_service::run, &io_service_));
00110
00111 ros::Rate r(15);
00112
00113 do
00114 {
00115 updater_.update();
00116
00117
00118 command_=command_queue_.top_msg();
00119
00120 try
00121 {
00122
00123 sendCommand();
00124 }catch(std::exception& e)
00125 {
00126 std::cout << "Exception: " << e.what() << "\n";
00127 }
00128
00129
00130 ros::spinOnce();
00131 r.sleep();
00132
00133 }while(ros::ok());
00134
00135
00136 io_service_.stop();
00137
00138 thread.join();
00139 }
00140
00141 void Plc::newData(string data)
00142 {
00143 std::size_t found=data.find("\x02");
00144 data.erase(0,found+1);
00145 data.erase(data.end()-1,data.end());
00146
00147 double throttle;
00148 double steering_wheel;
00149 double brake;
00150 double clutch;
00151 double rpm;
00152 double speed;
00153 int handbrake;
00154 int emergency;
00155 int gear;
00156 int error;
00157
00158 sscanf(data.c_str(),"%*s %lf %*s %lf %*s %lf %*s %lf %*s %d %*s %d %*s %lf %*s %lf %*s %d %*s %d",&throttle,&steering_wheel,&brake,&clutch,&handbrake,&gear,&speed,&rpm,&emergency,&error);
00159
00160 status_.clutch=clutch_calibration_.remap(clutch);
00161 status_.brake=brake_calibration_.remap(brake);
00162 status_.steering_wheel=steering_wheel_calibration_.remap(steering_wheel);
00163
00164 status_.rpm=rpm;
00165 status_.ignition=command_->ignition;
00166 status_.emergency=emergency;
00167
00168
00169 status_.lights_high=command_->lights_high;
00170 status_.lights_medium=command_->lights_medium;
00171 status_.lights_minimum=command_->lights_minimum;
00172 status_.lights_left=command_->lights_left;
00173 status_.lights_right=command_->lights_right;
00174 status_.lights_brake=command_->lights_brake;
00175 status_.lights_reverse=command_->lights_reverse;
00176 status_.lights_warning=command_->lights_warning;
00177
00178 status_.auto_ignition=command_->auto_ignition;
00179 status_.auto_brake=command_->auto_brake;
00180 status_.auto_direction=command_->auto_direction;
00181 status_.auto_clutch=command_->auto_clutch;
00182
00183 status_.header.stamp = ros::Time::now();
00184 status_.header.frame_id = "";
00185 status_pub_.publish(status_);
00186 status_freq_.tick();
00187 }
00188
00189 int Plc::sendCommand(void)
00190 {
00191 char message_string[2000];
00192 char text[2000];
00193
00194 double steering_wheel = steering_wheel_to_plc_calibration_.remap(command_->steering_wheel);
00195
00196 sprintf(message_string,"STTP %.4E ",0.0);
00197
00198 sprintf(text,"SSWP %.4E ",steering_wheel);
00199 strcat(message_string,text);
00200
00201 sprintf(text,"SBKP %.4E ",command_->brake);
00202 strcat(message_string,text);
00203
00204 sprintf(text,"SCLP %.4E ",command_->clutch);
00205 strcat(message_string,text);
00206
00207 sprintf(text,"SHBP %10d ",0);
00208 strcat(message_string,text);
00209
00210 sprintf(text,"SGER %10d ",0);
00211 strcat(message_string,text);
00212
00213 sprintf(text,"SIGN %10d ",command_->ignition);
00214 strcat(message_string,text);
00215
00216 sprintf(text,"SVHS %.4E ",0.0);
00217 strcat(message_string,text);
00218
00219 sprintf(text,"SVBS %10d ",1);
00220 strcat(message_string,text);
00221
00222 sprintf(text,"SFAL %10d ",command_->lights_warning);
00223 strcat(message_string,text);
00224
00225 sprintf(text,"SHIL %10d ",command_->lights_high);
00226 strcat(message_string,text);
00227
00228 sprintf(text,"SHEL %10d ",command_->lights_medium);
00229 strcat(message_string,text);
00230
00231 sprintf(text,"SRTL %10d ",command_->lights_right);
00232 strcat(message_string,text);
00233
00234 sprintf(text,"SLTL %10d ",command_->lights_left);
00235 strcat(message_string,text);
00236
00237 sprintf(text,"STTA %10d ",0);
00238 strcat(message_string,text);
00239
00240 sprintf(text,"SSWA %10d ",command_->auto_direction);
00241 strcat(message_string,text);
00242
00243 sprintf(text,"SBKA %10d ",command_->auto_brake);
00244 strcat(message_string,text);
00245
00246 sprintf(text,"SCLA %10d ",command_->auto_clutch);
00247 strcat(message_string,text);
00248
00249 sprintf(text,"SHBA %10d ",0);
00250 strcat(message_string,text);
00251
00252 sprintf(text,"SGEA %10d ",0);
00253 strcat(message_string,text);
00254
00255 sprintf(text,"EEST %10d ",command_->emergency);
00256 strcat(message_string,text);
00257
00258 sprintf(text,"SIGA %10d ",command_->auto_ignition);
00259 strcat(message_string,text);
00260
00261 sendMessage(message_string);
00262
00263 return 0;
00264 }
00265
00266 int Plc::sendMessage(char*message_string)
00267 {
00268 char formatted_message[2000];
00269
00270 memset(formatted_message,0,sizeof(formatted_message));
00271 sprintf(formatted_message,"%c%s%c",2,message_string,3);
00272
00273 std::string msg = std::string(formatted_message);
00274 if(verbose_)std::cout<<">> "<<msg<<std::endl;
00275 comm_.write(std::string(formatted_message));
00276
00277 return 0;
00278 }
00279
00280 void Plc::commandCallback(const atlascar_base::PlcCommandPtr& command)
00281 {
00282 command_queue_.push_msg(command);
00283 }
00284
00285 }