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__) 240 if (!msg->is_rtr && !msg->is_error && !msg->is_extended) {
247 dbw_mkz_msgs::BrakeReport out;
248 out.header.stamp = msg->header.stamp;
251 out.pedal_input = (float)ptr->
PI / UINT16_MAX;
252 out.pedal_cmd = (
float)ptr->
PC / UINT16_MAX;
253 out.pedal_output = (float)ptr->
PO / UINT16_MAX;
259 out.torque_input = ptr->
PI;
260 out.decel_cmd = ptr->
PC * 1e-3
f;
261 out.decel_output = ptr->
PO * 1e-3f;
262 }
else if (ptr->
BTYPE == 2) {
264 out.torque_input = ptr->
PI;
265 out.torque_cmd = ptr->
PC;
266 out.torque_output = ptr->
PO;
270 out.boo_cmd = ptr->
BC ?
true :
false;
271 out.enabled = ptr->
ENABLED ?
true :
false;
272 out.override = ptr->
OVERRIDE ?
true :
false;
273 out.driver = ptr->
DRIVER ?
true :
false;
274 out.watchdog_counter.source = ptr->
WDCSRC;
275 out.watchdog_braking = ptr->
WDCBRK ?
true :
false;
276 out.fault_wdc = ptr->
FLTWDC ?
true :
false;
277 out.fault_ch1 = ptr->
FLT1 ?
true :
false;
278 out.fault_ch2 = ptr->
FLT2 ?
true :
false;
279 out.fault_power = ptr->
FLTPWR ?
true :
false;
282 out.timeout = ptr->
TMOUT ?
true :
false;
288 ptr->
FLT1 ?
"true, " :
"false,",
289 ptr->
FLT2 ?
"true, " :
"false,",
290 ptr->
FLTPWR ?
"true" :
"false");
300 dbw_mkz_msgs::ThrottleReport out;
301 out.header.stamp = msg->header.stamp;
302 out.pedal_input = (float)ptr->
PI / UINT16_MAX;
303 out.pedal_cmd = (
float)ptr->
PC / UINT16_MAX;
304 out.pedal_output = (float)ptr->
PO / UINT16_MAX;
305 out.enabled = ptr->
ENABLED ?
true :
false;
306 out.override = ptr->
OVERRIDE ?
true :
false;
307 out.driver = ptr->
DRIVER ?
true :
false;
308 out.watchdog_counter.source = ptr->
WDCSRC;
309 out.fault_wdc = ptr->
FLTWDC ?
true :
false;
310 out.fault_ch1 = ptr->
FLT1 ?
true :
false;
311 out.fault_ch2 = ptr->
FLT2 ?
true :
false;
312 out.fault_power = ptr->
FLTPWR ?
true :
false;
315 out.timeout = ptr->
TMOUT ?
true :
false;
321 ptr->
FLT1 ?
"true, " :
"false,",
322 ptr->
FLT2 ?
"true, " :
"false,",
323 ptr->
FLTPWR ?
"true" :
"false");
334 dbw_mkz_msgs::SteeringReport out;
335 out.header.stamp = msg->header.stamp;
336 if ((uint16_t)ptr->
ANGLE == 0x8000) {
337 out.steering_wheel_angle = NAN;
339 out.steering_wheel_angle = (float)ptr->
ANGLE * (
float)(0.1 * M_PI / 180);
341 out.steering_wheel_cmd_type = ptr->
TMODE ? dbw_mkz_msgs::SteeringReport::CMD_TORQUE : dbw_mkz_msgs::SteeringReport::CMD_ANGLE;
342 if ((uint16_t)ptr->
CMD == 0xC000) {
343 out.steering_wheel_cmd = NAN;
344 }
else if (out.steering_wheel_cmd_type == dbw_mkz_msgs::SteeringReport::CMD_ANGLE) {
345 out.steering_wheel_cmd = (float)ptr->
CMD * (
float)(0.1 * M_PI / 180);
347 out.steering_wheel_cmd = (float)ptr->
CMD / 128.0f;
349 if ((uint8_t)ptr->
TORQUE == 0x80) {
350 out.steering_wheel_torque = NAN;
352 out.steering_wheel_torque = (float)ptr->
TORQUE * (
float)0.0625;
354 if (ptr->
SPEED == 0xFFFF) {
357 out.speed = (float)ptr->
SPEED * (
float)(0.01 / 3.6) * (float)
speedSign();
359 out.enabled = ptr->
ENABLED ?
true :
false;
360 out.override = ptr->
OVERRIDE ?
true :
false;
361 out.fault_wdc = ptr->
FLTWDC ?
true :
false;
362 out.fault_bus1 = ptr->
FLTBUS1 ?
true :
false;
363 out.fault_bus2 = ptr->
FLTBUS2 ?
true :
false;
364 out.fault_calibration = ptr->
FLTCAL ?
true :
false;
365 out.fault_power = ptr->
FLTPWR ?
true :
false;
368 out.timeout = ptr->
TMOUT ?
true :
false;
372 geometry_msgs::TwistStamped twist;
373 twist.header.stamp = out.header.stamp;
375 twist.twist.linear.x = out.speed;
383 ptr->
FLTBUS1 ?
"true, " :
"false,",
384 ptr->
FLTBUS2 ?
"true, " :
"false,",
385 ptr->
FLTPWR ?
"true" :
"false");
387 ROS_WARN_THROTTLE(5.0,
"Steering calibration fault. Drive at least 25 mph for at least 10 seconds in a straight line.");
396 dbw_mkz_msgs::GearReport out;
397 out.header.stamp = msg->header.stamp;
398 out.state.gear = ptr->
STATE;
399 out.cmd.gear = ptr->
CMD;
400 out.override = ptr->
OVERRIDE ?
true :
false;
401 out.fault_bus = ptr->
FLTBUS ?
true :
false;
403 out.reject.value = ptr->
REJECT;
404 if (out.reject.value == dbw_mkz_msgs::GearReject::NONE) {
408 switch (out.reject.value) {
409 case dbw_mkz_msgs::GearReject::SHIFT_IN_PROGRESS:
410 ROS_WARN(
"Gear shift rejected: Shift in progress");
412 case dbw_mkz_msgs::GearReject::OVERRIDE:
413 ROS_WARN(
"Gear shift rejected: Override on brake, throttle, or steering");
415 case dbw_mkz_msgs::GearReject::ROTARY_LOW:
416 ROS_WARN(
"Gear shift rejected: Rotary shifter can't shift to Low");
418 case dbw_mkz_msgs::GearReject::ROTARY_PARK:
419 ROS_WARN(
"Gear shift rejected: Rotary shifter can't shift out of Park");
421 case dbw_mkz_msgs::GearReject::VEHICLE:
422 ROS_WARN(
"Gear shift rejected: Rejected by vehicle, try pressing the brakes");
424 case dbw_mkz_msgs::GearReject::UNSUPPORTED:
425 ROS_WARN(
"Gear shift rejected: Unsupported gear command");
427 case dbw_mkz_msgs::GearReject::FAULT:
428 ROS_WARN(
"Gear shift rejected: System in fault state");
447 dbw_mkz_msgs::Misc1Report out;
448 out.header.stamp = msg->header.stamp;
450 out.high_beam_headlights = ptr->
head_light_hi ?
true :
false;
453 out.btn_cc_on = ptr->
btn_cc_on ?
true :
false;
454 out.btn_cc_off = ptr->
btn_cc_off ?
true :
false;
456 out.btn_cc_res = ptr->
btn_cc_res ?
true :
false;
466 out.fault_bus = ptr->
FLTBUS ?
true :
false;
472 out.door_hood = ptr->
door_hood ?
true :
false;
473 out.door_trunk = ptr->
door_trunk ?
true :
false;
478 out.btn_ld_ok = ptr->
btn_ld_ok ?
true :
false;
479 out.btn_ld_up = ptr->
btn_ld_up ?
true :
false;
485 out.btn_rd_ok = ptr->
btn_rd_ok ?
true :
false;
486 out.btn_rd_up = ptr->
btn_rd_up ?
true :
false;
492 out.btn_mute = ptr->
btn_mute ?
true :
false;
493 out.btn_media = ptr->
btn_media ?
true :
false;
494 out.btn_prev = ptr->
btn_prev ?
true :
false;
495 out.btn_next = ptr->
btn_next ?
true :
false;
496 out.btn_speak = ptr->
btn_speak ?
true :
false;
503 out.outside_temperature = NAN;
512 dbw_mkz_msgs::WheelSpeedReport out;
513 out.header.stamp = msg->header.stamp;
517 out.front_left = (float)ptr->
front_left * 0.01f;
520 out.front_right = NAN;
524 if ((uint16_t)ptr->
rear_left == 0x8000) {
527 out.rear_left = (float)ptr->
rear_left * 0.01f;
530 out.rear_right = NAN;
532 out.rear_right = (float)ptr->
rear_right * 0.01f;
544 dbw_mkz_msgs::WheelPositionReport out;
545 out.header.stamp = msg->header.stamp;
557 dbw_mkz_msgs::TirePressureReport out;
558 out.header.stamp = msg->header.stamp;
565 out.front_right = NAN;
575 out.rear_right = NAN;
586 dbw_mkz_msgs::FuelLevelReport out;
587 out.header.stamp = msg->header.stamp;
590 out.battery_12v = (float)ptr->
battery_12v * 0.0625f;
592 out.odometer = (float)ptr->
odometer * 0.1f;
601 dbw_mkz_msgs::SurroundReport out;
602 out.header.stamp = msg->header.stamp;
603 out.cta_left_alert = ptr->
l_cta_alert ?
true :
false;
604 out.cta_right_alert = ptr->
r_cta_alert ?
true :
false;
608 out.blis_right_alert = ptr->
r_blis_alert ?
true :
false;
613 if (out.sonar_enabled) {
628 sensor_msgs::PointCloud2 cloud;
637 dbw_mkz_msgs::BrakeInfoReport out;
638 out.header.stamp = msg->header.stamp;
645 out.brake_torque_actual = NAN;
650 out.wheel_torque_actual = NAN;
652 out.wheel_torque_actual = (float)ptr->
wheel_torque * 4.0f;
655 out.accel_over_ground = NAN;
659 out.brake_pedal_qf.value = ptr->
bped_qf;
662 out.abs_active = ptr->
abs_active ?
true :
false;
671 if (ptr->
bped_qf != dbw_mkz_msgs::QualityFactor::OK) {
680 dbw_mkz_msgs::ThrottleInfoReport out;
681 out.header.stamp = msg->header.stamp;
688 out.throttle_rate = NAN;
692 out.throttle_pedal_qf.value = ptr->
aped_qf;
694 out.engine_rpm = NAN;
696 out.engine_rpm = (float)ptr->
engine_rpm * 0.25f;
699 if ((uint16_t)ptr->
batt_curr == 0xE000) {
702 out.batt_curr = (float)ptr->
batt_curr * 0.0625f;
705 if (ptr->
aped_qf != dbw_mkz_msgs::QualityFactor::OK) {
714 dbw_mkz_msgs::DriverAssistReport out;
715 out.header.stamp = msg->header.stamp;
726 if (out.fcw_active) {
729 if (out.aeb_braking) {
744 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);
747 ROS_WARN_ONCE_ID(module,
"Licensing: %s one or more feature licenses expired due to the firmware build date", str_m);
749 }
else if (module ==
M_STEER) {
769 ROS_INFO(
"Licensing: %s license string date: %s", str_m,
ldate_.c_str());
772 ROS_INFO_ONCE(
"Licensing: %s MAC: %02X:%02X:%02X:%02X:%02X:%02X", str_m,
773 ptr->
mac.addr0, ptr->
mac.addr1,
774 ptr->
mac.addr2, ptr->
mac.addr3,
775 ptr->
mac.addr4, ptr->
mac.addr5);
777 std::string &bdate =
bdate_[module];
778 if (bdate.size() == 0) {
779 bdate.push_back(ptr->
bdate0.date0);
780 bdate.push_back(ptr->
bdate0.date1);
781 bdate.push_back(ptr->
bdate0.date2);
782 bdate.push_back(ptr->
bdate0.date3);
783 bdate.push_back(ptr->
bdate0.date4);
784 bdate.push_back(ptr->
bdate0.date5);
787 std::string &bdate =
bdate_[module];
788 if (bdate.size() == 6) {
789 bdate.push_back(ptr->
bdate1.date6);
790 bdate.push_back(ptr->
bdate1.date7);
791 bdate.push_back(ptr->
bdate1.date8);
792 bdate.push_back(ptr->
bdate1.date9);
793 ROS_INFO(
"Licensing: %s firmware build date: %s", str_m, bdate.c_str());
796 if (
vin_.size() == 0) {
805 if (
vin_.size() == 6) {
814 if (
vin_.size() == 12) {
820 std_msgs::String msg; msg.data =
vin_;
824 }
else if ((LIC_MUX_F0 <= ptr->mux) && (ptr->
mux <=
LIC_MUX_F7)) {
825 constexpr std::array<const char*, 8>
NAME = {
"BASE",
"CONTROL",
"SENSORS",
"",
"",
"",
"",
""};
827 const int id = module * NAME.size() + i;
829 ROS_INFO_ONCE_ID(
id,
"Licensing: %s feature '%s' enabled%s", str_m, NAME[i], ptr->
license.trial ?
" as a counted trial" :
"");
830 }
else if (ptr->
ready) {
831 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[i]);
834 ROS_INFO_ONCE(
"Licensing: Feature '%s' trials used: %u, remaining: %u", NAME[i],
850 if (latest.
valid()) {
853 ROS_WARN(
"Detected %s %s firmware version %u.%u.%u, which is unsupported. Platform: 0x%02X, Module: %u", str_p, str_m,
856 if (version < latest) {
857 ROS_WARN(
"Firmware %s %s has old version %u.%u.%u, updating to %u.%u.%u is suggested.", str_p, str_m,
858 version.v.major(), version.v.minor(), version.v.build(),
867 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Brake. Id: 0x%03X",
ID_BRAKE_CMD);
871 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Throttle. Id: 0x%03X",
ID_THROTTLE_CMD);
875 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Steering. Id: 0x%03X",
ID_STEERING_CMD);
879 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Shifting. Id: 0x%03X",
ID_GEAR_CMD);
887 ROS_INFO(
"ena: %s, clr: %s, brake: %s, throttle: %s, steering: %s, gear: %s",
889 clear() ?
"true " :
"false",
905 sensor_msgs::Imu out;
906 out.header.stamp = msgs[0]->header.stamp;
908 out.orientation_covariance[0] = -1;
909 if ((uint16_t)ptr_accel->
accel_long == 0x8000) {
910 out.linear_acceleration.x = NAN;
912 out.linear_acceleration.x = (double)ptr_accel->
accel_long * 0.01;
914 if ((uint16_t)ptr_accel->
accel_lat == 0x8000) {
915 out.linear_acceleration.y = NAN;
917 out.linear_acceleration.y = (double)ptr_accel->
accel_lat * -0.01;
919 if ((uint16_t)ptr_accel->
accel_vert == 0x8000) {
920 out.linear_acceleration.z = NAN;
922 out.linear_acceleration.z = (double)ptr_accel->
accel_vert * -0.01;
924 if ((uint16_t)ptr_gyro->gyro_roll == 0x8000) {
925 out.angular_velocity.x = NAN;
927 out.angular_velocity.x = (double)ptr_gyro->gyro_roll * 0.0002;
929 if ((uint16_t)ptr_gyro->gyro_yaw == 0x8000) {
930 out.angular_velocity.z = NAN;
932 out.angular_velocity.z = (double)ptr_gyro->gyro_yaw * 0.0002;
937 ROS_INFO(
"Time: %u.%u, %u.%u, delta: %fms",
938 msgs[0]->header.stamp.sec, msgs[0]->header.stamp.nsec,
939 msgs[1]->header.stamp.sec, msgs[1]->header.stamp.nsec,
940 labs((msgs[1]->header.stamp - msgs[0]->header.stamp).toNSec()) / 1000000.0);
954 sensor_msgs::NavSatFix msg_fix;
955 msg_fix.header.stamp = msgs[0]->header.stamp;
956 msg_fix.latitude = (
double)ptr1->
latitude / 3e6;
957 msg_fix.longitude = (double)ptr1->
longitude / 3e6;
958 msg_fix.altitude = (
double)ptr3->
altitude * 0.25;
959 msg_fix.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
960 msg_fix.status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
964 msg_fix.status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
968 msg_fix.status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
973 geometry_msgs::TwistStamped msg_vel;
974 msg_vel.header.stamp = msgs[0]->header.stamp;
975 double heading = (double)ptr3->
heading * (0.01 * M_PI / 180);
976 double speed = (double)ptr3->
speed * 0.44704;
977 msg_vel.twist.linear.x =
cos(heading) * speed;
978 msg_vel.twist.linear.y =
sin(heading) * speed;
981 sensor_msgs::TimeReference msg_time;
983 unix_time.tm_year = ptr2->utc_year + 100;
984 unix_time.tm_mon = ptr2->utc_month - 1;
985 unix_time.tm_mday = ptr2->utc_day;
986 unix_time.tm_hour = ptr2->utc_hours;
987 unix_time.tm_min = ptr2->utc_minutes;
988 unix_time.tm_sec = ptr2->utc_seconds;
989 msg_time.header.stamp = msgs[0]->header.stamp;
990 msg_time.time_ref.sec = timegm(&unix_time);
991 msg_time.time_ref.nsec = 0;
995 ROS_INFO(
"UTC Time: %04d-%02d-%02d %02d:%02d:%02d",
996 2000 + ptr2->utc_year, ptr2->utc_month, ptr2->utc_day,
997 ptr2->utc_hours, ptr2->utc_minutes, ptr2->utc_seconds);
1001 ROS_INFO(
"Time: %u.%u, %u.%u, %u.%u, delta: %fms",
1002 msgs[0]->header.stamp.sec, msgs[0]->header.stamp.nsec,
1003 msgs[1]->header.stamp.sec, msgs[1]->header.stamp.nsec,
1004 msgs[2]->header.stamp.sec, msgs[2]->header.stamp.nsec,
1006 labs((msgs[1]->header.stamp - msgs[0]->header.stamp).toNSec()),
1007 labs((msgs[2]->header.stamp - msgs[1]->header.stamp).toNSec())),
1008 labs((msgs[0]->header.stamp - msgs[2]->header.stamp).toNSec())) / 1000000.0);
1014 can_msgs::Frame out;
1016 out.is_extended =
false;
1019 memset(ptr, 0x00,
sizeof(*ptr));
1025 switch (msg->pedal_cmd_type) {
1026 case dbw_mkz_msgs::BrakeCmd::CMD_NONE:
1028 case dbw_mkz_msgs::BrakeCmd::CMD_PEDAL:
1029 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1030 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
1035 case dbw_mkz_msgs::BrakeCmd::CMD_PERCENT:
1037 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PERCENT;
1038 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
1040 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1044 case dbw_mkz_msgs::BrakeCmd::CMD_TORQUE:
1046 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE;
1047 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1049 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1053 ROS_WARN_THROTTLE(1.0,
"Module ABS does not support brake command type TORQUE");
1056 case dbw_mkz_msgs::BrakeCmd::CMD_TORQUE_RQ:
1057 if (fwd_abs || fwd_bpe) {
1060 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE_RQ;
1061 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1064 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE;
1065 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1068 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1072 ROS_WARN_THROTTLE(1.0,
"Module ABS does not support brake command type TORQUE_RQ");
1075 case dbw_mkz_msgs::BrakeCmd::CMD_DECEL:
1077 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_DECEL;
1078 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd * 1e3f, 0, 10e3);
1080 ROS_WARN_THROTTLE(1.0,
"Module BPEC does not support brake command type DECEL");
1084 ROS_WARN(
"Unknown brake command type: %u", msg->pedal_cmd_type);
1087 #if 1 // Manually implement auto BOO control (brake lights) for legacy firmware 1091 const uint16_t BOO_THRESH_LO = 0.20 * UINT16_MAX;
1092 const uint16_t BOO_THRESH_HI = 0.22 * UINT16_MAX;
1093 static bool boo_status_ =
false;
1097 if (!boo_status_ && (ptr->
PCMD > BOO_THRESH_HI)) {
1100 }
else if (boo_status_ && (ptr->
PCMD < BOO_THRESH_LO)) {
1102 boo_status_ =
false;
1106 if (
enabled() && msg->enable) {
1109 if (
clear() || msg->clear) {
1115 ptr->
COUNT = msg->count;
1121 can_msgs::Frame out;
1123 out.is_extended =
false;
1126 memset(ptr, 0x00,
sizeof(*ptr));
1130 switch (msg->pedal_cmd_type) {
1131 case dbw_mkz_msgs::ThrottleCmd::CMD_NONE:
1133 case dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL:
1134 ptr->
CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL;
1135 cmd = msg->pedal_cmd;
1137 case dbw_mkz_msgs::ThrottleCmd::CMD_PERCENT:
1139 ptr->
CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PERCENT;
1140 cmd = msg->pedal_cmd;
1142 ptr->
CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL;
1147 ROS_WARN(
"Unknown throttle command type: %u", msg->pedal_cmd_type);
1150 ptr->
PCMD = std::clamp<float>(cmd * UINT16_MAX, 0, UINT16_MAX);
1151 if (
enabled() && msg->enable) {
1154 if (
clear() || msg->clear) {
1160 ptr->
COUNT = msg->count;
1166 can_msgs::Frame out;
1168 out.is_extended =
false;
1171 memset(ptr, 0x00,
sizeof(*ptr));
1172 switch (msg->cmd_type) {
1173 case dbw_mkz_msgs::SteeringCmd::CMD_ANGLE:
1174 ptr->
SCMD = std::clamp<float>(msg->steering_wheel_angle_cmd * (float)(180 / M_PI * 10), -INT16_MAX, INT16_MAX);
1175 if (fabsf(msg->steering_wheel_angle_velocity) > 0) {
1177 ptr->
SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (
float)(180 / M_PI / 4)), 1, 254);
1179 ptr->
SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (
float)(180 / M_PI / 2)), 1, 254);
1182 ptr->
CMD_TYPE = dbw_mkz_msgs::SteeringCmd::CMD_ANGLE;
1184 case dbw_mkz_msgs::SteeringCmd::CMD_TORQUE:
1185 ptr->
SCMD = std::clamp<float>(msg->steering_wheel_torque_cmd * 128, -INT16_MAX, INT16_MAX);
1186 ptr->
CMD_TYPE = dbw_mkz_msgs::SteeringCmd::CMD_TORQUE;
1188 ROS_WARN_THROTTLE(1.0,
"Module STEER does not support steering command type TORQUE");
1192 ROS_WARN(
"Unknown steering command type: %u", msg->cmd_type);
1195 if (
enabled() && msg->enable) {
1198 if (
clear() || msg->clear) {
1207 ptr->
COUNT = msg->count;
1213 can_msgs::Frame out;
1215 out.is_extended =
false;
1218 memset(ptr, 0x00,
sizeof(*ptr));
1220 ptr->
GCMD = msg->cmd.gear;
1222 if (
clear() || msg->clear) {
1230 can_msgs::Frame out;
1232 out.is_extended =
false;
1235 memset(ptr, 0x00,
sizeof(*ptr));
1237 ptr->
TRNCMD = msg->cmd.value;
1244 bool change =
false;
1259 can_msgs::Frame out;
1260 out.is_extended =
false;
1265 memset(out.data.elems, 0x00, 8);
1273 memset(out.data.elems, 0x00, 8);
1281 memset(out.data.elems, 0x00, 8);
1289 memset(out.data.elems, 0x00, 8);
1301 ROS_WARN(
"DBW system not enabled. Steering calibration fault.");
1304 ROS_WARN(
"DBW system not enabled. Braking fault.");
1307 ROS_WARN(
"DBW system not enabled. Throttle fault.");
1310 ROS_WARN(
"DBW system not enabled. Steering fault.");
1313 ROS_WARN(
"DBW system not enabled. Watchdog fault.");
1320 ROS_INFO(
"DBW system enable requested. Waiting for ready.");
1340 ROS_WARN(
"DBW system disabled. Cancel button pressed.");
1347 if (en && timeout) {
1350 if (en &&
override) {
1356 ROS_WARN(
"DBW system disabled. Driver override on brake/throttle pedal.");
1366 if (en && timeout) {
1369 if (en &&
override) {
1375 ROS_WARN(
"DBW system disabled. Driver override on brake/throttle pedal.");
1385 if (en && timeout) {
1388 if (en &&
override) {
1394 ROS_WARN(
"DBW system disabled. Driver override on steering wheel.");
1404 if (en &&
override) {
1410 ROS_WARN(
"DBW system disabled. Driver override on shifter.");
1420 ROS_WARN(
"Brake subsystem disabled after 100ms command timeout");
1429 ROS_WARN(
"Throttle subsystem disabled after 100ms command timeout");
1438 ROS_WARN(
"Steering subsystem disabled after 100ms command timeout");
1453 ROS_ERROR(
"DBW system disabled. Braking fault.");
1469 ROS_ERROR(
"DBW system disabled. Throttle fault.");
1485 ROS_ERROR(
"DBW system disabled. Steering fault.");
1501 ROS_ERROR(
"DBW system disabled. Steering calibration fault.");
1517 ROS_ERROR(
"DBW system disabled. Watchdog fault.");
1523 ROS_WARN(
"Watchdog event: Alerting driver and applying brakes.");
1525 ROS_INFO(
"Watchdog event: Driver has successfully taken control.");
1529 case dbw_mkz_msgs::WatchdogCounter::OTHER_BRAKE:
1530 ROS_WARN(
"Watchdog event: Fault determined by brake controller");
1532 case dbw_mkz_msgs::WatchdogCounter::OTHER_THROTTLE:
1533 ROS_WARN(
"Watchdog event: Fault determined by throttle controller");
1535 case dbw_mkz_msgs::WatchdogCounter::OTHER_STEERING:
1536 ROS_WARN(
"Watchdog event: Fault determined by steering controller");
1538 case dbw_mkz_msgs::WatchdogCounter::BRAKE_COUNTER:
1539 ROS_WARN(
"Watchdog event: Brake command counter failed to increment");
1541 case dbw_mkz_msgs::WatchdogCounter::BRAKE_DISABLED:
1542 ROS_WARN(
"Watchdog event: Brake transition to disabled while in gear or moving");
1544 case dbw_mkz_msgs::WatchdogCounter::BRAKE_COMMAND:
1545 ROS_WARN(
"Watchdog event: Brake command timeout after 100ms");
1547 case dbw_mkz_msgs::WatchdogCounter::BRAKE_REPORT:
1548 ROS_WARN(
"Watchdog event: Brake report timeout after 100ms");
1550 case dbw_mkz_msgs::WatchdogCounter::THROTTLE_COUNTER:
1551 ROS_WARN(
"Watchdog event: Throttle command counter failed to increment");
1553 case dbw_mkz_msgs::WatchdogCounter::THROTTLE_DISABLED:
1554 ROS_WARN(
"Watchdog event: Throttle transition to disabled while in gear or moving");
1556 case dbw_mkz_msgs::WatchdogCounter::THROTTLE_COMMAND:
1557 ROS_WARN(
"Watchdog event: Throttle command timeout after 100ms");
1559 case dbw_mkz_msgs::WatchdogCounter::THROTTLE_REPORT:
1560 ROS_WARN(
"Watchdog event: Throttle report timeout after 100ms");
1562 case dbw_mkz_msgs::WatchdogCounter::STEERING_COUNTER:
1563 ROS_WARN(
"Watchdog event: Steering command counter failed to increment");
1565 case dbw_mkz_msgs::WatchdogCounter::STEERING_DISABLED:
1566 ROS_WARN(
"Watchdog event: Steering transition to disabled while in gear or moving");
1568 case dbw_mkz_msgs::WatchdogCounter::STEERING_COMMAND:
1569 ROS_WARN(
"Watchdog event: Steering command timeout after 100ms");
1571 case dbw_mkz_msgs::WatchdogCounter::STEERING_REPORT:
1572 ROS_WARN(
"Watchdog event: Steering report timeout after 100ms");
1576 }
else if (!fault) {
1581 ROS_WARN_THROTTLE(2.0,
"Watchdog event: Press left OK button on the steering wheel or cycle power to clear event.");
1591 double dt = (stamp -
joint_state_.header.stamp).toSec();
1593 if (std::isfinite(wheels->front_left)) {
1596 if (std::isfinite(wheels->front_right)) {
1599 if (std::isfinite(wheels->rear_left)) {
1602 if (std::isfinite(wheels->rear_right)) {
1607 if (std::isfinite(steering->steering_wheel_angle)) {
void recvSteeringCmd(const dbw_mkz_msgs::SteeringCmd::ConstPtr &msg)
ros::Publisher pub_wheel_positions_
PlatformMap FIRMWARE_LATEST({{PlatformVersion(P_FORD_CD4, M_BPEC, ModuleVersion(2, 4, 2))},{PlatformVersion(P_FORD_CD4, M_TPEC, ModuleVersion(2, 4, 2))},{PlatformVersion(P_FORD_CD4, M_STEER, ModuleVersion(2, 4, 2))},{PlatformVersion(P_FORD_CD4, M_SHIFT, ModuleVersion(2, 4, 2))},{PlatformVersion(P_FORD_CD5, M_BOO, ModuleVersion(1, 0, 0))},{PlatformVersion(P_FORD_CD5, M_TPEC, ModuleVersion(1, 0, 0))},{PlatformVersion(P_FORD_CD5, M_STEER, ModuleVersion(1, 0, 0))},{PlatformVersion(P_FORD_P5, M_TPEC, ModuleVersion(1, 3, 2))},{PlatformVersion(P_FORD_P5, M_STEER, ModuleVersion(1, 3, 2))},{PlatformVersion(P_FORD_P5, M_SHIFT, ModuleVersion(1, 3, 2))},{PlatformVersion(P_FORD_P5, M_ABS, ModuleVersion(1, 3, 2))},{PlatformVersion(P_FORD_P5, M_BOO, ModuleVersion(1, 3, 2))},{PlatformVersion(P_FORD_T6, M_TPEC, ModuleVersion(0, 1, 2))},{PlatformVersion(P_FORD_T6, M_STEER, ModuleVersion(0, 1, 2))},{PlatformVersion(P_FORD_U6, M_TPEC, ModuleVersion(0, 1, 2))},{PlatformVersion(P_FORD_U6, M_STEER, ModuleVersion(0, 1, 2))},{PlatformVersion(P_FORD_U6, M_SHIFT, ModuleVersion(0, 1, 2))},{PlatformVersion(P_FORD_U6, M_ABS, ModuleVersion(0, 1, 2))},{PlatformVersion(P_FORD_U6, M_BOO, ModuleVersion(0, 1, 2))},{PlatformVersion(P_FORD_C1, M_TPEC, ModuleVersion(1, 1, 2))},{PlatformVersion(P_FORD_C1, M_STEER, ModuleVersion(1, 1, 2))},{PlatformVersion(P_FORD_C1, M_SHIFT, ModuleVersion(1, 1, 2))},{PlatformVersion(P_FORD_C1, M_ABS, ModuleVersion(1, 1, 2))},{PlatformVersion(P_FORD_C1, M_BOO, ModuleVersion(1, 1, 2))},{PlatformVersion(P_FORD_C1, M_EPS, ModuleVersion(1, 1, 2))},})
void overrideBrake(bool override, bool timeout)
int16_t accel_over_ground_est
ros::Publisher pub_joint_states_
ros::Publisher pub_sys_enable_
void recvDisable(const std_msgs::Empty::ConstPtr &msg)
static float brakeTorqueFromPedal(float pedal)
#define ROS_WARN_THROTTLE(rate,...)
static float brakePedalFromPercent(float percent)
#define ROS_WARN_ONCE_ID(id,...)
void publish(const boost::shared_ptr< M > &message) const
struct dbw_mkz_can::MsgLicense::@1::@9 vin0
ros::Subscriber sub_throttle_
#define ROS_INFO_ONCE(...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool fault_watchdog_using_brakes_
void faultSteering(bool fault)
ros::Subscriber sub_enable_
void overrideThrottle(bool override, bool timeout)
#define ROS_INFO_ONCE_ID(id,...)
ros::Subscriber sub_disable_
ros::Subscriber sub_gear_
void faultSteeringCal(bool fault)
void processMsg(const Type &msg)
ros::Publisher pub_steering_
static float sonarMetersFromBits(uint8_t bits)
uint16_t brake_torque_actual
void timeoutThrottle(bool timeout, bool enabled)
struct dbw_mkz_can::MsgLicense::@1::@7 bdate0
struct dbw_mkz_can::MsgLicense::@1::@6 mac
ros::Publisher pub_gps_vel_
static const char * moduleToString(Module x)
TransportHints & tcpNoDelay(bool nodelay=true)
void timeoutBrake(bool timeout, bool enabled)
ros::Publisher pub_driver_assist_
void faultBrakes(bool fault)
std::map< uint8_t, std::string > bdate_
static const char * platformToString(Platform x)
bool fault_watchdog_warned_
void recvCanGps(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
INLINE Rall1d< T, V, S > atan(const Rall1d< T, V, S > &x)
ros::Publisher pub_surround_
void recvEnable(const std_msgs::Empty::ConstPtr &msg)
void recvCanImu(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
ros::Publisher pub_throttle_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::Publisher pub_brake_
void publishJointStates(const ros::Time &stamp, const dbw_mkz_msgs::WheelSpeedReport *wheels, const dbw_mkz_msgs::SteeringReport *steering)
static float throttlePedalFromPercent(float percent)
ros::Subscriber sub_turn_signal_
ros::Publisher pub_fuel_level_
void faultWatchdog(bool fault, uint8_t src, bool braking)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void faultThrottle(bool fault)
struct dbw_mkz_can::MsgLicense::@1::@10 vin1
void recvGearCmd(const dbw_mkz_msgs::GearCmd::ConstPtr &msg)
void overrideGear(bool override)
PlatformMap FIRMWARE_TIMEOUT({{PlatformVersion(P_FORD_CD4, M_BPEC, ModuleVersion(2, 0, 0))},{PlatformVersion(P_FORD_CD4, M_TPEC, ModuleVersion(2, 0, 0))},{PlatformVersion(P_FORD_CD4, M_STEER, ModuleVersion(2, 0, 0))},})
struct dbw_mkz_can::MsgLicense::@1::@11 vin2
void recvBrakeCmd(const dbw_mkz_msgs::BrakeCmd::ConstPtr &msg)
bool enable_joint_states_
uint16_t brake_torque_request
static float brakePedalFromTorque(float torque)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher pub_misc_1_
ros::Publisher pub_wheel_speeds_
ros::Publisher pub_sonar_cloud_
ros::Publisher pub_throttle_info_
struct dbw_mkz_can::MsgLicense::@1::@3 license
PlatformMap FIRMWARE_HIGH_RATE_LIMIT({{PlatformVersion(P_FORD_CD4, M_STEER, ModuleVersion(2, 2, 0))},{PlatformVersion(P_FORD_P5, M_STEER, ModuleVersion(1, 1, 0))},})
ros::Publisher pub_gps_time_
ros::Publisher pub_twist_
void recvThrottleCmd(const dbw_mkz_msgs::ThrottleCmd::ConstPtr &msg)
void recvCAN(const can_msgs::Frame::ConstPtr &msg)
bool getParam(const std::string &key, std::string &s) const
struct dbw_mkz_can::MsgLicense::@1::@8 bdate1
void setInterMessageLowerBound(ros::Duration lower_bound)
sensor_msgs::JointState joint_state_
#define ROS_WARN_COND(cond,...)
ros::Publisher pub_brake_info_
#define ROS_INFO_THROTTLE(rate,...)
static void sonarBuildPointCloud2(sensor_msgs::PointCloud2 &cloud, const dbw_mkz_msgs::SurroundReport &surround)
ros::Publisher pub_tire_pressure_
void timerCallback(const ros::TimerEvent &event)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
void overrideSteering(bool override, bool timeout)
dataspeed_can_msg_filters::ApproximateTime sync_gps_
ros::Subscriber sub_steering_
dataspeed_can_msg_filters::ApproximateTime sync_imu_
ros::Subscriber sub_brake_
ros::Publisher pub_gps_fix_
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
void timeoutSteering(bool timeout, bool enabled)
PlatformMap FIRMWARE_CMDTYPE({{PlatformVersion(P_FORD_CD4, M_BPEC, ModuleVersion(2, 0, 7))},{PlatformVersion(P_FORD_CD4, M_TPEC, ModuleVersion(2, 0, 7))},})
DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
void recvTurnSignalCmd(const dbw_mkz_msgs::TurnSignalCmd::ConstPtr &msg)