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__) 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-3f;
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;
705 out.engine_rpm = NAN;
707 out.engine_rpm = (float)ptr->
engine_rpm * 0.25f;
711 if ((uint16_t)ptr->
batt_curr == 0xE000) {
714 out.batt_curr = (float)ptr->
batt_curr * 0.0625f;
717 if (ptr->
aped_qf != dbw_mkz_msgs::QualityFactor::OK) {
726 dbw_mkz_msgs::DriverAssistReport out;
727 out.header.stamp = msg->header.stamp;
738 if (out.fcw_active) {
741 if (out.aeb_braking) {
756 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);
759 ROS_WARN_ONCE_ID(module,
"Licensing: %s one or more feature licenses expired due to the firmware build date", str_m);
761 }
else if (module ==
M_STEER) {
781 ROS_INFO(
"Licensing: %s license string date: %s", str_m,
ldate_.c_str());
784 ROS_INFO_ONCE(
"Licensing: %s MAC: %02X:%02X:%02X:%02X:%02X:%02X", str_m,
785 ptr->
mac.addr0, ptr->
mac.addr1,
786 ptr->
mac.addr2, ptr->
mac.addr3,
787 ptr->
mac.addr4, ptr->
mac.addr5);
789 std::string &bdate =
bdate_[module];
790 if (bdate.size() == 0) {
791 bdate.push_back(ptr->
bdate0.date0);
792 bdate.push_back(ptr->
bdate0.date1);
793 bdate.push_back(ptr->
bdate0.date2);
794 bdate.push_back(ptr->
bdate0.date3);
795 bdate.push_back(ptr->
bdate0.date4);
796 bdate.push_back(ptr->
bdate0.date5);
799 std::string &bdate =
bdate_[module];
800 if (bdate.size() == 6) {
801 bdate.push_back(ptr->
bdate1.date6);
802 bdate.push_back(ptr->
bdate1.date7);
803 bdate.push_back(ptr->
bdate1.date8);
804 bdate.push_back(ptr->
bdate1.date9);
805 ROS_INFO(
"Licensing: %s firmware build date: %s", str_m, bdate.c_str());
808 if (
vin_.size() == 0) {
817 if (
vin_.size() == 6) {
826 if (
vin_.size() == 12) {
832 std_msgs::String msg; msg.data =
vin_;
836 }
else if ((LIC_MUX_F0 <= ptr->mux) && (ptr->
mux <=
LIC_MUX_F7)) {
837 constexpr std::array<const char*, 8>
NAME = {
"BASE",
"CONTROL",
"SENSORS",
"REMOTE",
"",
"",
"",
""};
838 constexpr std::array<bool, 8> WARN = {
true,
true,
true,
false,
true,
true,
true,
true};
840 const int id = module * NAME.size() + i;
841 const std::string name = strcmp(NAME[i],
"") ? NAME[i] : std::string(1,
'0' + i);
843 ROS_INFO_ONCE_ID(
id,
"Licensing: %s feature '%s' enabled%s", str_m, name.c_str(), ptr->
license.trial ?
" as a counted trial" :
"");
844 }
else if (ptr->
ready && !WARN[i]) {
845 ROS_INFO_ONCE_ID(
id,
"Licensing: %s feature '%s' not licensed.", str_m, name.c_str());
846 }
else if (ptr->
ready) {
847 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());
850 ROS_INFO_ONCE(
"Licensing: Feature '%s' trials used: %u, remaining: %u", name.c_str(),
866 if (latest.
valid()) {
869 ROS_WARN(
"Detected %s %s firmware version %u.%u.%u, which is unsupported. Platform: 0x%02X, Module: %u", str_p, str_m,
872 if (version < latest) {
873 ROS_WARN(
"Firmware %s %s has old version %u.%u.%u, updating to %u.%u.%u is suggested.", str_p, str_m,
874 version.v.major(), version.v.minor(), version.v.build(),
883 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Brake. Id: 0x%03X",
ID_BRAKE_CMD);
887 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Throttle. Id: 0x%03X",
ID_THROTTLE_CMD);
891 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Steering. Id: 0x%03X",
ID_STEERING_CMD);
895 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Shifting. Id: 0x%03X",
ID_GEAR_CMD);
903 ROS_INFO(
"ena: %s, clr: %s, brake: %s, throttle: %s, steering: %s, gear: %s",
905 clear() ?
"true " :
"false",
921 sensor_msgs::Imu out;
922 out.header.stamp = msgs[0]->header.stamp;
924 out.orientation_covariance[0] = -1;
925 if ((uint16_t)ptr_accel->
accel_long == 0x8000) {
926 out.linear_acceleration.x = NAN;
928 out.linear_acceleration.x = (double)ptr_accel->
accel_long * 0.01;
930 if ((uint16_t)ptr_accel->
accel_lat == 0x8000) {
931 out.linear_acceleration.y = NAN;
933 out.linear_acceleration.y = (double)ptr_accel->
accel_lat * -0.01;
935 if ((uint16_t)ptr_accel->
accel_vert == 0x8000) {
936 out.linear_acceleration.z = NAN;
938 out.linear_acceleration.z = (double)ptr_accel->
accel_vert * -0.01;
940 if ((uint16_t)ptr_gyro->gyro_roll == 0x8000) {
941 out.angular_velocity.x = NAN;
943 out.angular_velocity.x = (double)ptr_gyro->gyro_roll * 0.0002;
945 if ((uint16_t)ptr_gyro->gyro_yaw == 0x8000) {
946 out.angular_velocity.z = NAN;
948 out.angular_velocity.z = (double)ptr_gyro->gyro_yaw * 0.0002;
953 ROS_INFO(
"Time: %u.%u, %u.%u, delta: %fms",
954 msgs[0]->
header.stamp.sec, msgs[0]->header.stamp.nsec,
955 msgs[1]->header.stamp.sec, msgs[1]->header.stamp.nsec,
956 labs((msgs[1]->
header.stamp - msgs[0]->header.stamp).toNSec()) / 1000000.0);
970 sensor_msgs::NavSatFix msg_fix;
971 msg_fix.header.stamp = msgs[0]->header.stamp;
972 msg_fix.latitude = (
double)ptr1->
latitude / 3e6;
973 msg_fix.longitude = (double)ptr1->
longitude / 3e6;
974 msg_fix.altitude = (
double)ptr3->
altitude * 0.25;
975 msg_fix.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
976 msg_fix.status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
980 msg_fix.status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
984 msg_fix.status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
989 geometry_msgs::TwistStamped msg_vel;
990 msg_vel.header.stamp = msgs[0]->header.stamp;
991 double heading = (double)ptr3->
heading * (0.01 * M_PI / 180);
992 double speed = (double)ptr3->
speed * 0.44704;
993 msg_vel.twist.linear.x =
cos(heading) * speed;
994 msg_vel.twist.linear.y =
sin(heading) * speed;
997 sensor_msgs::TimeReference msg_time;
999 unix_time.tm_year = ptr2->utc_year + 100;
1000 unix_time.tm_mon = ptr2->utc_month - 1;
1001 unix_time.tm_mday = ptr2->utc_day;
1002 unix_time.tm_hour = ptr2->utc_hours;
1003 unix_time.tm_min = ptr2->utc_minutes;
1004 unix_time.tm_sec = ptr2->utc_seconds;
1005 msg_time.header.stamp = msgs[0]->header.stamp;
1006 msg_time.time_ref.sec = timegm(&unix_time);
1007 msg_time.time_ref.nsec = 0;
1011 ROS_INFO(
"UTC Time: %04d-%02d-%02d %02d:%02d:%02d",
1012 2000 + ptr2->utc_year, ptr2->utc_month, ptr2->utc_day,
1013 ptr2->utc_hours, ptr2->utc_minutes, ptr2->utc_seconds);
1017 ROS_INFO(
"Time: %u.%u, %u.%u, %u.%u, delta: %fms",
1018 msgs[0]->
header.stamp.sec, msgs[0]->header.stamp.nsec,
1019 msgs[1]->header.stamp.sec, msgs[1]->header.stamp.nsec,
1020 msgs[2]->header.stamp.sec, msgs[2]->header.stamp.nsec,
1022 labs((msgs[1]->
header.stamp - msgs[0]->header.stamp).toNSec()),
1023 labs((msgs[2]->
header.stamp - msgs[1]->header.stamp).toNSec())),
1024 labs((msgs[0]->
header.stamp - msgs[2]->header.stamp).toNSec())) / 1000000.0);
1030 can_msgs::Frame out;
1032 out.is_extended =
false;
1035 memset(ptr, 0x00,
sizeof(*ptr));
1041 switch (msg->pedal_cmd_type) {
1042 case dbw_mkz_msgs::BrakeCmd::CMD_NONE:
1044 case dbw_mkz_msgs::BrakeCmd::CMD_PEDAL:
1045 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1046 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
1051 case dbw_mkz_msgs::BrakeCmd::CMD_PERCENT:
1053 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PERCENT;
1054 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
1056 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1060 case dbw_mkz_msgs::BrakeCmd::CMD_TORQUE:
1062 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE;
1063 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1065 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1069 ROS_WARN_THROTTLE(1.0,
"Module ABS does not support brake command type TORQUE");
1072 case dbw_mkz_msgs::BrakeCmd::CMD_TORQUE_RQ:
1073 if (fwd_abs || fwd_bpe) {
1076 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE_RQ;
1077 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1080 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE;
1081 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1084 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1088 ROS_WARN_THROTTLE(1.0,
"Module ABS does not support brake command type TORQUE_RQ");
1091 case dbw_mkz_msgs::BrakeCmd::CMD_DECEL:
1093 ptr->
CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_DECEL;
1094 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd * 1e3f, 0, 10e3);
1096 ROS_WARN_THROTTLE(1.0,
"Module BPEC does not support brake command type DECEL");
1100 ROS_WARN(
"Unknown brake command type: %u", msg->pedal_cmd_type);
1103 #if 1 // Manually implement auto BOO control (brake lights) for legacy firmware 1107 const uint16_t BOO_THRESH_LO = 0.20 * UINT16_MAX;
1108 const uint16_t BOO_THRESH_HI = 0.22 * UINT16_MAX;
1109 static bool boo_status_ =
false;
1113 if (!boo_status_ && (ptr->
PCMD > BOO_THRESH_HI)) {
1116 }
else if (boo_status_ && (ptr->
PCMD < BOO_THRESH_LO)) {
1118 boo_status_ =
false;
1122 if (
enabled() && msg->enable) {
1125 if (
clear() || msg->clear) {
1131 ptr->
COUNT = msg->count;
1137 can_msgs::Frame out;
1139 out.is_extended =
false;
1142 memset(ptr, 0x00,
sizeof(*ptr));
1146 switch (msg->pedal_cmd_type) {
1147 case dbw_mkz_msgs::ThrottleCmd::CMD_NONE:
1149 case dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL:
1150 ptr->
CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL;
1151 cmd = msg->pedal_cmd;
1153 case dbw_mkz_msgs::ThrottleCmd::CMD_PERCENT:
1155 ptr->
CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PERCENT;
1156 cmd = msg->pedal_cmd;
1158 ptr->
CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL;
1163 ROS_WARN(
"Unknown throttle command type: %u", msg->pedal_cmd_type);
1166 ptr->
PCMD = std::clamp<float>(cmd * UINT16_MAX, 0, UINT16_MAX);
1167 if (
enabled() && msg->enable) {
1170 if (
clear() || msg->clear) {
1176 ptr->
COUNT = msg->count;
1182 can_msgs::Frame out;
1184 out.is_extended =
false;
1187 memset(ptr, 0x00,
sizeof(*ptr));
1188 switch (msg->cmd_type) {
1189 case dbw_mkz_msgs::SteeringCmd::CMD_ANGLE:
1190 ptr->
SCMD = std::clamp<float>(msg->steering_wheel_angle_cmd * (float)(180 / M_PI * 10), -INT16_MAX, INT16_MAX);
1191 if (fabsf(msg->steering_wheel_angle_velocity) > 0) {
1193 ptr->
SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (
float)(180 / M_PI / 4)), 1, 254);
1195 ptr->
SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (
float)(180 / M_PI / 2)), 1, 254);
1198 ptr->
CMD_TYPE = dbw_mkz_msgs::SteeringCmd::CMD_ANGLE;
1200 case dbw_mkz_msgs::SteeringCmd::CMD_TORQUE:
1201 ptr->
SCMD = std::clamp<float>(msg->steering_wheel_torque_cmd * 128, -INT16_MAX, INT16_MAX);
1202 ptr->
CMD_TYPE = dbw_mkz_msgs::SteeringCmd::CMD_TORQUE;
1204 ROS_WARN_THROTTLE(1.0,
"Module STEER does not support steering command type TORQUE");
1208 ROS_WARN(
"Unknown steering command type: %u", msg->cmd_type);
1211 if (
enabled() && msg->enable) {
1214 if (
clear() || msg->clear) {
1226 ptr->
COUNT = msg->count;
1232 can_msgs::Frame out;
1234 out.is_extended =
false;
1237 memset(ptr, 0x00,
sizeof(*ptr));
1239 ptr->
GCMD = msg->cmd.gear;
1241 if (
clear() || msg->clear) {
1249 can_msgs::Frame out;
1251 out.is_extended =
false;
1254 memset(ptr, 0x00,
sizeof(*ptr));
1256 ptr->
TRNCMD = msg->cmd.value;
1266 if (change || force) {
1279 ROS_WARN(
"DBW system enable status changed unexpectedly");
1284 can_msgs::Frame out;
1285 out.is_extended =
false;
1290 memset(out.data.elems, 0x00, 8);
1298 memset(out.data.elems, 0x00, 8);
1306 memset(out.data.elems, 0x00, 8);
1314 memset(out.data.elems, 0x00, 8);
1326 ROS_WARN(
"DBW system not enabled. Steering calibration fault.");
1329 ROS_WARN(
"DBW system not enabled. Braking fault.");
1332 ROS_WARN(
"DBW system not enabled. Throttle fault.");
1335 ROS_WARN(
"DBW system not enabled. Steering fault.");
1338 ROS_WARN(
"DBW system not enabled. Watchdog fault.");
1345 ROS_INFO(
"DBW system enable requested. Waiting for ready.");
1365 ROS_WARN(
"DBW system disabled. Cancel button pressed.");
1372 if (en && timeout) {
1375 if (en &&
override) {
1381 ROS_WARN(
"DBW system disabled. Driver override on brake/throttle pedal.");
1391 if (en && timeout) {
1394 if (en &&
override) {
1400 ROS_WARN(
"DBW system disabled. Driver override on brake/throttle pedal.");
1410 if (en && timeout) {
1413 if (en &&
override) {
1419 ROS_WARN(
"DBW system disabled. Driver override on steering wheel.");
1429 if (en &&
override) {
1435 ROS_WARN(
"DBW system disabled. Driver override on shifter.");
1445 ROS_WARN(
"Brake subsystem disabled after 100ms command timeout");
1454 ROS_WARN(
"Throttle subsystem disabled after 100ms command timeout");
1463 ROS_WARN(
"Steering subsystem disabled after 100ms command timeout");
1478 ROS_ERROR(
"DBW system disabled. Braking fault.");
1494 ROS_ERROR(
"DBW system disabled. Throttle fault.");
1510 ROS_ERROR(
"DBW system disabled. Steering fault.");
1526 ROS_ERROR(
"DBW system disabled. Steering calibration fault.");
1542 ROS_ERROR(
"DBW system disabled. Watchdog fault.");
1548 ROS_WARN(
"Watchdog event: Alerting driver and applying brakes.");
1550 ROS_INFO(
"Watchdog event: Driver has successfully taken control.");
1554 case dbw_mkz_msgs::WatchdogCounter::OTHER_BRAKE:
1555 ROS_WARN(
"Watchdog event: Fault determined by brake controller");
1557 case dbw_mkz_msgs::WatchdogCounter::OTHER_THROTTLE:
1558 ROS_WARN(
"Watchdog event: Fault determined by throttle controller");
1560 case dbw_mkz_msgs::WatchdogCounter::OTHER_STEERING:
1561 ROS_WARN(
"Watchdog event: Fault determined by steering controller");
1563 case dbw_mkz_msgs::WatchdogCounter::BRAKE_COUNTER:
1564 ROS_WARN(
"Watchdog event: Brake command counter failed to increment");
1566 case dbw_mkz_msgs::WatchdogCounter::BRAKE_DISABLED:
1567 ROS_WARN(
"Watchdog event: Brake transition to disabled while in gear or moving");
1569 case dbw_mkz_msgs::WatchdogCounter::BRAKE_COMMAND:
1570 ROS_WARN(
"Watchdog event: Brake command timeout after 100ms");
1572 case dbw_mkz_msgs::WatchdogCounter::BRAKE_REPORT:
1573 ROS_WARN(
"Watchdog event: Brake report timeout after 100ms");
1575 case dbw_mkz_msgs::WatchdogCounter::THROTTLE_COUNTER:
1576 ROS_WARN(
"Watchdog event: Throttle command counter failed to increment");
1578 case dbw_mkz_msgs::WatchdogCounter::THROTTLE_DISABLED:
1579 ROS_WARN(
"Watchdog event: Throttle transition to disabled while in gear or moving");
1581 case dbw_mkz_msgs::WatchdogCounter::THROTTLE_COMMAND:
1582 ROS_WARN(
"Watchdog event: Throttle command timeout after 100ms");
1584 case dbw_mkz_msgs::WatchdogCounter::THROTTLE_REPORT:
1585 ROS_WARN(
"Watchdog event: Throttle report timeout after 100ms");
1587 case dbw_mkz_msgs::WatchdogCounter::STEERING_COUNTER:
1588 ROS_WARN(
"Watchdog event: Steering command counter failed to increment");
1590 case dbw_mkz_msgs::WatchdogCounter::STEERING_DISABLED:
1591 ROS_WARN(
"Watchdog event: Steering transition to disabled while in gear or moving");
1593 case dbw_mkz_msgs::WatchdogCounter::STEERING_COMMAND:
1594 ROS_WARN(
"Watchdog event: Steering command timeout after 100ms");
1596 case dbw_mkz_msgs::WatchdogCounter::STEERING_REPORT:
1597 ROS_WARN(
"Watchdog event: Steering report timeout after 100ms");
1601 }
else if (!fault) {
1606 ROS_WARN_THROTTLE(2.0,
"Watchdog event: Press left OK button on the steering wheel or cycle power to clear event.");
1616 double dt = (stamp -
joint_state_.header.stamp).toSec();
1618 if (std::isfinite(wheels->front_left)) {
1621 if (std::isfinite(wheels->front_right)) {
1624 if (std::isfinite(wheels->rear_left)) {
1627 if (std::isfinite(wheels->rear_right)) {
1632 if (std::isfinite(steering->steering_wheel_angle)) {
void recvSteeringCmd(const dbw_mkz_msgs::SteeringCmd::ConstPtr &msg)
ros::Publisher pub_wheel_positions_
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)
static float brakePedalFromPercent(float percent)
#define ROS_WARN_ONCE_ID(id,...)
struct dbw_mkz_can::MsgLicense::@1::@9 vin0
PlatformMap FIRMWARE_CMDTYPE({ {PlatformVersion(P_FORD_CD4, M_BPEC, ModuleVersion(2, 0, 7))}, {PlatformVersion(P_FORD_CD4, M_TPEC, ModuleVersion(2, 0, 7))}, })
ros::Subscriber sub_throttle_
#define ROS_INFO_ONCE(...)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
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_
ros::Subscriber sub_misc_
PlatformMap FIRMWARE_LATEST({ {PlatformVersion(P_FORD_C1, M_TPEC, ModuleVersion(1, 3, 3))}, {PlatformVersion(P_FORD_C1, M_STEER, ModuleVersion(1, 3, 3))}, {PlatformVersion(P_FORD_C1, M_SHIFT, ModuleVersion(1, 3, 3))}, {PlatformVersion(P_FORD_C1, M_ABS, ModuleVersion(1, 3, 3))}, {PlatformVersion(P_FORD_C1, M_BOO, ModuleVersion(1, 3, 3))}, {PlatformVersion(P_FORD_C1, M_EPS, ModuleVersion(1, 3, 3))}, {PlatformVersion(P_FORD_CD4, M_BPEC, ModuleVersion(2, 6, 3))}, {PlatformVersion(P_FORD_CD4, M_TPEC, ModuleVersion(2, 6, 3))}, {PlatformVersion(P_FORD_CD4, M_STEER, ModuleVersion(2, 6, 3))}, {PlatformVersion(P_FORD_CD4, M_SHIFT, ModuleVersion(2, 6, 3))}, {PlatformVersion(P_FORD_CD5, M_BOO, ModuleVersion(1, 2, 3))}, {PlatformVersion(P_FORD_CD5, M_TPEC, ModuleVersion(1, 2, 3))}, {PlatformVersion(P_FORD_CD5, M_STEER, ModuleVersion(1, 2, 3))}, {PlatformVersion(P_FORD_GE1, M_TPEC, ModuleVersion(1, 0, 3))}, {PlatformVersion(P_FORD_GE1, M_STEER, ModuleVersion(1, 0, 3))}, {PlatformVersion(P_FORD_GE1, M_SHIFT, ModuleVersion(1, 0, 3))}, {PlatformVersion(P_FORD_P5, M_TPEC, ModuleVersion(1, 5, 3))}, {PlatformVersion(P_FORD_P5, M_STEER, ModuleVersion(1, 5, 3))}, {PlatformVersion(P_FORD_P5, M_SHIFT, ModuleVersion(1, 5, 3))}, {PlatformVersion(P_FORD_P5, M_ABS, ModuleVersion(1, 5, 3))}, {PlatformVersion(P_FORD_P5, M_BOO, ModuleVersion(1, 5, 3))}, {PlatformVersion(P_FORD_P702, M_TPEC, ModuleVersion(0, 1, 3))}, {PlatformVersion(P_FORD_P702, M_STEER, ModuleVersion(0, 1, 3))}, {PlatformVersion(P_FORD_P702, M_SHIFT, ModuleVersion(0, 1, 3))}, {PlatformVersion(P_FORD_T6, M_TPEC, ModuleVersion(0, 3, 3))}, {PlatformVersion(P_FORD_T6, M_STEER, ModuleVersion(0, 3, 3))}, {PlatformVersion(P_FORD_T6, M_SHIFT, ModuleVersion(0, 3, 3))}, {PlatformVersion(P_FORD_U6, M_TPEC, ModuleVersion(1, 1, 3))}, {PlatformVersion(P_FORD_U6, M_STEER, ModuleVersion(1, 1, 3))}, {PlatformVersion(P_FORD_U6, M_SHIFT, ModuleVersion(1, 1, 3))}, {PlatformVersion(P_FORD_U6, M_ABS, ModuleVersion(1, 1, 3))}, {PlatformVersion(P_FORD_U6, M_BOO, ModuleVersion(1, 1, 3))}, })
static float sonarMetersFromBits(uint8_t bits)
uint16_t brake_torque_actual
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))}, })
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)
bool publishDbwEnabled(bool force=false)
TransportHints & tcpNoDelay(bool nodelay=true)
void timeoutBrake(bool timeout, bool enabled)
ros::Publisher pub_driver_assist_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void faultBrakes(bool fault)
void publish(const boost::shared_ptr< M > &message) const
std::map< uint8_t, std::string > bdate_
static const char * platformToString(Platform x)
bool fault_watchdog_warned_
#define ROS_INFO_THROTTLE(period,...)
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)
#define ROS_WARN_THROTTLE(period,...)
void recvCanImu(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
ros::Publisher pub_throttle_
bool getParam(const std::string &key, std::string &s) const
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))}, })
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)
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)
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_
void recvMiscCmd(const dbw_mkz_msgs::MiscCmd::ConstPtr &msg)
struct dbw_mkz_can::MsgLicense::@1::@3 license
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)
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_
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)
DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh)