85 return std::shared_ptr<Pacmod3TxMsg>(
new AccelRptMsg);
97 return std::shared_ptr<Pacmod3TxMsg>(
new BrakeRptMsg);
115 return std::shared_ptr<Pacmod3TxMsg>(
new DoorRptMsg);
124 return std::shared_ptr<Pacmod3TxMsg>(
new HornRptMsg);
145 return std::shared_ptr<Pacmod3TxMsg>(
new ShiftRptMsg);
169 return std::shared_ptr<Pacmod3TxMsg>(
new SteerRptMsg);
184 return std::shared_ptr<Pacmod3TxMsg>(
new VinRptMsg);
190 return std::shared_ptr<Pacmod3TxMsg>(
new WiperRptMsg);
229 override_active(false),
230 command_output_fault(false),
231 input_output_fault(false),
232 output_reported_fault(false),
268 fault_active = ((in[0] & 0x80) > 0);
269 config_fault_active = ((in[1] & 0x01) > 0);
270 user_can_timeout = ((in[0] & 0x04) > 0);
271 steering_can_timeout = ((in[0] & 0x08) > 0);
272 brake_can_timeout = ((in[0] & 0x10) > 0);
273 subsystem_can_timeout = ((in[0] & 0x20) > 0);
274 vehicle_can_timeout = ((in[0] & 0x40) > 0);
275 user_can_read_errors = ((in[6] << 8) | in[7]);
280 enabled = ((in[0] & 0x01) > 0);
289 command = ((in[2] & 0x01) > 0);
290 output = ((in[3] & 0x01) > 0);
295 enabled = ((in[0] & 0x01) > 0);
310 enabled = ((in[0] & 0x01) > 0);
320 temp = ((int16_t)in[1] << 8) | in[2];
323 temp = ((int16_t)in[3] << 8) | in[4];
324 command = (double)(temp / 1000.0);
326 temp = ((int16_t)in[5] << 8) | in[6];
327 output = (double)(temp / 1000.0);
334 temp = ((int16_t)in[0] << 8) | in[1];
335 raw_pedal_pos = (float)temp / 1000.0;
337 temp = ((int16_t)in[2] << 8) | in[3];
338 raw_pedal_force = (float)temp / 1000.0;
340 user_interaction = (in[4] & 0x01) > 0;
341 raw_pedal_pos_is_valid = (in[5] & 0x01) > 0;
342 raw_pedal_force_is_valid = (in[5] & 0x02) > 0;
343 user_interaction_is_valid = (in[5] & 0x04) > 0;
350 temp = ((int16_t)in[0] << 8) | in[1];
351 raw_pedal_pos = (float)temp / 1000.0;
353 temp = ((int16_t)in[2] << 8) | in[3];
354 raw_pedal_force = (float)temp / 1000.0;
356 temp = ((int16_t)in[4] << 8) | in[5];
357 raw_brake_pressure = (float)temp / 1000.0;
359 user_interaction = (in[6] & 0x01) > 0;
360 brake_on_off = (in[6] & 0x02) > 0;
361 raw_pedal_pos_is_valid = (in[7] & 0x01) > 0;
362 raw_pedal_force_is_valid = (in[7] & 0x02) > 0;
363 raw_brake_pressure_is_valid = (in[7] & 0x04) > 0;
364 user_interaction_is_valid = (in[7] & 0x08) > 0;
365 brake_on_off_is_valid = (in[7] & 0x10) > 0;
382 temp = (((int16_t)in[0] << 8) | in[1]);
383 front_object_distance_low_res = (double)(temp / 1000.0);
385 temp = (((int16_t)in[2] << 8) | in[3]);
386 front_object_distance_high_res = (double)(temp / 1000.0);
391 driver_door_open = ((in[0] & 0x01) > 0);
392 driver_door_open_is_valid = ((in[1] & 0x01) > 0);
393 passenger_door_open = ((in[0] & 0x02) > 0);
394 passenger_door_open_is_valid = ((in[1] & 0x02) > 0);
395 rear_driver_door_open = ((in[0] & 0x04) > 0);
396 rear_driver_door_open_is_valid = ((in[1] & 0x04) > 0);
397 rear_passenger_door_open = ((in[0] & 0x08) > 0);
398 rear_passenger_door_open_is_valid = ((in[1] & 0x08) > 0);
399 hood_open = ((in[0] & 0x10) > 0);
400 hood_open_is_valid = ((in[1] & 0x10) > 0);
401 trunk_open = ((in[0] & 0x20) > 0);
402 trunk_open_is_valid = ((in[1] & 0x20) > 0);
403 fuel_door_open = ((in[0] & 0x40) > 0);
404 fuel_door_open_is_valid = ((in[1] & 0x40) > 0);
409 headlights_on = (in[0] & 0x01) > 0;
410 headlights_on_bright = (in[0] & 0x02) > 0;
411 fog_lights_on = (in[0] & 0x04) > 0;
412 headlights_mode = in[1];
413 headlights_on_is_valid = (in[2] & 0x01) > 0;
414 headlights_on_bright_is_valid = (in[2] & 0x02) > 0;
415 fog_lights_on = (in[2] & 0x04) > 0;
416 headlights_mode_is_valid = (in[2] & 0x08) > 0;
421 front_dome_lights_on = ((in[0] & 0x01) > 0);
422 front_dome_lights_on_is_valid = ((in[2] & 0x01) > 0);
423 rear_dome_lights_on = ((in[0] & 0x02) > 0);
424 rear_dome_lights_on_is_valid = ((in[2] & 0x02) > 0);
425 mood_lights_on = ((in[0] & 0x04) > 0);
426 mood_lights_on_is_valid = ((in[2] & 0x04) > 0);
428 dim_level_is_valid = ((in[2] & 0x08) > 0);
433 latitude_degrees = (int8_t)in[0];
434 latitude_minutes = (uint8_t)in[1];
435 latitude_seconds = (uint8_t)in[2];
436 longitude_degrees = (int8_t)in[3];
437 longitude_minutes = (uint8_t)in[4];
438 longitude_seconds = (uint8_t)in[5];
439 heading = (((int16_t)in[6] << 8) | in[7]) / 100.0;
446 temp = ((int32_t)in[0] << 24) | ((int32_t)in[1] << 16) | ((int32_t)in[2] << 8) | in[3];
447 current = (double)(temp / 1000.0);
449 temp = ((int32_t)in[4] << 24) | ((int32_t)in[5] << 16) | ((int32_t)in[6] << 8) | in[7];
450 position = (double)(temp / 1000.0);
458 temp16 = ((int16_t)in[0] << 8) | in[1];
459 encoder_temp = (double)temp16;
461 temp16 = ((int16_t)in[2] << 8) | in[3];
462 motor_temp = (double)temp16;
464 temp32 = ((int32_t)in[7] << 24) | ((int32_t)in[6] << 16) | ((int32_t)in[5] << 8) | in[4];
465 velocity = (double)(temp32 / 1000.0);
472 temp = ((int32_t)in[0] << 24) | ((int32_t)in[1] << 16) | ((int32_t)in[2] << 8) | in[3];
473 torque_output = (double)(temp / 1000.0);
475 temp = ((int32_t)in[4] << 24) | ((int32_t)in[5] << 16) | ((int32_t)in[6] << 8) | in[7];
476 torque_input = (double)(temp / 1000.0);
481 driver_seat_occupied = ((in[0] & 0x01) > 0);
482 driver_seat_occupied_is_valid = ((in[1] & 0x01) > 0);
483 passenger_seat_occupied = ((in[0] & 0x02) > 0);
484 passenger_seat_occupied_is_valid = ((in[1] & 0x02) > 0);
485 rear_seat_occupied = ((in[0] & 0x04) > 0);
486 rear_seat_occupied_is_valid = ((in[1] & 0x04) > 0);
487 driver_seatbelt_buckled = ((in[0] & 0x08) > 0);
488 driver_seatbelt_buckled_is_valid = ((in[1] & 0x08) > 0);
489 passenger_seatbelt_buckled = ((in[0] & 0x10) > 0);
490 passenger_seatbelt_buckled_is_valid = ((in[1] & 0x10) > 0);
491 rear_seatbelt_buckled = ((in[0] & 0x20) > 0);
492 rear_seatbelt_buckled_is_valid = ((in[1] & 0x20) > 0);
497 brake_lights_on = ((in[0] & 0x01) > 0);
498 brake_lights_on_is_valid = ((in[1] & 0x01) > 0);
499 reverse_lights_on = ((in[0] & 0x02) > 0);
500 reverse_lights_on_is_valid = ((in[1] & 0x02) > 0);
505 between_gears = (in[0] & 0x01) > 0;
506 stay_in_neutral_mode = (in[0] & 0x02) > 0;
507 brake_interlock_active = (in[0] & 0x04) > 0;
508 speed_interlock_active = (in[0] & 0x08) > 0;
509 between_gears_is_valid = (in[1] & 0x01) > 0;
510 stay_in_neutral_mode_is_valid = (in[1] & 0x02) > 0;
511 brake_interlock_active_is_valid = (in[1] & 0x04) > 0;
512 speed_interlock_active_is_valid = (in[1] & 0x08) > 0;
519 temp = ((int16_t)in[0] << 8) | in[1];
520 raw_position = (float)temp / 10.0;
522 temp = ((int16_t)in[2] << 8) | in[3];
523 raw_torque = (float)temp / 10.0;
527 temp2 = ((uint16_t)in[4] << 8) | in[5];
528 rotation_rate = (float)temp2 / 100.0;
530 user_interaction = (in[6] & 0x01) > 0;
531 raw_position_is_valid = (in[7] & 0x01) > 0;
532 raw_torque_is_valid = (in[7] & 0x02) > 0;
533 rotation_rate_is_valid = (in[7] & 0x04) > 0;
534 user_interaction_is_valid = (in[7] & 0x08) > 0;
541 temp = ((int16_t)in[0] << 8) | in[1];
542 dt = (double)(temp / 1000.0);
544 temp = ((int16_t)in[2] << 8) | in[3];
545 Kp = (double)(temp / 1000.0);
547 temp = ((int16_t)in[4] << 8) | in[5];
548 Ki = (double)(temp / 1000.0);
550 temp = ((int16_t)in[6] << 8) | in[7];
551 Kd = (double)(temp / 1000.0);
558 temp = ((int16_t)in[0] << 8) | in[1];
559 P_term = (double)(temp / 1000.0);
561 temp = ((int16_t)in[2] << 8) | in[3];
562 I_term = (double)(temp / 1000.0);
564 temp = ((int16_t)in[4] << 8) | in[5];
565 D_term = (double)(temp / 1000.0);
567 temp = ((int16_t)in[6] << 8) | in[7];
568 all_terms = (double)(temp / 1000.0);
575 temp = ((int16_t)in[0] << 8) | in[1];
576 new_torque = (double)(temp / 1000.0);
578 temp = ((int16_t)in[2] << 8) | in[3];
579 str_angle_desired = (double)(temp / 1000.0);
581 temp = ((int16_t)in[4] << 8) | in[5];
582 str_angle_actual = (double)(temp / 1000.0);
584 temp = ((int16_t)in[6] << 8) | in[7];
585 error = (double)(temp / 1000.0);
592 temp = ((int16_t)in[0] << 8) | in[1];
593 angular_velocity = (double)(temp / 1000.0);
595 temp = ((int16_t)in[2] << 8) | in[3];
596 angular_acceleration = (double)(temp / 1000.0);
601 driver_blinker_bulb_on = (in[0] & 0x01) > 0;
602 passenger_blinker_bulb_on = (in[0] & 0x02) > 0;
603 driver_blinker_bulb_on_is_valid = (in[1] & 0x01) > 0;
604 passenger_blinker_bulb_on_is_valid = (in[1] & 0x02) > 0;
617 temp = (((int16_t)in[1] << 8) | in[2]);
618 brake_torque = (double)(temp / 1000.0);
627 temp = ((int16_t)in[0] << 8) | in[1];
628 vehicle_speed = (double)(temp / 100.0);
630 vehicle_speed_valid = (in[2] == 1);
631 vehicle_speed_raw[0] = in[3];
632 vehicle_speed_raw[1] = in[4];
637 std::ostringstream oss;
638 oss << in[0] << in[1] << in[2];
639 mfg_code = oss.str();
641 if (mfg_code ==
"52C")
642 mfg =
"POLARIS INDUSTRIES INC.";
643 else if (mfg_code ==
"3HS")
644 mfg =
"NAVISTAR, INC.";
645 else if (mfg_code ==
"2T2")
646 mfg =
"TOYOTA MOTOR MANUFACTURING CANADA";
650 model_year_code = in[3];
652 if (model_year_code >=
'1' && model_year_code <=
'9')
654 model_year = 2000 + model_year_code;
656 else if (model_year_code >=
'A' && model_year_code <
'Z')
658 switch (model_year_code)
732 serial = (in[4] & 0x0F);
733 serial = (serial << 8) | in[5];
734 serial = (serial << 8) | in[6];
741 temp = ((int16_t)in[0] << 8) | in[1];
742 front_left_wheel_speed = (double)(temp / 100.0);
744 temp = ((int16_t)in[2] << 8) | in[3];
745 front_right_wheel_speed = (double)(temp / 100.0);
747 temp = ((int16_t)in[4] << 8) | in[5];
748 rear_left_wheel_speed = (double)(temp / 100.0);
750 temp = ((int16_t)in[6] << 8) | in[7];
751 rear_right_wheel_speed = (double)(temp / 100.0);
756 front_wiping = (in[0] & 0x01) > 0;
757 front_spraying = (in[0] & 0x02) > 0;
758 rear_wiping = (in[0] & 0x04) > 0;
759 rear_spraying = (in[0] & 0x08) > 0;
760 spray_near_empty = (in[0] & 0x10) > 0;
761 spray_empty = (in[0] & 0x20) > 0;
762 front_wiping_is_valid = (in[1] & 0x01) > 0;
763 front_spraying_is_valid = (in[1] & 0x02) > 0;
764 rear_wiping_is_valid = (in[1] & 0x04) > 0;
765 rear_spraying_is_valid = (in[1] & 0x08) > 0;
766 spray_near_empty_is_valid = (in[1] & 0x10) > 0;
767 spray_empty_is_valid = (in[1] & 0x20) > 0;
774 temp = ((int16_t)in[0] << 8) | in[1];
775 yaw_rate = (double)(temp / 100.0);
780 bool ignore_overrides,
786 data[0] = (enable ? 0x01 : 0x00);
787 data[0] |= (ignore_overrides ? 0x02 : 0x00);
788 data[0] |= clear_override ? 0x04 : 0x00;
789 data[1] = (cmd ? 0x01 : 0x00);
793 bool ignore_overrides,
799 data[0] = enable ? 0x01 : 0x00;
800 data[0] |= ignore_overrides ? 0x02 : 0x00;
801 data[0] |= clear_override ? 0x04 : 0x00;
803 uint16_t cmd_float = (uint16_t)(cmd * 1000.0);
804 data[1] = (cmd_float & 0xFF00) >> 8;
805 data[2] = cmd_float & 0x00FF;
809 bool ignore_overrides,
815 data[0] = enable ? 0x01 : 0x00;
816 data[0] |= ignore_overrides ? 0x02 : 0x00;
817 data[0] |= clear_override ? 0x04 : 0x00;
822 bool ignore_overrides,
829 data[0] = enable ? 0x01 : 0x00;
830 data[0] |= ignore_overrides ? 0x02 : 0x00;
831 data[0] |= clear_override ? 0x04 : 0x00;
833 int16_t raw_pos = (int16_t)(1000.0 * steer_pos);
834 uint16_t raw_spd = (uint16_t)(1000.0 * steer_spd);
836 data[1] = (raw_pos & 0xFF00) >> 8;
837 data[2] = raw_pos & 0x00FF;
838 data[3] = (raw_spd & 0xFF00) >> 8;
839 data[4] = raw_spd & 0x00FF;
static const int64_t CAN_ID
void encode(bool enable, bool ignore_overrides, bool clear_override, uint8_t cmd)
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static std::shared_ptr< Pacmod3TxMsg > make_message(const int64_t &can_id)
static const int64_t CAN_ID
static const int64_t CAN_ID
bool command_output_fault
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
void encode(bool enabled, bool ignore_overrides, bool clear_override, float steer_pos, float steer_spd)
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
ROSLIB_DECL std::string command(const std::string &cmd)
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
void encode(bool enable, bool ignore_overrides, bool clear_override, float cmd)
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
void encode(bool enable, bool ignore_overrides, bool clear_override, bool cmd)
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
bool output_reported_fault
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID