pacmod_ros_msg_handler.cpp
Go to the documentation of this file.
1 // Copyright (c) 2019 AutonomouStuff, LLC
2 //
3 // Permission is hereby granted, free of charge, to any person obtaining a copy
4 // of this software and associated documentation files (the "Software"), to deal
5 // in the Software without restriction, including without limitation the rights
6 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
7 // copies of the Software, and to permit persons to whom the Software is
8 // furnished to do so, subject to the following conditions:
9 //
10 // The above copyright notice and this permission notice shall be included in
11 // all copies or substantial portions of the Software.
12 //
13 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
14 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
15 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
16 // THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
17 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
18 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
19 // THE SOFTWARE.
20 
22 
23 #include <string>
24 #include <vector>
25 #include <memory>
26 
27 namespace AS
28 {
29 namespace Drivers
30 {
31 namespace PACMod
32 {
33 
35  _data(),
36  _data_mut(),
37  _is_valid(false),
38  _valid_mut()
39 {
40 }
41 
42 bool LockedData::isValid() const
43 {
44  std::lock_guard<std::mutex> lck(_valid_mut);
45  return _is_valid;
46 }
47 
48 void LockedData::setIsValid(bool valid)
49 {
50  std::lock_guard<std::mutex> lck(_valid_mut);
51  _is_valid = valid;
52 }
53 
54 std::vector<unsigned char> LockedData::getData() const
55 {
56  std::lock_guard<std::mutex> lck(_data_mut);
57  return _data;
58 }
59 
60 void LockedData::setData(std::vector<unsigned char> new_data)
61 {
62  std::lock_guard<std::mutex> lck(_data_mut);
63  _data = new_data;
64 }
65 
66 void PacmodTxRosMsgHandler::fillAndPublish(const int64_t& can_id,
67  std::string frame_id,
68  const ros::Publisher& pub,
69  const std::shared_ptr<PacmodTxMsg>& parser_class)
70 {
71  if (can_id == TurnSignalRptMsg::CAN_ID ||
72  can_id == ShiftRptMsg::CAN_ID ||
73  can_id == HeadlightRptMsg::CAN_ID ||
74  can_id == HornRptMsg::CAN_ID ||
75  can_id == WiperRptMsg::CAN_ID)
76  {
77  pacmod_msgs::SystemRptInt new_msg;
78  fillSystemRptInt(parser_class, &new_msg, frame_id);
79  pub.publish(new_msg);
80  }
81  else if (can_id == AccelRptMsg::CAN_ID ||
82  can_id == BrakeRptMsg::CAN_ID ||
83  can_id == SteerRptMsg::CAN_ID ||
84  can_id == SteerRpt2Msg::CAN_ID ||
85  can_id == SteerRpt3Msg::CAN_ID)
86  {
87  pacmod_msgs::SystemRptFloat new_msg;
88  fillSystemRptFloat(parser_class, &new_msg, frame_id);
89  pub.publish(new_msg);
90  }
91  else if (can_id == GlobalRptMsg::CAN_ID)
92  {
93  pacmod_msgs::GlobalRpt new_msg;
94  fillGlobalRpt(parser_class, &new_msg, frame_id);
95  pub.publish(new_msg);
96  }
97  else if (can_id == VehicleSpeedRptMsg::CAN_ID)
98  {
99  pacmod_msgs::VehicleSpeedRpt new_msg;
100  fillVehicleSpeedRpt(parser_class, &new_msg, frame_id);
101  pub.publish(new_msg);
102  }
103  else if (can_id == BrakeMotorRpt1Msg::CAN_ID ||
104  can_id == SteerMotorRpt1Msg::CAN_ID)
105  {
106  pacmod_msgs::MotorRpt1 new_msg;
107  fillMotorRpt1(parser_class, &new_msg, frame_id);
108  pub.publish(new_msg);
109  }
110  else if (can_id == BrakeMotorRpt2Msg::CAN_ID ||
111  can_id == SteerMotorRpt2Msg::CAN_ID)
112  {
113  pacmod_msgs::MotorRpt2 new_msg;
114  fillMotorRpt2(parser_class, &new_msg, frame_id);
115  pub.publish(new_msg);
116  }
117  else if (can_id == BrakeMotorRpt3Msg::CAN_ID ||
118  can_id == SteerMotorRpt3Msg::CAN_ID)
119  {
120  pacmod_msgs::MotorRpt3 new_msg;
121  fillMotorRpt3(parser_class, &new_msg, frame_id);
122  pub.publish(new_msg);
123  }
124  else if (can_id == WheelSpeedRptMsg::CAN_ID)
125  {
126  pacmod_msgs::WheelSpeedRpt new_msg;
127  fillWheelSpeedRpt(parser_class, &new_msg, frame_id);
128  pub.publish(new_msg);
129  }
130  else if (can_id == SteeringPIDRpt1Msg::CAN_ID)
131  {
132  pacmod_msgs::SteeringPIDRpt1 new_msg;
133  fillSteeringPIDRpt1(parser_class, &new_msg, frame_id);
134  pub.publish(new_msg);
135  }
136  else if (can_id == SteeringPIDRpt2Msg::CAN_ID)
137  {
138  pacmod_msgs::SteeringPIDRpt2 new_msg;
139  fillSteeringPIDRpt2(parser_class, &new_msg, frame_id);
140  pub.publish(new_msg);
141  }
142  else if (can_id == SteeringPIDRpt3Msg::CAN_ID)
143  {
144  pacmod_msgs::SteeringPIDRpt3 new_msg;
145  fillSteeringPIDRpt3(parser_class, &new_msg, frame_id);
146  pub.publish(new_msg);
147  }
148  else if (can_id == ParkingBrakeStatusRptMsg::CAN_ID)
149  {
150  pacmod_msgs::ParkingBrakeStatusRpt new_msg;
151  fillParkingBrakeStatusRpt(parser_class, &new_msg, frame_id);
152  pub.publish(new_msg);
153  }
154  else if (can_id == YawRateRptMsg::CAN_ID)
155  {
156  pacmod_msgs::YawRateRpt new_msg;
157  fillYawRateRpt(parser_class, &new_msg, frame_id);
158  pub.publish(new_msg);
159  }
160  else if (can_id == LatLonHeadingRptMsg::CAN_ID)
161  {
162  pacmod_msgs::LatLonHeadingRpt new_msg;
163  fillLatLonHeadingRpt(parser_class, &new_msg, frame_id);
164  pub.publish(new_msg);
165  }
166  else if (can_id == DateTimeRptMsg::CAN_ID)
167  {
168  pacmod_msgs::DateTimeRpt new_msg;
169  fillDateTimeRpt(parser_class, &new_msg, frame_id);
170  pub.publish(new_msg);
171  }
172  else if (can_id == SteeringPIDRpt4Msg::CAN_ID)
173  {
174  pacmod_msgs::SteeringPIDRpt4 new_msg;
175  fillSteeringPIDRpt4(parser_class, &new_msg, frame_id);
176  pub.publish(new_msg);
177  }
178  else if (can_id == VinRptMsg::CAN_ID)
179  {
180  pacmod_msgs::VinRpt new_msg;
181  fillVinRpt(parser_class, &new_msg, frame_id);
182  pub.publish(new_msg);
183  }
184 }
185 
186 void PacmodTxRosMsgHandler::fillSystemRptInt(const std::shared_ptr<PacmodTxMsg>& parser_class,
187  pacmod_msgs::SystemRptInt* new_msg,
188  std::string frame_id)
189 {
190  auto dc_parser = std::dynamic_pointer_cast<SystemRptIntMsg>(parser_class);
191 
192  new_msg->manual_input = dc_parser->manual_input;
193  new_msg->command = dc_parser->command;
194  new_msg->output = dc_parser->output;
195 
196  new_msg->header.frame_id = frame_id;
197  new_msg->header.stamp = ros::Time::now();
198 }
199 
200 void PacmodTxRosMsgHandler::fillSystemRptFloat(const std::shared_ptr<PacmodTxMsg>& parser_class,
201  pacmod_msgs::SystemRptFloat* new_msg,
202  std::string frame_id)
203 {
204  auto dc_parser = std::dynamic_pointer_cast<SystemRptFloatMsg>(parser_class);
205 
206  new_msg->manual_input = dc_parser->manual_input;
207  new_msg->command = dc_parser->command;
208  new_msg->output = dc_parser->output;
209 
210  new_msg->header.frame_id = frame_id;
211  new_msg->header.stamp = ros::Time::now();
212 }
213 
214 void PacmodTxRosMsgHandler::fillGlobalRpt(const std::shared_ptr<PacmodTxMsg>& parser_class,
215  pacmod_msgs::GlobalRpt* new_msg,
216  std::string frame_id)
217 {
218  auto dc_parser = std::dynamic_pointer_cast<GlobalRptMsg>(parser_class);
219 
220  new_msg->enabled = dc_parser->enabled;
221  new_msg->override_active = dc_parser->override_active;
222  new_msg->user_can_timeout = dc_parser->user_can_timeout;
223  new_msg->brake_can_timeout = dc_parser->brake_can_timeout;
224  new_msg->steering_can_timeout = dc_parser->steering_can_timeout;
225  new_msg->vehicle_can_timeout = dc_parser->vehicle_can_timeout;
226  new_msg->user_can_read_errors = dc_parser->user_can_read_errors;
227 
228  new_msg->header.frame_id = frame_id;
229  new_msg->header.stamp = ros::Time::now();
230 }
231 
232 void PacmodTxRosMsgHandler::fillVehicleSpeedRpt(const std::shared_ptr<PacmodTxMsg>& parser_class,
233  pacmod_msgs::VehicleSpeedRpt* new_msg,
234  std::string frame_id)
235 {
236  auto dc_parser = std::dynamic_pointer_cast<VehicleSpeedRptMsg>(parser_class);
237 
238  new_msg->vehicle_speed = dc_parser->vehicle_speed;
239  new_msg->vehicle_speed_valid = dc_parser->vehicle_speed_valid;
240  new_msg->vehicle_speed_raw[0] = dc_parser->vehicle_speed_raw[0];
241  new_msg->vehicle_speed_raw[1] = dc_parser->vehicle_speed_raw[1];
242 
243  new_msg->header.frame_id = frame_id;
244  new_msg->header.stamp = ros::Time::now();
245 }
246 
247 void PacmodTxRosMsgHandler::fillMotorRpt1(const std::shared_ptr<PacmodTxMsg>& parser_class,
248  pacmod_msgs::MotorRpt1* new_msg,
249  std::string frame_id)
250 {
251  auto dc_parser = std::dynamic_pointer_cast<MotorRpt1Msg>(parser_class);
252 
253  new_msg->current = dc_parser->current;
254  new_msg->position = dc_parser->position;
255 
256  new_msg->header.frame_id = frame_id;
257  new_msg->header.stamp = ros::Time::now();
258 }
259 
260 void PacmodTxRosMsgHandler::fillMotorRpt2(const std::shared_ptr<PacmodTxMsg>& parser_class,
261  pacmod_msgs::MotorRpt2* new_msg,
262  std::string frame_id)
263 {
264  auto dc_parser = std::dynamic_pointer_cast<MotorRpt2Msg>(parser_class);
265 
266  new_msg->encoder_temp = dc_parser->encoder_temp;
267  new_msg->motor_temp = dc_parser->motor_temp;
268  new_msg->angular_velocity = dc_parser->velocity;
269 
270  new_msg->header.frame_id = frame_id;
271  new_msg->header.stamp = ros::Time::now();
272 }
273 
274 void PacmodTxRosMsgHandler::fillMotorRpt3(const std::shared_ptr<PacmodTxMsg>& parser_class,
275  pacmod_msgs::MotorRpt3* new_msg,
276  std::string frame_id)
277 {
278  auto dc_parser = std::dynamic_pointer_cast<MotorRpt3Msg>(parser_class);
279 
280  new_msg->torque_output = dc_parser->torque_output;
281  new_msg->torque_input = dc_parser->torque_input;
282 
283  new_msg->header.frame_id = frame_id;
284  new_msg->header.stamp = ros::Time::now();
285 }
286 
287 void PacmodTxRosMsgHandler::fillWheelSpeedRpt(const std::shared_ptr<PacmodTxMsg>& parser_class,
288  pacmod_msgs::WheelSpeedRpt* new_msg,
289  std::string frame_id)
290 {
291  auto dc_parser = std::dynamic_pointer_cast<WheelSpeedRptMsg>(parser_class);
292 
293  new_msg->front_left_wheel_speed = dc_parser->front_left_wheel_speed;
294  new_msg->front_right_wheel_speed = dc_parser->front_right_wheel_speed;
295  new_msg->rear_left_wheel_speed = dc_parser->rear_left_wheel_speed;
296  new_msg->rear_right_wheel_speed = dc_parser->rear_right_wheel_speed;
297 
298  new_msg->header.frame_id = frame_id;
299  new_msg->header.stamp = ros::Time::now();
300 }
301 
302 void PacmodTxRosMsgHandler::fillSteeringPIDRpt1(const std::shared_ptr<PacmodTxMsg>& parser_class,
303  pacmod_msgs::SteeringPIDRpt1* new_msg,
304  std::string frame_id)
305 {
306  auto dc_parser = std::dynamic_pointer_cast<SteeringPIDRpt1Msg>(parser_class);
307 
308  new_msg->dt = dc_parser->dt;
309  new_msg->kp = dc_parser->kp;
310  new_msg->ki = dc_parser->ki;
311  new_msg->kd = dc_parser->kd;
312 
313  new_msg->header.frame_id = frame_id;
314  new_msg->header.stamp = ros::Time::now();
315 }
316 
317 void PacmodTxRosMsgHandler::fillSteeringPIDRpt2(const std::shared_ptr<PacmodTxMsg>& parser_class,
318  pacmod_msgs::SteeringPIDRpt2* new_msg,
319  std::string frame_id)
320 {
321  auto dc_parser = std::dynamic_pointer_cast<SteeringPIDRpt2Msg>(parser_class);
322 
323  new_msg->p_term = dc_parser->p_term;
324  new_msg->i_term = dc_parser->i_term;
325  new_msg->d_term = dc_parser->d_term;
326  new_msg->all_terms = dc_parser->all_terms;
327 
328  new_msg->header.frame_id = frame_id;
329  new_msg->header.stamp = ros::Time::now();
330 }
331 
332 void PacmodTxRosMsgHandler::fillSteeringPIDRpt3(const std::shared_ptr<PacmodTxMsg>& parser_class,
333  pacmod_msgs::SteeringPIDRpt3* new_msg,
334  std::string frame_id)
335 {
336  auto dc_parser = std::dynamic_pointer_cast<SteeringPIDRpt3Msg>(parser_class);
337 
338  new_msg->new_torque = dc_parser->new_torque;
339  new_msg->str_angle_desired = dc_parser->str_angle_desired;
340  new_msg->str_angle_actual = dc_parser->str_angle_actual;
341  new_msg->error = dc_parser->error;
342 
343  new_msg->header.frame_id = frame_id;
344  new_msg->header.stamp = ros::Time::now();
345 }
346 
347 void PacmodTxRosMsgHandler::fillParkingBrakeStatusRpt(const std::shared_ptr<PacmodTxMsg>& parser_class,
348  pacmod_msgs::ParkingBrakeStatusRpt* new_msg,
349  std::string frame_id)
350 {
351  auto dc_parser = std::dynamic_pointer_cast<ParkingBrakeStatusRptMsg>(parser_class);
352 
353  new_msg->parking_brake_engaged = dc_parser->parking_brake_engaged;
354 
355  new_msg->header.frame_id = frame_id;
356  new_msg->header.stamp = ros::Time::now();
357 }
358 
359 void PacmodTxRosMsgHandler::fillYawRateRpt(const std::shared_ptr<PacmodTxMsg>& parser_class,
360  pacmod_msgs::YawRateRpt* new_msg,
361  std::string frame_id)
362 {
363  auto dc_parser = std::dynamic_pointer_cast<YawRateRptMsg>(parser_class);
364 
365  new_msg->yaw_rate = dc_parser->yaw_rate;
366 
367  new_msg->header.frame_id = frame_id;
368  new_msg->header.stamp = ros::Time::now();
369 }
370 
371 void PacmodTxRosMsgHandler::fillLatLonHeadingRpt(const std::shared_ptr<PacmodTxMsg>& parser_class,
372  pacmod_msgs::LatLonHeadingRpt* new_msg,
373  std::string frame_id)
374 {
375  auto dc_parser = std::dynamic_pointer_cast<LatLonHeadingRptMsg>(parser_class);
376 
377  new_msg->latitude_degrees = dc_parser->latitude_degrees;
378  new_msg->latitude_minutes = dc_parser->latitude_minutes;
379  new_msg->latitude_seconds = dc_parser->latitude_seconds;
380  new_msg->longitude_degrees = dc_parser->longitude_degrees;
381  new_msg->longitude_minutes = dc_parser->longitude_minutes;
382  new_msg->longitude_seconds = dc_parser->longitude_seconds;
383  new_msg->heading = dc_parser->heading;
384 
385  new_msg->header.frame_id = frame_id;
386  new_msg->header.stamp = ros::Time::now();
387 }
388 
389 void PacmodTxRosMsgHandler::fillDateTimeRpt(const std::shared_ptr<PacmodTxMsg>& parser_class,
390  pacmod_msgs::DateTimeRpt* new_msg,
391  std::string frame_id)
392 {
393  auto dc_parser = std::dynamic_pointer_cast<DateTimeRptMsg>(parser_class);
394 
395  new_msg->year = dc_parser->year;
396  new_msg->month = dc_parser->month;
397  new_msg->day = dc_parser->day;
398  new_msg->hour = dc_parser->hour;
399  new_msg->minute = dc_parser->minute;
400  new_msg->second = dc_parser->second;
401 
402  new_msg->header.frame_id = frame_id;
403  new_msg->header.stamp = ros::Time::now();
404 }
405 
406 void PacmodTxRosMsgHandler::fillSteeringPIDRpt4(const std::shared_ptr<PacmodTxMsg>& parser_class,
407  pacmod_msgs::SteeringPIDRpt4* new_msg,
408  std::string frame_id)
409 {
410  auto dc_parser = std::dynamic_pointer_cast<SteeringPIDRpt4Msg>(parser_class);
411 
412  new_msg->angular_velocity = dc_parser->angular_velocity;
413  new_msg->angular_acceleration = dc_parser->angular_acceleration;
414 
415  new_msg->header.frame_id = frame_id;
416  new_msg->header.stamp = ros::Time::now();
417 }
418 
419 void PacmodTxRosMsgHandler::fillVinRpt(const std::shared_ptr<PacmodTxMsg>& parser_class,
420  pacmod_msgs::VinRpt* new_msg,
421  std::string frame_id)
422 {
423  auto dc_parser = std::dynamic_pointer_cast<VinRptMsg>(parser_class);
424 
425  new_msg->mfg_code = dc_parser->mfg_code;
426  new_msg->mfg = dc_parser->mfg;
427  new_msg->model_year_code = dc_parser->model_year_code;
428  new_msg->model_year = dc_parser->model_year;
429  new_msg->serial = dc_parser->serial;
430 
431  new_msg->header.frame_id = frame_id;
432  new_msg->header.stamp = ros::Time::now();
433 }
434 
435 std::vector<uint8_t> PacmodRxRosMsgHandler::unpackAndEncode(const int64_t& can_id,
436  const pacmod_msgs::PacmodCmd::ConstPtr& msg)
437 {
438  if (can_id == TurnSignalCmdMsg::CAN_ID)
439  {
440  TurnSignalCmdMsg encoder;
441  encoder.encode(msg->ui16_cmd);
442  return encoder.data;
443  }
444  else if (can_id == ShiftCmdMsg::CAN_ID)
445  {
446  ShiftCmdMsg encoder;
447  encoder.encode(msg->ui16_cmd);
448  return encoder.data;
449  }
450  else if (can_id == AccelCmdMsg::CAN_ID)
451  {
452  AccelCmdMsg encoder;
453  encoder.encode(msg->f64_cmd);
454  return encoder.data;
455  }
456  else if (can_id == GlobalCmdMsg::CAN_ID)
457  {
458  GlobalCmdMsg encoder;
459  encoder.encode(msg->enable, msg->clear, msg->ignore);
460  return encoder.data;
461  }
462  else if (can_id == BrakeCmdMsg::CAN_ID)
463  {
464  BrakeCmdMsg encoder;
465  encoder.encode(msg->f64_cmd);
466  return encoder.data;
467  }
468  else if (can_id == HeadlightCmdMsg::CAN_ID)
469  {
470  HeadlightCmdMsg encoder;
471  encoder.encode(msg->ui16_cmd);
472  return encoder.data;
473  }
474  else if (can_id == HornCmdMsg::CAN_ID)
475  {
476  HornCmdMsg encoder;
477  encoder.encode(msg->ui16_cmd);
478  return encoder.data;
479  }
480  else if (can_id == WiperCmdMsg::CAN_ID)
481  {
482  WiperCmdMsg encoder;
483  encoder.encode(msg->ui16_cmd);
484  return encoder.data;
485  }
486 }
487 
488 std::vector<uint8_t> PacmodRxRosMsgHandler::unpackAndEncode(const int64_t& can_id,
489  const pacmod_msgs::PositionWithSpeed::ConstPtr& msg)
490 {
491  std::vector<uint8_t> ret_vec;
492 
493  if (can_id == SteerCmdMsg::CAN_ID)
494  {
495  SteerCmdMsg encoder;
496  encoder.encode(msg->angular_position, msg->angular_velocity_limit);
497  return encoder.data;
498  }
499 }
500 
501 } // namespace PACMod
502 } // namespace Drivers
503 } // namespace AS
void fillSteeringPIDRpt3(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::SteeringPIDRpt3 *new_msg, std::string frame_id)
static const int64_t CAN_ID
Definition: pacmod_core.h:468
void fillSteeringPIDRpt1(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::SteeringPIDRpt1 *new_msg, std::string frame_id)
void fillSystemRptInt(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::SystemRptInt *new_msg, std::string frame_id)
void fillYawRateRpt(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::YawRateRpt *new_msg, std::string frame_id)
void encode(uint8_t turn_signal_cmd)
static const int64_t CAN_ID
Definition: pacmod_core.h:127
void fillSteeringPIDRpt4(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::SteeringPIDRpt4 *new_msg, std::string frame_id)
void encode(double steer_pos, double steer_spd)
static const int64_t CAN_ID
Definition: pacmod_core.h:423
void fillMotorRpt1(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::MotorRpt1 *new_msg, std::string frame_id)
void fillVinRpt(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::VinRpt *new_msg, std::string frame_id)
void fillParkingBrakeStatusRpt(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::ParkingBrakeStatusRpt *new_msg, std::string frame_id)
static const int64_t CAN_ID
Definition: pacmod_core.h:450
void fillWheelSpeedRpt(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::WheelSpeedRpt *new_msg, std::string frame_id)
void fillVehicleSpeedRpt(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::VehicleSpeedRpt *new_msg, std::string frame_id)
Definition: pacmod_core.h:30
static const int64_t CAN_ID
Definition: pacmod_core.h:166
static const int64_t CAN_ID
Definition: pacmod_core.h:396
void encode(double accel_cmd)
static const int64_t CAN_ID
Definition: pacmod_core.h:120
static const int64_t CAN_ID
Definition: pacmod_core.h:73
static const int64_t CAN_ID
Definition: pacmod_core.h:159
std::vector< unsigned char > _data
std::vector< uint8_t > data
Definition: pacmod_core.h:389
void encode(uint8_t horn_cmd)
void fillGlobalRpt(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::GlobalRpt *new_msg, std::string frame_id)
std::vector< unsigned char > getData() const
void publish(const boost::shared_ptr< M > &message) const
static std::vector< uint8_t > unpackAndEncode(const int64_t &can_id, const pacmod_msgs::PacmodCmd::ConstPtr &msg)
static const int64_t CAN_ID
Definition: pacmod_core.h:432
static const int64_t CAN_ID
Definition: pacmod_core.h:113
void encode(uint8_t shift_cmd)
static const int64_t CAN_ID
Definition: pacmod_core.h:441
static const int64_t CAN_ID
Definition: pacmod_core.h:56
void fillLatLonHeadingRpt(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::LatLonHeadingRpt *new_msg, std::string frame_id)
void fillMotorRpt2(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::MotorRpt2 *new_msg, std::string frame_id)
void encode(double brake_cmd)
static const int64_t CAN_ID
Definition: pacmod_core.h:145
void encode(bool enable, bool clear_override, bool ignore_overide)
static const int64_t CAN_ID
Definition: pacmod_core.h:173
void fillSystemRptFloat(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::SystemRptFloat *new_msg, std::string frame_id)
void encode(uint8_t wiper_cmd)
void encode(uint8_t headlight_cmd)
void fillDateTimeRpt(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::DateTimeRpt *new_msg, std::string frame_id)
static Time now()
void fillMotorRpt3(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::MotorRpt3 *new_msg, std::string frame_id)
static const int64_t CAN_ID
Definition: pacmod_core.h:152
void fillAndPublish(const int64_t &can_id, std::string frame_id, const ros::Publisher &pub, const std::shared_ptr< PacmodTxMsg > &parser_class)
void fillSteeringPIDRpt2(const std::shared_ptr< PacmodTxMsg > &parser_class, pacmod_msgs::SteeringPIDRpt2 *new_msg, std::string frame_id)
static const int64_t CAN_ID
Definition: pacmod_core.h:459
void setData(std::vector< unsigned char > new_data)


pacmod
Author(s): Joe Driscoll , Josh Whitley
autogenerated on Mon Feb 28 2022 23:03:08