41 #define ROS_LOG_ONCE_ID(id, level, name, ...) \
44 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
45 static std::map<int, bool> map; \
46 bool &hit = map[id]; \
47 if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(!hit)) \
50 ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
53 #define ROS_DEBUG_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
54 #define ROS_INFO_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
55 #define ROS_WARN_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
56 #define ROS_ERROR_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
57 #define ROS_FATAL_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
184 pub_can_ =
node.advertise<can_msgs::Frame>(
"can_tx", 10);
185 pub_brake_ =
node.advertise<dbw_mkz_msgs::BrakeReport>(
"brake_report", 2);
186 pub_throttle_ =
node.advertise<dbw_mkz_msgs::ThrottleReport>(
"throttle_report", 2);
187 pub_steering_ =
node.advertise<dbw_mkz_msgs::SteeringReport>(
"steering_report", 2);
188 pub_gear_ =
node.advertise<dbw_mkz_msgs::GearReport>(
"gear_report", 2);
189 pub_misc_1_ =
node.advertise<dbw_mkz_msgs::Misc1Report>(
"misc_1_report", 2);
194 pub_surround_ =
node.advertise<dbw_mkz_msgs::SurroundReport>(
"surround_report", 2);
199 pub_imu_ =
node.advertise<sensor_msgs::Imu>(
"imu/data_raw", 10);
203 pub_twist_ =
node.advertise<geometry_msgs::TwistStamped>(
"twist", 10);
204 pub_vin_ =
node.advertise<std_msgs::String>(
"vin", 1,
true);
248 if (!msg->is_rtr && !msg->is_error && !msg->is_extended) {
255 dbw_mkz_msgs::BrakeReport out;
256 out.header.stamp = msg->header.stamp;
259 out.pedal_input = (float)ptr->
PI / UINT16_MAX;
260 out.pedal_cmd = (
float)ptr->
PC / UINT16_MAX;
261 out.pedal_output = (float)ptr->
PO / UINT16_MAX;
267 out.torque_input = ptr->
PI;
268 out.decel_cmd = ptr->
PC * 1e-3
f;
269 out.decel_output = ptr->
PO * 1e-3
f;
270 }
else if (ptr->
BTYPE == 2) {
272 out.torque_input = ptr->
PI;
273 out.torque_cmd = ptr->
PC;
274 out.torque_output = ptr->
PO;
278 out.boo_cmd = ptr->
BC ? true :
false;
279 out.enabled = ptr->
ENABLED ? true :
false;
280 out.override = ptr->
OVERRIDE ? true :
false;
281 out.driver = ptr->
DRIVER ? true :
false;
282 out.watchdog_counter.source = ptr->
WDCSRC;
283 out.watchdog_braking = ptr->
WDCBRK ? true :
false;
284 out.fault_wdc = ptr->
FLTWDC ? true :
false;
285 out.fault_ch1 = ptr->
FLT1 ? true :
false;
286 out.fault_ch2 = ptr->
FLT2 ? true :
false;
287 out.fault_power = ptr->
FLTPWR ? true :
false;
290 out.timeout = ptr->
TMOUT ? true :
false;
296 ptr->
FLT1 ?
"true, " :
"false,",
297 ptr->
FLT2 ?
"true, " :
"false,",
298 ptr->
FLTPWR ?
"true" :
"false");
308 dbw_mkz_msgs::ThrottleReport out;
309 out.header.stamp = msg->header.stamp;
310 out.pedal_input = (float)ptr->
PI / UINT16_MAX;
311 out.pedal_cmd = (
float)ptr->
PC / UINT16_MAX;
312 out.pedal_output = (float)ptr->
PO / UINT16_MAX;
313 out.enabled = ptr->
ENABLED ?
true :
false;
314 out.override = ptr->
OVERRIDE ?
true :
false;
315 out.driver = ptr->
DRIVER ?
true :
false;
316 out.watchdog_counter.source = ptr->
WDCSRC;
317 out.fault_wdc = ptr->
FLTWDC ?
true :
false;
318 out.fault_ch1 = ptr->
FLT1 ?
true :
false;
319 out.fault_ch2 = ptr->
FLT2 ?
true :
false;
320 out.fault_power = ptr->
FLTPWR ?
true :
false;
323 out.timeout = ptr->
TMOUT ? true :
false;
329 ptr->
FLT1 ?
"true, " :
"false,",
330 ptr->
FLT2 ?
"true, " :
"false,",
331 ptr->
FLTPWR ?
"true" :
"false");
342 dbw_mkz_msgs::SteeringReport out;
343 out.header.stamp = msg->header.stamp;
344 if ((uint16_t)ptr->
ANGLE == 0x8000) {
345 out.steering_wheel_angle = NAN;
347 out.steering_wheel_angle = (float)ptr->
ANGLE * (
float)(0.1 * M_PI / 180);
349 out.steering_wheel_cmd_type = ptr->
TMODE ? dbw_mkz_msgs::SteeringReport::CMD_TORQUE : dbw_mkz_msgs::SteeringReport::CMD_ANGLE;
350 if ((uint16_t)ptr->
CMD == 0xC000) {
351 out.steering_wheel_cmd = NAN;
352 }
else if (out.steering_wheel_cmd_type == dbw_mkz_msgs::SteeringReport::CMD_ANGLE) {
353 out.steering_wheel_cmd = (float)ptr->
CMD * (
float)(0.1 * M_PI / 180);
355 out.steering_wheel_cmd = (float)ptr->
CMD / 128.0f;
357 if ((uint8_t)ptr->
TORQUE == 0x80) {
358 out.steering_wheel_torque = NAN;
360 out.steering_wheel_torque = (float)ptr->
TORQUE * (
float)0.0625;
362 if ((uint16_t)ptr->
VEH_VEL == 0x8000) {
365 out.speed = (float)ptr->
VEH_VEL * (
float)(0.01 / 3.6);
367 out.enabled = ptr->
ENABLED ? true :
false;
368 out.override = ptr->
OVERRIDE ? true :
false;
369 out.fault_wdc = ptr->
FLTWDC ? true :
false;
370 out.fault_bus1 = ptr->
FLTBUS1 ? true :
false;
371 out.fault_bus2 = ptr->
FLTBUS2 ? true :
false;
372 out.fault_calibration = ptr->
FLTCAL ? true :
false;
373 out.fault_power = ptr->
FLTPWR ? true :
false;
376 out.timeout = ptr->
TMOUT ? true :
false;
380 geometry_msgs::TwistStamped twist;
381 twist.header.stamp = out.header.stamp;
383 twist.twist.linear.x = out.speed;
391 ptr->
FLTBUS1 ?
"true, " :
"false,",
392 ptr->
FLTBUS2 ?
"true, " :
"false,",
393 ptr->
FLTPWR ?
"true" :
"false");
394 }
else if (ptr->
FLTCAL && (uint16_t)ptr->
ANGLE == 0x8000) {
395 ROS_WARN_THROTTLE(5.0,
"Steering calibration fault. Drive at least 25 mph for at least 10 seconds in a straight line.");
397 ROS_WARN_THROTTLE(5.0,
"Steering configuration fault. Contact support@dataspeedinc.com if not resolved in a few minutes.");
406 dbw_mkz_msgs::GearReport out;
407 out.header.stamp = msg->header.stamp;
408 out.state.gear = ptr->
STATE;
409 out.cmd.gear = ptr->
CMD;
410 out.ready = ptr->
READY ? true :
false;
411 out.override = ptr->
OVERRIDE ? true :
false;
412 out.fault_bus = ptr->
FLTBUS ? true :
false;
414 out.reject.value = ptr->
REJECT;
415 if (out.reject.value == dbw_mkz_msgs::GearReject::NONE) {
419 switch (out.reject.value) {
420 case dbw_mkz_msgs::GearReject::SHIFT_IN_PROGRESS:
421 ROS_WARN(
"Gear shift rejected: Shift in progress");
423 case dbw_mkz_msgs::GearReject::OVERRIDE:
424 ROS_WARN(
"Gear shift rejected: Override on brake, throttle, or steering");
426 case dbw_mkz_msgs::GearReject::ROTARY_LOW:
427 ROS_WARN(
"Gear shift rejected: Rotary shifter can't shift to Low");
429 case dbw_mkz_msgs::GearReject::ROTARY_PARK:
430 ROS_WARN(
"Gear shift rejected: Rotary shifter can't shift out of Park");
432 case dbw_mkz_msgs::GearReject::VEHICLE:
433 ROS_WARN(
"Gear shift rejected: Rejected by vehicle, try pressing the brakes");
435 case dbw_mkz_msgs::GearReject::UNSUPPORTED:
436 ROS_WARN(
"Gear shift rejected: Unsupported gear command");
438 case dbw_mkz_msgs::GearReject::FAULT:
439 ROS_WARN(
"Gear shift rejected: System in fault state");
458 dbw_mkz_msgs::Misc1Report out;
459 out.header.stamp = msg->header.stamp;
461 out.high_beam_headlights = ptr->
head_light_hi ? true :
false;
464 out.btn_cc_on = ptr->
btn_cc_on ? true :
false;
465 out.btn_cc_off = ptr->
btn_cc_off ? true :
false;
467 out.btn_cc_res = ptr->
btn_cc_res ? true :
false;
477 out.fault_bus = ptr->
FLTBUS ? true :
false;
483 out.door_hood = ptr->
door_hood ? true :
false;
484 out.door_trunk = ptr->
door_trunk ? true :
false;
489 out.btn_ld_ok = ptr->
btn_ld_ok ? true :
false;
490 out.btn_ld_up = ptr->
btn_ld_up ? true :
false;
496 out.btn_rd_ok = ptr->
btn_rd_ok ? true :
false;
497 out.btn_rd_up = ptr->
btn_rd_up ? true :
false;
503 out.btn_mute = ptr->
btn_mute ? true :
false;
504 out.btn_media = ptr->
btn_media ? true :
false;
505 out.btn_prev = ptr->
btn_prev ? true :
false;
506 out.btn_next = ptr->
btn_next ? true :
false;
507 out.btn_speak = ptr->
btn_speak ? true :
false;
514 out.outside_temperature = NAN;
523 dbw_mkz_msgs::WheelSpeedReport out;
524 out.header.stamp = msg->header.stamp;
528 out.front_left = (float)ptr->
front_left * 0.01f;
531 out.front_right = NAN;
535 if ((uint16_t)ptr->
rear_left == 0x8000) {
538 out.rear_left = (float)ptr->
rear_left * 0.01f;
541 out.rear_right = NAN;
543 out.rear_right = (float)ptr->
rear_right * 0.01f;
555 dbw_mkz_msgs::WheelPositionReport out;
556 out.header.stamp = msg->header.stamp;
568 dbw_mkz_msgs::TirePressureReport out;
569 out.header.stamp = msg->header.stamp;
576 out.front_right = NAN;
586 out.rear_right = NAN;
597 dbw_mkz_msgs::FuelLevelReport out;
598 out.header.stamp = msg->header.stamp;
601 out.battery_12v = (float)ptr->
battery_12v * 0.0625f;
603 out.odometer = (float)ptr->
odometer * 0.1f;
612 dbw_mkz_msgs::SurroundReport out;
613 out.header.stamp = msg->header.stamp;
614 out.cta_left_alert = ptr->
l_cta_alert ?
true :
false;
615 out.cta_right_alert = ptr->
r_cta_alert ?
true :
false;
619 out.blis_right_alert = ptr->
r_blis_alert ?
true :
false;
624 if (out.sonar_enabled) {
639 sensor_msgs::PointCloud2 cloud;
648 dbw_mkz_msgs::BrakeInfoReport out;
649 out.header.stamp = msg->header.stamp;
656 out.brake_torque_actual = NAN;
661 out.wheel_torque_actual = NAN;
663 out.wheel_torque_actual = (float)ptr->
wheel_torque * 4.0f;
666 out.accel_over_ground = NAN;
670 out.brake_pedal_qf.value = ptr->
bped_qf;
673 out.abs_active = ptr->
abs_active ? true :
false;
682 if (ptr->
bped_qf != dbw_mkz_msgs::QualityFactor::OK) {
691 dbw_mkz_msgs::ThrottleInfoReport out;
692 out.header.stamp = msg->header.stamp;
699 out.throttle_rate = NAN;
703 out.throttle_pedal_qf.value = ptr->
aped_qf;
706 out.engine_rpm = NAN;
708 out.engine_rpm = (float)ptr->
engine_rpm * 0.25f;
712 if ((uint16_t)ptr->
batt_curr == 0xE000) {
715 out.batt_curr = (float)ptr->
batt_curr * 0.0625f;
718 if (ptr->
aped_qf != dbw_mkz_msgs::QualityFactor::OK) {
727 dbw_mkz_msgs::DriverAssistReport out;
728 out.header.stamp = msg->header.stamp;
739 if (out.fcw_active) {
742 if (out.aeb_braking) {
757 ROS_WARN_ONCE_ID(module,
"Licensing: %s one or more features licensed as a counted trial. Visit https://www.dataspeedinc.com/products/maintenance-subscription/ to request a full license.", str_m);
760 ROS_WARN_ONCE_ID(module,
"Licensing: %s one or more feature licenses expired due to the firmware build date", str_m);
762 }
else if (module ==
M_STEER) {
782 ROS_INFO(
"Licensing: %s license string date: %s", str_m,
ldate_.c_str());
785 ROS_INFO_ONCE(
"Licensing: %s MAC: %02X:%02X:%02X:%02X:%02X:%02X", str_m,
786 ptr->
mac.addr0, ptr->
mac.addr1,
787 ptr->
mac.addr2, ptr->
mac.addr3,
788 ptr->
mac.addr4, ptr->
mac.addr5);
790 std::string &bdate =
bdate_[module];
791 if (bdate.size() == 0) {
792 bdate.push_back(ptr->
bdate0.date0);
793 bdate.push_back(ptr->
bdate0.date1);
794 bdate.push_back(ptr->
bdate0.date2);
795 bdate.push_back(ptr->
bdate0.date3);
796 bdate.push_back(ptr->
bdate0.date4);
797 bdate.push_back(ptr->
bdate0.date5);
800 std::string &bdate =
bdate_[module];
801 if (bdate.size() == 6) {
802 bdate.push_back(ptr->
bdate1.date6);
803 bdate.push_back(ptr->
bdate1.date7);
804 bdate.push_back(ptr->
bdate1.date8);
805 bdate.push_back(ptr->
bdate1.date9);
806 ROS_INFO(
"Licensing: %s firmware build date: %s", str_m, bdate.c_str());
809 if (
vin_.size() == 0) {
818 if (
vin_.size() == 6) {
827 if (
vin_.size() == 12) {
833 std_msgs::String msg; msg.data =
vin_;
837 }
else if ((LIC_MUX_F0 <= ptr->mux) && (ptr->
mux <=
LIC_MUX_F7)) {
838 constexpr std::array<const char*, 8>
NAME = {
"BASE",
"CONTROL",
"SENSORS",
"REMOTE",
"",
"",
"",
""};
839 constexpr std::array<bool, 8> WARN = {
true,
true,
true,
false,
true,
true,
true,
true};
841 const int id = module *
NAME.size() + i;
842 const std::string name = strcmp(
NAME[i],
"") ?
NAME[i] : std::string(1,
'0' + i);
844 ROS_INFO_ONCE_ID(
id,
"Licensing: %s feature '%s' enabled%s", str_m, name.c_str(), ptr->
license.trial ?
" as a counted trial" :
"");
845 }
else if (ptr->
ready && !WARN[i]) {
846 ROS_INFO_ONCE_ID(
id,
"Licensing: %s feature '%s' not licensed.", str_m, name.c_str());
847 }
else if (ptr->
ready) {
848 ROS_WARN_ONCE_ID(
id,
"Licensing: %s feature '%s' not licensed. Visit https://www.dataspeedinc.com/products/maintenance-subscription/ to request a license.", str_m, name.c_str());
851 ROS_INFO_ONCE(
"Licensing: Feature '%s' trials used: %u, remaining: %u", name.c_str(),
867 if (latest.
valid()) {
870 ROS_WARN(
"Detected %s %s firmware version %u.%u.%u, which is unsupported. Platform: 0x%02X, Module: %u", str_p, str_m,
873 if (version < latest) {
874 ROS_WARN(
"Firmware %s %s has old version %u.%u.%u, updating to %u.%u.%u is suggested.", str_p, str_m,
875 version.v.major(), version.v.minor(), version.v.build(),
884 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Brake. Id: 0x%03X",
ID_BRAKE_CMD);
888 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Throttle. Id: 0x%03X",
ID_THROTTLE_CMD);
892 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Steering. Id: 0x%03X",
ID_STEERING_CMD);
896 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Shifting. Id: 0x%03X",
ID_GEAR_CMD);
902 case 0x100 ... 0x103:
903 case 0x6C0 ... 0x6C5:
904 ROS_WARN_ONCE_ID(msg->id,
"Received unsupported CAN ID %03X from next-generation drive-by-wire system (DBW2)"
905 "\nUse the ROS2 ds_dbw_can package instead", msg->id);
910 ROS_INFO(
"ena: %s, clr: %s, brake: %s, throttle: %s, steering: %s, gear: %s",
912 clear() ?
"true " :
"false",
928 sensor_msgs::Imu out;
929 out.header.stamp = msgs[0]->header.stamp;
931 out.orientation_covariance[0] = -1;
932 if ((uint16_t)ptr_accel->
accel_long == 0x8000) {
933 out.linear_acceleration.x = NAN;
935 out.linear_acceleration.x = (double)ptr_accel->
accel_long * 0.01;
937 if ((uint16_t)ptr_accel->
accel_lat == 0x8000) {
938 out.linear_acceleration.y = NAN;
940 out.linear_acceleration.y = (double)ptr_accel->
accel_lat * -0.01;
942 if ((uint16_t)ptr_accel->
accel_vert == 0x8000) {
943 out.linear_acceleration.z = NAN;
945 out.linear_acceleration.z = (double)ptr_accel->
accel_vert * -0.01;
947 if ((uint16_t)ptr_gyro->gyro_roll == 0x8000) {
948 out.angular_velocity.x = NAN;
950 out.angular_velocity.x = (double)ptr_gyro->gyro_roll * 0.0002;
952 if ((uint16_t)ptr_gyro->gyro_yaw == 0x8000) {
953 out.angular_velocity.z = NAN;
955 out.angular_velocity.z = (double)ptr_gyro->gyro_yaw * 0.0002;
960 ROS_INFO(
"Time: %u.%u, %u.%u, delta: %fms",
961 msgs[0]->
header.stamp.sec, msgs[0]->header.stamp.nsec,
962 msgs[1]->header.stamp.sec, msgs[1]->header.stamp.nsec,
963 labs((msgs[1]->
header.stamp - msgs[0]->header.stamp).toNSec()) / 1000000.0);
977 sensor_msgs::NavSatFix msg_fix;
978 msg_fix.header.stamp = msgs[0]->header.stamp;
979 msg_fix.latitude = (
double)ptr1->
latitude / 3e6;
980 msg_fix.longitude = (double)ptr1->
longitude / 3e6;
981 msg_fix.altitude = (
double)ptr3->
altitude * 0.25;
982 msg_fix.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
983 msg_fix.status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
987 msg_fix.status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
991 msg_fix.status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
996 geometry_msgs::TwistStamped msg_vel;
997 msg_vel.header.stamp = msgs[0]->header.stamp;
998 double heading = (double)ptr3->
heading * (0.01 * M_PI / 180);
999 double speed = (double)ptr3->
speed * 0.44704;
1000 msg_vel.twist.linear.x = cos(heading) * speed;
1001 msg_vel.twist.linear.y = sin(heading) * speed;
1004 sensor_msgs::TimeReference msg_time;
1005 struct tm unix_time;
1006 unix_time.tm_year = ptr2->utc_year + 100;
1007 unix_time.tm_mon = ptr2->utc_month - 1;
1008 unix_time.tm_mday = ptr2->utc_day;
1009 unix_time.tm_hour = ptr2->utc_hours;
1010 unix_time.tm_min = ptr2->utc_minutes;
1011 unix_time.tm_sec = ptr2->utc_seconds;
1012 msg_time.header.stamp = msgs[0]->header.stamp;
1013 msg_time.time_ref.sec = timegm(&unix_time);
1014 msg_time.time_ref.nsec = 0;
1018 ROS_INFO(
"UTC Time: %04d-%02d-%02d %02d:%02d:%02d",
1019 2000 + ptr2->utc_year, ptr2->utc_month, ptr2->utc_day,
1020 ptr2->utc_hours, ptr2->utc_minutes, ptr2->utc_seconds);
1024 ROS_INFO(
"Time: %u.%u, %u.%u, %u.%u, delta: %fms",
1025 msgs[0]->
header.stamp.sec, msgs[0]->header.stamp.nsec,
1026 msgs[1]->header.stamp.sec, msgs[1]->header.stamp.nsec,
1027 msgs[2]->header.stamp.sec, msgs[2]->header.stamp.nsec,
1029 labs((msgs[1]->
header.stamp - msgs[0]->header.stamp).toNSec()),
1030 labs((msgs[2]->
header.stamp - msgs[1]->header.stamp).toNSec())),
1031 labs((msgs[0]->
header.stamp - msgs[2]->header.stamp).toNSec())) / 1000000.0);
1037 can_msgs::Frame out;
1039 out.is_extended =
false;
1042 memset(ptr, 0x00,
sizeof(*ptr));
1048 switch (msg->pedal_cmd_type) {
1049 case dbw_mkz_msgs::BrakeCmd::CMD_NONE:
1051 case dbw_mkz_msgs::BrakeCmd::CMD_PEDAL:
1052 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1053 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
1058 case dbw_mkz_msgs::BrakeCmd::CMD_PERCENT:
1060 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PERCENT;
1061 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
1063 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1067 case dbw_mkz_msgs::BrakeCmd::CMD_TORQUE:
1069 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE;
1070 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1072 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1076 ROS_WARN_THROTTLE(1.0,
"Module ABS does not support brake command type TORQUE");
1079 case dbw_mkz_msgs::BrakeCmd::CMD_TORQUE_RQ:
1080 if (fwd_abs || fwd_bpe) {
1083 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE_RQ;
1084 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1087 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE;
1088 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1091 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1095 ROS_WARN_THROTTLE(1.0,
"Module ABS does not support brake command type TORQUE_RQ");
1098 case dbw_mkz_msgs::BrakeCmd::CMD_DECEL:
1100 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_DECEL;
1101 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd * 1e3f, 0, 10e3);
1103 ROS_WARN_THROTTLE(1.0,
"Module BPEC does not support brake command type DECEL");
1107 ROS_WARN(
"Unknown brake command type: %u", msg->pedal_cmd_type);
1110 #if 1 // Manually implement auto BOO control (brake lights) for legacy firmware
1114 const uint16_t BOO_THRESH_LO = 0.20 * UINT16_MAX;
1115 const uint16_t BOO_THRESH_HI = 0.22 * UINT16_MAX;
1116 static bool boo_status_ =
false;
1120 if (!boo_status_ && (ptr->
PCMD > BOO_THRESH_HI)) {
1123 }
else if (boo_status_ && (ptr->
PCMD < BOO_THRESH_LO)) {
1125 boo_status_ =
false;
1129 if (
enabled() && msg->enable) {
1132 if (
clear() || msg->clear) {
1138 ptr->
COUNT = msg->count;
1144 can_msgs::Frame out;
1146 out.is_extended =
false;
1149 memset(ptr, 0x00,
sizeof(*ptr));
1153 switch (msg->pedal_cmd_type) {
1154 case dbw_mkz_msgs::ThrottleCmd::CMD_NONE:
1156 case dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL:
1157 ptr->
CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL;
1158 cmd = msg->pedal_cmd;
1160 case dbw_mkz_msgs::ThrottleCmd::CMD_PERCENT:
1162 ptr->
CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PERCENT;
1163 cmd = msg->pedal_cmd;
1165 ptr->
CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL;
1170 ROS_WARN(
"Unknown throttle command type: %u", msg->pedal_cmd_type);
1173 ptr->
PCMD = std::clamp<float>(
cmd * UINT16_MAX, 0, UINT16_MAX);
1174 if (
enabled() && msg->enable) {
1177 if (
clear() || msg->clear) {
1183 ptr->
COUNT = msg->count;
1189 can_msgs::Frame out;
1191 out.is_extended =
false;
1194 memset(ptr, 0x00,
sizeof(*ptr));
1195 switch (msg->cmd_type) {
1196 case dbw_mkz_msgs::SteeringCmd::CMD_ANGLE:
1197 ptr->
SCMD = std::clamp<float>(msg->steering_wheel_angle_cmd * (
float)(180 / M_PI * 10), -INT16_MAX, INT16_MAX);
1198 if (fabsf(msg->steering_wheel_angle_velocity) > 0) {
1200 ptr->
SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (
float)(180 / M_PI / 4)), 1, 254);
1202 ptr->
SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (
float)(180 / M_PI / 2)), 1, 254);
1205 ptr->
CMD_TYPE = dbw_mkz_msgs::SteeringCmd::CMD_ANGLE;
1207 case dbw_mkz_msgs::SteeringCmd::CMD_TORQUE:
1208 ptr->
SCMD = std::clamp<float>(msg->steering_wheel_torque_cmd * 128, -INT16_MAX, INT16_MAX);
1209 ptr->
CMD_TYPE = dbw_mkz_msgs::SteeringCmd::CMD_TORQUE;
1211 ROS_WARN_THROTTLE(1.0,
"Module STEER does not support steering command type TORQUE");
1215 ROS_WARN(
"Unknown steering command type: %u", msg->cmd_type);
1218 if (
enabled() && msg->enable) {
1221 if (
clear() || msg->clear) {
1233 ptr->
COUNT = msg->count;
1239 can_msgs::Frame out;
1241 out.is_extended =
false;
1244 memset(ptr, 0x00,
sizeof(*ptr));
1246 ptr->
GCMD = msg->cmd.gear;
1248 if (
clear() || msg->clear) {
1256 can_msgs::Frame out;
1258 out.is_extended =
false;
1261 memset(ptr, 0x00,
sizeof(*ptr));
1263 ptr->
TRNCMD = msg->cmd.value;
1273 if (change || force) {
1286 ROS_WARN(
"DBW system enable status changed unexpectedly");
1291 can_msgs::Frame out;
1292 out.is_extended =
false;
1297 memset(out.data.elems, 0x00, 8);
1305 memset(out.data.elems, 0x00, 8);
1313 memset(out.data.elems, 0x00, 8);
1321 memset(out.data.elems, 0x00, 8);
1333 ROS_WARN(
"DBW system not enabled. Steering calibration fault.");
1336 ROS_WARN(
"DBW system not enabled. Braking fault.");
1339 ROS_WARN(
"DBW system not enabled. Throttle fault.");
1342 ROS_WARN(
"DBW system not enabled. Steering fault.");
1345 ROS_WARN(
"DBW system not enabled. Watchdog fault.");
1352 ROS_INFO(
"DBW system enable requested. Waiting for ready.");
1372 ROS_WARN(
"DBW system disabled. Cancel button pressed.");
1379 if (en && timeout) {
1382 if (en &&
override) {
1388 ROS_WARN(
"DBW system disabled. Driver override on brake/throttle pedal.");
1398 if (en && timeout) {
1401 if (en &&
override) {
1407 ROS_WARN(
"DBW system disabled. Driver override on brake/throttle pedal.");
1417 if (en && timeout) {
1420 if (en &&
override) {
1426 ROS_WARN(
"DBW system disabled. Driver override on steering wheel.");
1436 if (en &&
override) {
1442 ROS_WARN(
"DBW system disabled. Driver override on shifter.");
1452 ROS_WARN(
"Brake subsystem disabled after 100ms command timeout");
1461 ROS_WARN(
"Throttle subsystem disabled after 100ms command timeout");
1470 ROS_WARN(
"Steering subsystem disabled after 100ms command timeout");
1485 ROS_ERROR(
"DBW system disabled. Braking fault.");
1501 ROS_ERROR(
"DBW system disabled. Throttle fault.");
1517 ROS_ERROR(
"DBW system disabled. Steering fault.");
1533 ROS_ERROR(
"DBW system disabled. Steering calibration fault.");
1549 ROS_ERROR(
"DBW system disabled. Watchdog fault.");
1555 ROS_WARN(
"Watchdog event: Alerting driver and applying brakes.");
1557 ROS_INFO(
"Watchdog event: Driver has successfully taken control.");
1561 case dbw_mkz_msgs::WatchdogCounter::OTHER_BRAKE:
1562 ROS_WARN(
"Watchdog event: Fault determined by brake controller");
1564 case dbw_mkz_msgs::WatchdogCounter::OTHER_THROTTLE:
1565 ROS_WARN(
"Watchdog event: Fault determined by throttle controller");
1567 case dbw_mkz_msgs::WatchdogCounter::OTHER_STEERING:
1568 ROS_WARN(
"Watchdog event: Fault determined by steering controller");
1570 case dbw_mkz_msgs::WatchdogCounter::BRAKE_COUNTER:
1571 ROS_WARN(
"Watchdog event: Brake command counter failed to increment");
1573 case dbw_mkz_msgs::WatchdogCounter::BRAKE_DISABLED:
1574 ROS_WARN(
"Watchdog event: Brake transition to disabled while in gear or moving");
1576 case dbw_mkz_msgs::WatchdogCounter::BRAKE_COMMAND:
1577 ROS_WARN(
"Watchdog event: Brake command timeout after 100ms");
1579 case dbw_mkz_msgs::WatchdogCounter::BRAKE_REPORT:
1580 ROS_WARN(
"Watchdog event: Brake report timeout after 100ms");
1582 case dbw_mkz_msgs::WatchdogCounter::THROTTLE_COUNTER:
1583 ROS_WARN(
"Watchdog event: Throttle command counter failed to increment");
1585 case dbw_mkz_msgs::WatchdogCounter::THROTTLE_DISABLED:
1586 ROS_WARN(
"Watchdog event: Throttle transition to disabled while in gear or moving");
1588 case dbw_mkz_msgs::WatchdogCounter::THROTTLE_COMMAND:
1589 ROS_WARN(
"Watchdog event: Throttle command timeout after 100ms");
1591 case dbw_mkz_msgs::WatchdogCounter::THROTTLE_REPORT:
1592 ROS_WARN(
"Watchdog event: Throttle report timeout after 100ms");
1594 case dbw_mkz_msgs::WatchdogCounter::STEERING_COUNTER:
1595 ROS_WARN(
"Watchdog event: Steering command counter failed to increment");
1597 case dbw_mkz_msgs::WatchdogCounter::STEERING_DISABLED:
1598 ROS_WARN(
"Watchdog event: Steering transition to disabled while in gear or moving");
1600 case dbw_mkz_msgs::WatchdogCounter::STEERING_COMMAND:
1601 ROS_WARN(
"Watchdog event: Steering command timeout after 100ms");
1603 case dbw_mkz_msgs::WatchdogCounter::STEERING_REPORT:
1604 ROS_WARN(
"Watchdog event: Steering report timeout after 100ms");
1608 }
else if (!
fault) {
1613 ROS_WARN_THROTTLE(2.0,
"Watchdog event: Press left OK button on the steering wheel or cycle power to clear event.");
1623 double dt = (stamp -
joint_state_.header.stamp).toSec();
1625 if (std::isfinite(wheels->front_left)) {
1628 if (std::isfinite(wheels->front_right)) {
1631 if (std::isfinite(wheels->rear_left)) {
1634 if (std::isfinite(wheels->rear_right)) {
1639 if (std::isfinite(steering->steering_wheel_angle)) {
1642 const double r = L / tan(steering->steering_wheel_angle /
steering_ratio_);