pacmod_core.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 
21 #include <pacmod/pacmod_core.h>
22 
23 #include <memory>
24 
25 namespace AS
26 {
27 namespace Drivers
28 {
29 namespace PACMod
30 {
31 
32 const int64_t TurnSignalCmdMsg::CAN_ID = 0x63;
33 const int64_t TurnSignalRptMsg::CAN_ID = 0x64;
34 const int64_t ShiftCmdMsg::CAN_ID = 0x65;
35 const int64_t ShiftRptMsg::CAN_ID = 0x66;
36 const int64_t AccelCmdMsg::CAN_ID = 0x67;
37 const int64_t AccelRptMsg::CAN_ID = 0x68;
38 const int64_t GlobalCmdMsg::CAN_ID = 0x69;
39 const int64_t GlobalRptMsg::CAN_ID = 0x6A;
40 const int64_t BrakeCmdMsg::CAN_ID = 0x6B;
41 const int64_t SteerCmdMsg::CAN_ID = 0x6D;
42 const int64_t BrakeRptMsg::CAN_ID = 0x6C;
43 const int64_t SteerRptMsg::CAN_ID = 0x6E;
44 const int64_t VehicleSpeedRptMsg::CAN_ID = 0x6F;
45 const int64_t BrakeMotorRpt1Msg::CAN_ID = 0x70;
46 const int64_t BrakeMotorRpt2Msg::CAN_ID = 0x71;
47 const int64_t BrakeMotorRpt3Msg::CAN_ID = 0x72;
48 const int64_t SteerMotorRpt1Msg::CAN_ID = 0x73;
49 const int64_t SteerMotorRpt2Msg::CAN_ID = 0x74;
50 const int64_t SteerMotorRpt3Msg::CAN_ID = 0x75;
51 const int64_t HeadlightCmdMsg::CAN_ID = 0x76;
52 const int64_t HeadlightRptMsg::CAN_ID = 0x77;
53 const int64_t HornCmdMsg::CAN_ID = 0x78;
54 const int64_t HornRptMsg::CAN_ID = 0x79;
55 const int64_t WheelSpeedRptMsg::CAN_ID = 0x7A;
56 const int64_t SteeringPIDRpt1Msg::CAN_ID = 0x7B;
57 const int64_t SteeringPIDRpt2Msg::CAN_ID = 0x7C;
58 const int64_t SteeringPIDRpt3Msg::CAN_ID = 0x7D;
59 const int64_t SteerRpt2Msg::CAN_ID = 0x7E;
60 const int64_t SteerRpt3Msg::CAN_ID = 0x7F;
61 const int64_t ParkingBrakeStatusRptMsg::CAN_ID = 0x80;
62 const int64_t YawRateRptMsg::CAN_ID = 0x81;
63 const int64_t LatLonHeadingRptMsg::CAN_ID = 0x82;
64 const int64_t DateTimeRptMsg::CAN_ID = 0x83;
65 const int64_t SteeringPIDRpt4Msg::CAN_ID = 0x84;
66 const int64_t WiperCmdMsg::CAN_ID = 0x90;
67 const int64_t WiperRptMsg::CAN_ID = 0x91;
68 const int64_t VinRptMsg::CAN_ID = 0xFF;
69 
70 std::shared_ptr<PacmodTxMsg> PacmodTxMsg::make_message(const int64_t& can_id)
71 {
72  switch (can_id)
73  {
75  return std::shared_ptr<PacmodTxMsg>(new TurnSignalRptMsg);
76  break;
78  return std::shared_ptr<PacmodTxMsg>(new ShiftRptMsg);
79  break;
81  return std::shared_ptr<PacmodTxMsg>(new AccelRptMsg);
82  break;
84  return std::shared_ptr<PacmodTxMsg>(new GlobalRptMsg);
85  break;
87  return std::shared_ptr<PacmodTxMsg>(new BrakeRptMsg);
88  break;
90  return std::shared_ptr<PacmodTxMsg>(new SteerRptMsg);
91  break;
93  return std::shared_ptr<PacmodTxMsg>(new VehicleSpeedRptMsg);
94  break;
96  return std::shared_ptr<PacmodTxMsg>(new BrakeMotorRpt1Msg);
97  break;
99  return std::shared_ptr<PacmodTxMsg>(new BrakeMotorRpt2Msg);
100  break;
102  return std::shared_ptr<PacmodTxMsg>(new BrakeMotorRpt3Msg);
103  break;
105  return std::shared_ptr<PacmodTxMsg>(new SteerMotorRpt1Msg);
106  break;
108  return std::shared_ptr<PacmodTxMsg>(new SteerMotorRpt2Msg);
109  break;
111  return std::shared_ptr<PacmodTxMsg>(new SteerMotorRpt3Msg);
112  break;
114  return std::shared_ptr<PacmodTxMsg>(new HeadlightRptMsg);
115  break;
116  case HornRptMsg::CAN_ID:
117  return std::shared_ptr<PacmodTxMsg>(new HornRptMsg);
118  break;
120  return std::shared_ptr<PacmodTxMsg>(new WheelSpeedRptMsg);
121  break;
123  return std::shared_ptr<PacmodTxMsg>(new SteeringPIDRpt1Msg);
124  break;
126  return std::shared_ptr<PacmodTxMsg>(new SteeringPIDRpt2Msg);
127  break;
129  return std::shared_ptr<PacmodTxMsg>(new SteeringPIDRpt3Msg);
130  break;
132  return std::shared_ptr<PacmodTxMsg>(new SteerRpt2Msg);
133  break;
135  return std::shared_ptr<PacmodTxMsg>(new SteerRpt3Msg);
136  break;
138  return std::shared_ptr<PacmodTxMsg>(new ParkingBrakeStatusRptMsg);
139  break;
141  return std::shared_ptr<PacmodTxMsg>(new YawRateRptMsg);
142  break;
144  return std::shared_ptr<PacmodTxMsg>(new LatLonHeadingRptMsg);
145  break;
147  return std::shared_ptr<PacmodTxMsg>(new DateTimeRptMsg);
148  break;
150  return std::shared_ptr<PacmodTxMsg>(new SteeringPIDRpt4Msg);
151  break;
152  case WiperRptMsg::CAN_ID:
153  return std::shared_ptr<PacmodTxMsg>(new WiperRptMsg);
154  break;
155  case VinRptMsg::CAN_ID:
156  return std::shared_ptr<PacmodTxMsg>(new VinRptMsg);
157  break;
158  default:
159  return NULL;
160  }
161 }
162 
163 // TX Messages
164 void GlobalRptMsg::parse(uint8_t *in)
165 {
166  enabled = in[0] & 0x01;
167  override_active = ((in[0] & 0x02) >> 1) != 0;
168  user_can_timeout = ((in[0] & 0x20) >> 5) != 0;
169  brake_can_timeout = ((in[0] & 0x10) >> 4) != 0;
170  steering_can_timeout = ((in[0] & 0x08) >> 3) != 0;
171  vehicle_can_timeout = ((in[0] & 0x04) >> 2) != 0;
172  user_can_read_errors = ((in[6] << 8) | in[7]);
173 }
174 
175 void VinRptMsg::parse(uint8_t *in)
176 {
177  std::ostringstream oss;
178  oss << in[0] << in[1] << in[2];
179  mfg_code = oss.str();
180 
181  if (mfg_code == "52C")
182  mfg = "POLARIS INDUSTRIES INC.";
183  else if (mfg_code == "3HS")
184  mfg = "NAVISTAR, INC.";
185  else if (mfg_code == "2T2")
186  mfg = "TOYOTA MOTOR MANUFACTURING CANADA";
187 
188  model_year_code = in[3];
189 
190  if (model_year_code >= '1' && model_year_code <= '9')
191  {
192  model_year = 2000 + model_year_code;
193  }
194  else if (model_year_code >= 'A' && model_year_code < 'Z')
195  {
196  switch (model_year_code)
197  {
198  case 'A':
199  model_year = 2010;
200  break;
201  case 'B':
202  model_year = 2011;
203  break;
204  case 'C':
205  model_year = 2012;
206  break;
207  case 'D':
208  model_year = 2013;
209  break;
210  case 'E':
211  model_year = 2014;
212  break;
213  case 'F':
214  model_year = 2015;
215  break;
216  case 'G':
217  model_year = 2016;
218  break;
219  case 'H':
220  model_year = 2017;
221  break;
222  case 'J':
223  model_year = 2018;
224  break;
225  case 'K':
226  model_year = 2019;
227  break;
228  case 'L':
229  model_year = 2020;
230  break;
231  case 'M':
232  model_year = 2021;
233  break;
234  case 'N':
235  model_year = 2022;
236  break;
237  case 'P':
238  model_year = 2023;
239  break;
240  case 'R':
241  model_year = 2024;
242  break;
243  case 'S':
244  model_year = 2025;
245  break;
246  case 'T':
247  model_year = 2026;
248  break;
249  case 'V':
250  model_year = 2027;
251  break;
252  case 'W':
253  model_year = 2028;
254  break;
255  case 'X':
256  model_year = 2029;
257  break;
258  case 'Y':
259  model_year = 2030;
260  break;
261  }
262  }
263 
264  serial = (in[4] & 0x0F);
265  serial = (serial << 8) | in[5];
266  serial = (serial << 8) | in[6];
267 }
268 
269 void SystemRptIntMsg::parse(uint8_t *in)
270 {
271  manual_input = in[0];
272  command = in[1];
273  output = in[2];
274 }
275 
276 void SystemRptFloatMsg::parse(uint8_t *in)
277 {
278  int16_t temp;
279 
280  temp = (static_cast<int16_t>(in[0]) << 8) | in[1];
281  manual_input = static_cast<double>(temp / 1000.0);
282 
283  temp = (static_cast<int16_t>(in[2]) << 8) | in[3];
284  command = static_cast<double>(temp / 1000.0);
285 
286  temp = (static_cast<int16_t>(in[4]) << 8) | in[5];
287  output = static_cast<double>(temp / 1000.0);
288 }
289 
290 void VehicleSpeedRptMsg::parse(uint8_t *in)
291 {
292  int16_t temp;
293 
294  temp = (static_cast<int16_t>(in[0]) << 8) | in[1];
295  vehicle_speed = static_cast<double>(temp / 100.0);
296 
297  vehicle_speed_valid = (in[2] == 1);
298  vehicle_speed_raw[0] = in[3];
299  vehicle_speed_raw[1] = in[4];
300 }
301 
302 void YawRateRptMsg::parse(uint8_t *in)
303 {
304  int16_t temp;
305 
306  temp = (static_cast<int16_t>(in[0]) << 8) | in[1];
307  yaw_rate = static_cast<double>(temp / 100.0);
308 }
309 
310 void LatLonHeadingRptMsg::parse(uint8_t *in)
311 {
312  latitude_degrees = static_cast<int8_t>(in[0]);
313  latitude_minutes = in[1];
314  latitude_seconds = in[2];
315  longitude_degrees = static_cast<int8_t>(in[3]);
316  longitude_minutes = in[4];
317  longitude_seconds = in[5];
318  heading = ((static_cast<int16_t>(in[6]) << 8) | in[7]) / 100.0;
319 }
320 
321 void DateTimeRptMsg::parse(uint8_t *in)
322 {
323  year = in[0];
324  month = in[1];
325  day = in[2];
326  hour = in[3];
327  minute = in[4];
328  second = in[5];
329 }
330 
331 void WheelSpeedRptMsg::parse(uint8_t *in)
332 {
333  int16_t temp;
334 
335  temp = (static_cast<int16_t>(in[0]) << 8) | in[1];
336  front_left_wheel_speed = static_cast<double>(temp / 100.0);
337 
338  temp = (static_cast<int16_t>(in[2]) << 8) | in[3];
339  front_right_wheel_speed = static_cast<double>(temp / 100.0);
340 
341  temp = (static_cast<int16_t>(in[4]) << 8) | in[5];
342  rear_left_wheel_speed = static_cast<double>(temp / 100.0);
343 
344  temp = (static_cast<int16_t>(in[6]) << 8) | in[7];
345  rear_right_wheel_speed = static_cast<double>(temp / 100.0);
346 }
347 
348 void MotorRpt1Msg::parse(uint8_t *in)
349 {
350  int32_t temp;
351 
352  temp = (static_cast<int32_t>(in[0]) << 24) |
353  (static_cast<int32_t>(in[1]) << 16) |
354  (static_cast<int32_t>(in[2]) << 8) | in[3];
355  current = static_cast<double>(temp / 1000.0);
356 
357  temp = (static_cast<int32_t>(in[4]) << 24) |
358  (static_cast<int32_t>(in[5]) << 16) |
359  (static_cast<int32_t>(in[6]) << 8) | in[7];
360  position = static_cast<double>(temp / 1000.0);
361 }
362 
363 void MotorRpt2Msg::parse(uint8_t *in)
364 {
365  int16_t temp16;
366  int32_t temp32;
367 
368  temp16 = (static_cast<int16_t>(in[0]) << 8) | in[1];
369  encoder_temp = static_cast<double>(temp16);
370 
371  temp16 = (static_cast<int16_t>(in[2]) << 8) | in[3];
372  motor_temp = static_cast<double>(temp16);
373 
374  temp32 = (static_cast<int32_t>(in[7]) << 24) |
375  (static_cast<int32_t>(in[6]) << 16) |
376  (static_cast<int32_t>(in[5]) << 8) | in[4];
377  velocity = static_cast<double>(temp32 / 1000.0);
378 }
379 
380 void MotorRpt3Msg::parse(uint8_t *in)
381 {
382  int32_t temp;
383 
384  temp = (static_cast<int32_t>(in[0]) << 24) |
385  (static_cast<int32_t>(in[1]) << 16) |
386  (static_cast<int32_t>(in[2]) << 8) | in[3];
387  torque_output = static_cast<double>(temp / 1000.0);
388 
389  temp = (static_cast<int32_t>(in[4]) << 24) |
390  (static_cast<int32_t>(in[5]) << 16) |
391  (static_cast<int32_t>(in[6]) << 8) | in[7];
392  torque_input = static_cast<double>(temp / 1000.0);
393 }
394 
395 void SteeringPIDRpt1Msg::parse(uint8_t *in)
396 {
397  int16_t temp;
398 
399  temp = (static_cast<int16_t>(in[0]) << 8) | in[1];
400  dt = static_cast<double>(temp / 1000.0);
401 
402  temp = (static_cast<int16_t>(in[2]) << 8) | in[3];
403  kp = static_cast<double>(temp / 1000.0);
404 
405  temp = (static_cast<int16_t>(in[4]) << 8) | in[5];
406  ki = static_cast<double>(temp / 1000.0);
407 
408  temp = (static_cast<int16_t>(in[6]) << 8) | in[7];
409  kd = static_cast<double>(temp / 1000.0);
410 }
411 
412 void SteeringPIDRpt2Msg::parse(uint8_t *in)
413 {
414  int16_t temp;
415 
416  temp = (static_cast<int16_t>(in[0]) << 8) | in[1];
417  p_term = static_cast<double>(temp / 1000.0);
418 
419  temp = (static_cast<int16_t>(in[2]) << 8) | in[3];
420  i_term = static_cast<double>(temp / 1000.0);
421 
422  temp = (static_cast<int16_t>(in[4]) << 8) | in[5];
423  d_term = static_cast<double>(temp / 1000.0);
424 
425  temp = (static_cast<int16_t>(in[6]) << 8) | in[7];
426  all_terms = static_cast<double>(temp / 1000.0);
427 }
428 
429 void SteeringPIDRpt3Msg::parse(uint8_t *in)
430 {
431  int16_t temp;
432 
433  temp = (static_cast<int16_t>(in[0]) << 8) | in[1];
434  new_torque = static_cast<double>(temp / 1000.0);
435 
436  temp = (static_cast<int16_t>(in[2]) << 8) | in[3];
437  str_angle_desired = static_cast<double>(temp / 1000.0);
438 
439  temp = (static_cast<int16_t>(in[4]) << 8) | in[5];
440  str_angle_actual = static_cast<double>(temp / 1000.0);
441 
442  temp = (static_cast<int16_t>(in[6]) << 8) | in[7];
443  error = static_cast<double>(temp / 1000.0);
444 }
445 
446 void SteeringPIDRpt4Msg::parse(uint8_t *in)
447 {
448  int16_t temp;
449 
450  temp = (static_cast<int16_t>(in[0]) << 8) | in[1];
451  angular_velocity = static_cast<double>(temp / 1000.0);
452 
453  temp = (static_cast<int16_t>(in[2]) << 8) | in[3];
454  angular_acceleration = static_cast<double>(temp / 1000.0);
455 }
456 
458 {
459  parking_brake_engaged = (in[0] == 0x01);
460 }
461 
462 // RX Messages
463 void GlobalCmdMsg::encode(bool enable, bool clear_override, bool ignore_overide)
464 {
465  data.assign(8, 0);
466 
467  if (enable)
468  data[0] |= 0x01;
469  if (clear_override)
470  data[0] |= 0x02;
471  if (ignore_overide)
472  data[0] |= 0x04;
473 }
474 
475 void TurnSignalCmdMsg::encode(uint8_t turn_signal_cmd)
476 {
477  data.assign(8, 0);
478  data[0] = turn_signal_cmd;
479 }
480 
481 void HeadlightCmdMsg::encode(uint8_t headlight_cmd)
482 {
483  data.assign(8, 0);
484  data[0] = headlight_cmd;
485 }
486 
487 void HornCmdMsg::encode(uint8_t horn_cmd)
488 {
489  data.assign(8, 0);
490  data[0] = horn_cmd;
491 }
492 
493 void WiperCmdMsg::encode(uint8_t wiper_cmd)
494 {
495  data.assign(8, 0);
496  data[0] = wiper_cmd;
497 }
498 
499 void ShiftCmdMsg::encode(uint8_t shift_cmd)
500 {
501  data.assign(8, 0);
502  data[0] = shift_cmd;
503 }
504 
505 void AccelCmdMsg::encode(double accel_cmd)
506 {
507  data.assign(8, 0);
508  uint16_t cmdInt = static_cast<uint16_t>(accel_cmd * 1000.0);
509  data[0] = (cmdInt & 0xFF00) >> 8;
510  data[1] = cmdInt & 0x00FF;
511 }
512 
513 void SteerCmdMsg::encode(double steer_pos, double steer_spd)
514 {
515  data.assign(8, 0);
516  int32_t raw_pos = static_cast<int32_t>(1000.0 * steer_pos);
517  uint32_t raw_spd = (uint32_t)(1000.0 * steer_spd);
518 
519  data[0] = (raw_pos & 0xFF000000) >> 24;
520  data[1] = (raw_pos & 0x00FF0000) >> 16;
521  data[2] = (raw_pos & 0x0000FF00) >> 8;
522  data[3] = raw_pos & 0x000000FF;
523  data[4] = (raw_spd & 0xFF000000) >> 24;
524  data[5] = (raw_spd & 0x00FF0000) >> 16;
525  data[6] = (raw_spd & 0x0000FF00) >> 8;
526  data[7] = raw_spd & 0x000000FF;
527 }
528 
529 void BrakeCmdMsg::encode(double brake_pct)
530 {
531  data.assign(8, 0);
532  uint16_t raw_pct = static_cast<uint16_t>(1000.0 * brake_pct);
533 
534  data[0] = (raw_pct & 0xFF00) >> 8;
535  data[1] = (raw_pct & 0x00FF);
536 }
537 
538 } // namespace PACMod
539 } // namespace Drivers
540 } // namespace AS
static const int64_t CAN_ID
Definition: pacmod_core.h:468
void encode(uint8_t turn_signal_cmd)
static const int64_t CAN_ID
Definition: pacmod_core.h:127
void encode(double steer_pos, double steer_spd)
static const int64_t CAN_ID
Definition: pacmod_core.h:423
static const int64_t CAN_ID
Definition: pacmod_core.h:450
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 std::shared_ptr< PacmodTxMsg > make_message(const int64_t &can_id)
Definition: pacmod_core.cpp:70
static const int64_t CAN_ID
Definition: pacmod_core.h:73
static const int64_t CAN_ID
Definition: pacmod_core.h:159
void encode(uint8_t horn_cmd)
static const int64_t CAN_ID
Definition: pacmod_core.h:432
static const int64_t CAN_ID
Definition: pacmod_core.h:113
ROSLIB_DECL std::string command(const std::string &cmd)
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 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 encode(uint8_t wiper_cmd)
void encode(uint8_t headlight_cmd)
static const int64_t CAN_ID
Definition: pacmod_core.h:152
static const int64_t CAN_ID
Definition: pacmod_core.h:459


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