plc.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
32 #include "plc.h"
33 
34 namespace atlascar_base
35 {
36 
37 Plc::Plc(const ros::NodeHandle& nh,std::string ip, std::string port)
38 :
39 server_ip_(ip),
40 server_port_(port),
41 nh_(nh),
42 status_freq_("Plc",updater_,diagnostic_updater::FrequencyStatusParam(&status_max_frequency_,&status_min_frequency_, 0.1, 10)),
43 status_max_frequency_(10.0),
44 status_min_frequency_(20.0),
45 comm_(io_service_,server_ip_,server_port_,std::string("\x03"))
46 {
47  verbose_=0;
48 }
49 
51 {}
52 
53 void Plc::init()
54 {
55  safety_command_.reset(new atlascar_base::PlcCommand);
56 
57  //Set the safety message default values, this messages will never be removed from the list
58  safety_command_->lifetime=INFINITY;
59  safety_command_->priority=0;
60  safety_command_->brake=0; //This will make the pedal go down
61  safety_command_->clutch=0; //This will make the pedal go down
62  safety_command_->steering_wheel=0;//center steering wheel
63 
64  //Push the safety message into the queue
66 
67  //Set diagnostics
68  updater_.setHardwareID("plc");
70 
71  //Setup the new data handler
72  comm_.readHandler.connect(boost::bind(&Plc::newData,this,_1));
73 
74  //Get the atlascar parameters
75  nh_.param("steering_wheel_from_plc_min",steering_wheel_calibration_.minimum_value_,-1.);
76  nh_.param("steering_wheel_from_plc_max",steering_wheel_calibration_.maximum_value_,-1.);
77 
78  nh_.param("steering_wheel_from_plc_rad_min",steering_wheel_calibration_.minimum_required_,-1.);
79  nh_.param("steering_wheel_from_plc_rad_max",steering_wheel_calibration_.maximum_required_,-1.);
80 
81  nh_.param("steering_wheel_to_plc_min",steering_wheel_to_plc_calibration_.minimum_required_,-1.);
82  nh_.param("steering_wheel_to_plc_max",steering_wheel_to_plc_calibration_.maximum_required_,-1.);
83 
84  nh_.param("steering_wheel_to_plc_rad_min",steering_wheel_to_plc_calibration_.minimum_value_,-1.);
85  nh_.param("steering_wheel_to_plc_rad_max",steering_wheel_to_plc_calibration_.maximum_value_,-1.);
86 
87  nh_.param("brake_plc_min",brake_calibration_.minimum_value_,-1.);
88  nh_.param("brake_plc_max",brake_calibration_.maximum_value_,-1.);
89 
92 
93  nh_.param("clutch_plc_min",clutch_calibration_.minimum_value_,-1.);
94  nh_.param("clutch_plc_max",clutch_calibration_.maximum_value_,-1.);
95 
98 }
99 
101 {
102  command_sub_ = nh_.subscribe("command", 1, &Plc::commandCallback, this);
103  status_pub_ = nh_.advertise<atlascar_base::PlcStatus>("status", 1);
104 }
105 
106 void Plc::loop()
107 {
108  //Run io service on a different tread
109  boost::thread thread(boost::bind(&boost::asio::io_service::run, &io_service_));
110 
111  ros::Rate r(15);//Hz
112 
113  do
114  {
115  updater_.update();
116 
117  //Get top layer message, the command message that has the most priority and is still valid
118  command_=command_queue_.top_msg();
119 
120  if(!command_)
121  {
122  cout<<"Error!! Invalid command in queue, safety message removed by user!!"<<endl;
123  }else
124  {
125  try
126  {
127  //Send the command message to the PLC
128  sendCommand();
129  }catch(std::exception& e)
130  {
131  std::cout << "Exception: " << e.what() << "\n";
132  }
133  }
134 
135  //Spin ros and sleep the desired amount
136  ros::spinOnce();
137  r.sleep();
138 
139  }while(ros::ok());
140 
141  //Stop the io service running in a separate thread
142  io_service_.stop();
143  //Join the thread
144  thread.join();
145 }
146 
147 void Plc::newData(string data)
148 {
149  std::size_t found=data.find("\x02");
150  data.erase(0,found+1);
151  data.erase(data.end()-1,data.end());
152 
153  double throttle;
154  double steering_wheel;
155  double brake;
156  double clutch;
157  double rpm;
158  double speed;
159  int handbrake;
160  int emergency;
161  int gear;
162  int error;
163 
164  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);
165 
166  status_.clutch=clutch_calibration_.remap(clutch);
167  status_.brake=brake_calibration_.remap(brake);
168  status_.steering_wheel=steering_wheel_calibration_.remap(steering_wheel);
169 
170  status_.rpm=rpm;
171  status_.ignition=command_->ignition;
172  status_.emergency=emergency;
173 
174  /*Get the rest of the stuff from the outgoing message*/
175  status_.lights_high=command_->lights_high;
176  status_.lights_medium=command_->lights_medium;
177  status_.lights_minimum=command_->lights_minimum;
178  status_.lights_left=command_->lights_left;
179  status_.lights_right=command_->lights_right;
180  status_.lights_brake=command_->lights_brake;
181  status_.lights_reverse=command_->lights_reverse;
182  status_.lights_warning=command_->lights_warning;
183 
184  status_.auto_ignition=command_->auto_ignition;
185  status_.auto_brake=command_->auto_brake;
186  status_.auto_direction=command_->auto_direction;
187  status_.auto_clutch=command_->auto_clutch;
188 
189  status_.header.stamp = ros::Time::now();
190  status_.header.frame_id = "";
191  status_pub_.publish(status_);
192  status_freq_.tick();
193 }
194 
196 {
197  char message_string[2000];
198  char text[2000];
199 
200  double steering_wheel = steering_wheel_to_plc_calibration_.remap(command_->steering_wheel);
201 
202  sprintf(message_string,"STTP %.4E ",0.0);
203 
204  sprintf(text,"SSWP %.4E ",steering_wheel);
205  strcat(message_string,text);
206 
207  sprintf(text,"SBKP %.4E ",command_->brake);
208  strcat(message_string,text);
209 
210  sprintf(text,"SCLP %.4E ",command_->clutch);
211  strcat(message_string,text);
212 
213  sprintf(text,"SHBP %10d ",0);
214  strcat(message_string,text);
215 
216  sprintf(text,"SGER %10d ",0);
217  strcat(message_string,text);
218 
219  sprintf(text,"SIGN %10d ",command_->ignition);
220  strcat(message_string,text);
221 
222  sprintf(text,"SVHS %.4E ",0.0);
223  strcat(message_string,text);
224 
225  sprintf(text,"SVBS %10d ",1);
226  strcat(message_string,text);
227 
228  sprintf(text,"SFAL %10d ",command_->lights_warning);
229  strcat(message_string,text);
230 
231  sprintf(text,"SHIL %10d ",command_->lights_high);
232  strcat(message_string,text);
233 
234  sprintf(text,"SHEL %10d ",command_->lights_medium);
235  strcat(message_string,text);
236 
237  sprintf(text,"SRTL %10d ",command_->lights_right);
238  strcat(message_string,text);
239 
240  sprintf(text,"SLTL %10d ",command_->lights_left);
241  strcat(message_string,text);
242 
243  sprintf(text,"STTA %10d ",0);
244  strcat(message_string,text);
245 
246  sprintf(text,"SSWA %10d ",command_->auto_direction);
247  strcat(message_string,text);
248 
249  sprintf(text,"SBKA %10d ",command_->auto_brake);
250  strcat(message_string,text);
251 
252  sprintf(text,"SCLA %10d ",command_->auto_clutch);
253  strcat(message_string,text);
254 
255  sprintf(text,"SHBA %10d ",0);
256  strcat(message_string,text);
257 
258  sprintf(text,"SGEA %10d ",0);
259  strcat(message_string,text);
260 
261  sprintf(text,"EEST %10d ",command_->emergency);
262  strcat(message_string,text);
263 
264  sprintf(text,"SIGA %10d ",command_->auto_ignition);
265  strcat(message_string,text);
266 
267  sendMessage(message_string);
268 
269  return 0;
270 }
271 
272 int Plc::sendMessage(char*message_string)
273 {
274  char formatted_message[2000];
275 
276  memset(formatted_message,0,sizeof(formatted_message));
277  sprintf(formatted_message,"%c%s%c",2,message_string,3);
278 
279  std::string msg = std::string(formatted_message);
280  if(verbose_)std::cout<<">> "<<msg<<std::endl;
281  comm_.write(std::string(formatted_message));
282 
283  return 0;
284 }
285 
286 void Plc::commandCallback(const atlascar_base::PlcCommandPtr& command)
287 {
288  command_queue_.push_msg(command);
289 }
290 
291 }
TopicQueuePriority< atlascar_base::PlcCommandPtr > command_queue_
Command queue holding class.
Definition: plc.h:275
boost::asio::io_service io_service_
Input/Output communication service.
Definition: plc.h:299
atlascar_base::PlcStatus status_
Status message.
Definition: plc.h:287
void commandCallback(const atlascar_base::PlcCommandPtr &command)
Command message handler.
Definition: plc.cpp:286
bool verbose_
Verbose mode.
Definition: plc.h:279
void setupMessaging()
Start ros message subscribing and advertising.
Definition: plc.cpp:100
diagnostic_updater::Updater updater_
Diagnostics class.
Definition: plc.h:290
~Plc()
Class destructor.
Definition: plc.cpp:50
void newData(string data)
This function will be called (asynchronously) upon arrival of new data.
Definition: plc.cpp:147
SimpleCalibration brake_calibration_
Calibration of the brake pedal.
Definition: plc.h:259
AsyncClient comm_
Asynchronous tcp/ip communication object.
Definition: plc.h:301
void loop()
Start main control loop.
Definition: plc.cpp:106
ros::Publisher status_pub_
Ros status publisher.
Definition: plc.h:273
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Diagnostics function handler.
Definition: plc.h:194
int sendMessage(char *message_string)
Send a message.
Definition: plc.cpp:272
SimpleCalibration steering_wheel_to_plc_calibration_
Calibration of the steering wheel to the plc.
Definition: plc.h:256
SimpleCalibration clutch_calibration_
Calibration of the clutch pedal.
Definition: plc.h:261
SimpleCalibration steering_wheel_calibration_
Calibration of the steering wheel from the plc.
Definition: plc.h:254
Plc(const ros::NodeHandle &nh, std::string ip, std::string port)
Class constructor.
Definition: plc.cpp:37
atlascar_base::PlcCommandPtr command_
Command message pointer.
Definition: plc.h:283
atlascar_base::PlcCommandPtr safety_command_
Safety command message pointer.
Definition: plc.h:285
Plc class declaration.
double remap(double value)
Linear mapping function.
Definition: plc.h:78
diagnostic_updater::HeaderlessTopicDiagnostic status_freq_
Frequency diagnostics tool.
Definition: plc.h:292
ros::NodeHandle nh_
Ros node handler.
Definition: plc.h:269
ros::Subscriber command_sub_
Ros command subscriber.
Definition: plc.h:271
int sendCommand(void)
Send a global command down to the plc.
Definition: plc.cpp:195
void init()
Initialize the class.
Definition: plc.cpp:53


atlascar_base
Author(s): Jorge Almeida, Sérgio Pinho, Miguel Oliveira, Pedro Salvado, Andre Oliveira and Pedro Pinheiro
autogenerated on Mon Mar 2 2015 01:31:23