40 #define ROS_LOG_ONCE_ID(id, level, name, ...) \ 43 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \ 44 static std::map<int, bool> map; \ 45 bool &hit = map[id]; \ 46 if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(!hit)) \ 49 ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \ 52 #define ROS_DEBUG_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__) 53 #define ROS_INFO_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__) 54 #define ROS_WARN_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__) 55 #define ROS_ERROR_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__) 56 #define ROS_FATAL_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__) 209 if (!msg->is_rtr && !msg->is_error && !msg->is_extended) {
218 dbw_fca_msgs::BrakeReport out;
219 out.header.stamp = msg->header.stamp;
220 if (ptr->
BTYPE == 0) {
222 out.pedal_input = (float)ptr->
PI / UINT16_MAX;
223 out.pedal_cmd = (
float)ptr->
PC / UINT16_MAX;
224 out.pedal_output = (float)ptr->
PO / UINT16_MAX;
228 }
else if (ptr->
BTYPE == 1) {
230 out.torque_input = ptr->
PI;
231 out.decel_cmd = ptr->
PC * 1e-3
f;
232 out.decel_output = ptr->
PO * 1e-3f;
236 out.enabled = ptr->
ENABLED ?
true :
false;
237 out.override = ptr->
OVERRIDE ?
true :
false;
238 out.driver = ptr->
DRIVER ?
true :
false;
239 out.watchdog_counter.source = ptr->
WDCSRC;
240 out.watchdog_braking = ptr->
WDCBRK ?
true :
false;
241 out.fault_wdc = ptr->
FLTWDC ?
true :
false;
242 out.fault_ch1 = ptr->
FLT1 ?
true :
false;
243 out.fault_ch2 = ptr->
FLT2 ?
true :
false;
244 out.fault_power = ptr->
FLTPWR ?
true :
false;
245 out.timeout = ptr->
TMOUT ?
true :
false;
249 ptr->
FLT1 ?
"true, " :
"false,",
250 ptr->
FLT2 ?
"true, " :
"false,",
251 ptr->
FLTPWR ?
"true" :
"false");
263 dbw_fca_msgs::ThrottleReport out;
264 out.header.stamp = msg->header.stamp;
265 out.pedal_input = (float)ptr->
PI / UINT16_MAX;
266 out.pedal_cmd = (
float)ptr->
PC / UINT16_MAX;
267 out.pedal_output = (float)ptr->
PO / UINT16_MAX;
268 out.enabled = ptr->
ENABLED ?
true :
false;
269 out.override = ptr->
OVERRIDE ?
true :
false;
270 out.driver = ptr->
DRIVER ?
true :
false;
271 out.watchdog_counter.source = ptr->
WDCSRC;
272 out.fault_wdc = ptr->
FLTWDC ?
true :
false;
273 out.fault_ch1 = ptr->
FLT1 ?
true :
false;
274 out.fault_ch2 = ptr->
FLT2 ?
true :
false;
275 out.fault_power = ptr->
FLTPWR ?
true :
false;
276 out.timeout = ptr->
TMOUT ?
true :
false;
280 ptr->
FLT1 ?
"true, " :
"false,",
281 ptr->
FLT2 ?
"true, " :
"false,",
282 ptr->
FLTPWR ?
"true" :
"false");
295 dbw_fca_msgs::SteeringReport out;
296 out.header.stamp = msg->header.stamp;
297 if ((uint16_t)ptr->
ANGLE == 0x8000) {
298 out.steering_wheel_angle = NAN;
300 out.steering_wheel_angle = (float)ptr->
ANGLE * (
float)(0.1 * M_PI / 180);
302 out.steering_wheel_cmd_type = ptr->
TMODE ? dbw_fca_msgs::SteeringReport::CMD_TORQUE : dbw_fca_msgs::SteeringReport::CMD_ANGLE;
303 if ((uint16_t)ptr->
CMD == 0xC000) {
304 out.steering_wheel_cmd = NAN;
305 }
else if (out.steering_wheel_cmd_type == dbw_fca_msgs::SteeringReport::CMD_ANGLE) {
306 out.steering_wheel_cmd = (float)ptr->
CMD * (
float)(0.1 * M_PI / 180);
308 out.steering_wheel_cmd = (float)ptr->
CMD / 128.0f;
310 if ((uint8_t)ptr->
TORQUE == 0x80) {
311 out.steering_wheel_torque = NAN;
313 out.steering_wheel_torque = (float)ptr->
TORQUE * (
float)0.0625;
315 if (ptr->
SPEED == 0xFFFF) {
318 out.speed = (float)ptr->
SPEED * (
float)(0.01 / 3.6) * (float)
speedSign();
320 out.enabled = ptr->
ENABLED ?
true :
false;
321 out.override = ptr->
OVERRIDE ?
true :
false;
322 out.fault_wdc = ptr->
FLTWDC ?
true :
false;
323 out.fault_bus1 = ptr->
FLTBUS1 ?
true :
false;
324 out.fault_bus2 = ptr->
FLTBUS2 ?
true :
false;
325 out.fault_calibration = ptr->
FLTCAL ?
true :
false;
326 out.fault_power = ptr->
FLTPWR ?
true :
false;
327 out.timeout = ptr->
TMOUT ?
true :
false;
329 geometry_msgs::TwistStamped twist;
330 twist.header.stamp = out.header.stamp;
332 twist.twist.linear.x = out.speed;
340 ptr->
FLTBUS1 ?
"true, " :
"false,",
341 ptr->
FLTBUS2 ?
"true, " :
"false,",
342 ptr->
FLTPWR ?
"true" :
"false");
344 ROS_WARN_THROTTLE(5.0,
"Steering calibration fault. Drive at least 25 mph for at least 10 seconds in a straight line.");
353 dbw_fca_msgs::GearReport out;
354 out.header.stamp = msg->header.stamp;
355 out.state.gear = ptr->
STATE;
356 out.cmd.gear = ptr->
CMD;
357 out.override = ptr->
OVERRIDE ?
true :
false;
358 out.fault_bus = ptr->
FLTBUS ?
true :
false;
360 out.reject.value = ptr->
REJECT;
361 if (out.reject.value == dbw_fca_msgs::GearReject::NONE) {
365 switch (out.reject.value) {
366 case dbw_fca_msgs::GearReject::SHIFT_IN_PROGRESS:
367 ROS_WARN(
"Gear shift rejected: Shift in progress");
369 case dbw_fca_msgs::GearReject::OVERRIDE:
370 ROS_WARN(
"Gear shift rejected: Override on brake, throttle, or steering");
372 case dbw_fca_msgs::GearReject::VEHICLE:
373 ROS_WARN(
"Gear shift rejected: Rejected by vehicle, try pressing the brakes");
375 case dbw_fca_msgs::GearReject::UNSUPPORTED:
376 ROS_WARN(
"Gear shift rejected: Unsupported gear command");
378 case dbw_fca_msgs::GearReject::FAULT:
379 ROS_WARN(
"Gear shift rejected: System in fault state");
398 dbw_fca_msgs::Misc1Report out;
399 out.header.stamp = msg->header.stamp;
404 out.btn_cc_res = ptr->
btn_cc_res ?
true :
false;
411 out.btn_ld_ok = ptr->
btn_ld_ok ?
true :
false;
412 out.btn_ld_up = ptr->
btn_ld_up ?
true :
false;
416 out.fault_bus = ptr->
FLTBUS ?
true :
false;
419 out.door_trunk = ptr->
door_trunk ?
true :
false;
427 dbw_fca_msgs::Misc2Report out;
428 out.header.stamp = msg->header.stamp;
432 out.max_ac = ptr->
max_ac ?
true :
false;
433 out.ac = ptr->
ac ?
true :
false;
434 out.ft_hvac = ptr->
ft_hvac ?
true :
false;
435 out.auto_md = ptr->
auto_md ?
true :
false;
436 out.recirc = ptr->
recirc ?
true :
false;
437 out.sync = ptr->
sync ?
true :
false;
438 out.r_defr = ptr->
r_defr ?
true :
false;
439 out.f_defr = ptr->
f_defr ?
true :
false;
441 out.heated_steering_wheel = ptr->
hsw_stat ?
true :
false;
453 dbw_fca_msgs::WheelSpeedReport out;
454 out.header.stamp = msg->header.stamp;
458 out.front_left = (float)ptr->
front_left * 0.01f;
461 out.front_right = NAN;
465 if ((uint16_t)ptr->
rear_left == 0x8000) {
468 out.rear_left = (float)ptr->
rear_left * 0.01f;
471 out.rear_right = NAN;
473 out.rear_right = (float)ptr->
rear_right * 0.01f;
482 dbw_fca_msgs::WheelPositionReport out;
483 out.header.stamp = msg->header.stamp;
495 dbw_fca_msgs::TirePressureReport out;
496 out.header.stamp = msg->header.stamp;
503 out.front_right = NAN;
513 out.rear_right = NAN;
525 dbw_fca_msgs::FuelLevelReport out;
526 out.header.stamp = msg->header.stamp;
529 out.battery_12v = (float)ptr->
battery_12v * 0.0625f;
530 out.odometer = (
float)ptr->
odometer * 0.1f;
539 dbw_fca_msgs::BrakeInfoReport out;
540 out.header.stamp = msg->header.stamp;
544 out.brake_pc = (float)ptr->
brake_pc * 0.4f;
547 out.brake_torque_request = NAN;
552 out.brake_torque_actual = NAN;
557 out.brake_pressure = NAN;
569 dbw_fca_msgs::ThrottleInfoReport out;
570 out.header.stamp = msg->header.stamp;
577 out.axle_torque = NAN;
579 out.axle_torque = (float)ptr->
axle_torque * 1.5625f;
595 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);
598 ROS_WARN_ONCE_ID(module,
"Licensing: %s one or more feature licenses expired due to the firmware build date", str_m);
600 }
else if (module ==
M_STEER) {
620 ROS_INFO(
"Licensing: %s license string date: %s", str_m,
ldate_.c_str());
623 ROS_INFO_ONCE(
"Licensing: %s MAC: %02X:%02X:%02X:%02X:%02X:%02X", str_m,
624 ptr->
mac.addr0, ptr->
mac.addr1,
625 ptr->
mac.addr2, ptr->
mac.addr3,
626 ptr->
mac.addr4, ptr->
mac.addr5);
628 std::string &bdate =
bdate_[module];
629 if (bdate.size() == 0) {
630 bdate.push_back(ptr->
bdate0.date0);
631 bdate.push_back(ptr->
bdate0.date1);
632 bdate.push_back(ptr->
bdate0.date2);
633 bdate.push_back(ptr->
bdate0.date3);
634 bdate.push_back(ptr->
bdate0.date4);
635 bdate.push_back(ptr->
bdate0.date5);
638 std::string &bdate =
bdate_[module];
639 if (bdate.size() == 6) {
640 bdate.push_back(ptr->
bdate1.date6);
641 bdate.push_back(ptr->
bdate1.date7);
642 bdate.push_back(ptr->
bdate1.date8);
643 bdate.push_back(ptr->
bdate1.date9);
644 ROS_INFO(
"Licensing: %s firmware build date: %s", str_m, bdate.c_str());
647 if (
vin_.size() == 0) {
656 if (
vin_.size() == 6) {
665 if (
vin_.size() == 12) {
671 std_msgs::String msg; msg.data =
vin_;
675 }
else if ((LIC_MUX_F0 <= ptr->mux) && (ptr->
mux <=
LIC_MUX_F7)) {
676 constexpr std::array<const char*, 8>
NAME = {
"BASE",
"CONTROL",
"SENSORS",
"",
"",
"",
"",
""};
678 const int id = module * NAME.size() + i;
680 ROS_INFO_ONCE_ID(
id,
"Licensing: %s feature '%s' enabled%s", str_m, NAME[i], ptr->
license.trial ?
" as a counted trial" :
"");
681 }
else if (ptr->
ready) {
682 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]);
685 ROS_INFO_ONCE(
"Licensing: Feature '%s' trials used: %u, remaining: %u", NAME[i],
701 if (latest.
valid()) {
704 ROS_WARN(
"Detected %s %s firmware version %u.%u.%u, which is unsupported. Platform: 0x%02X, Module: %u", str_p, str_m,
707 if (version < latest) {
708 ROS_WARN(
"Firmware %s %s has old version %u.%u.%u, updating to %u.%u.%u is suggested.", str_p, str_m,
709 version.v.major(), version.v.minor(), version.v.build(),
718 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Brake. Id: 0x%03X",
ID_BRAKE_CMD);
722 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Throttle. Id: 0x%03X",
ID_THROTTLE_CMD);
726 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Steering. Id: 0x%03X",
ID_STEERING_CMD);
730 "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Shifting. Id: 0x%03X",
ID_GEAR_CMD);
738 ROS_INFO(
"ena: %s, clr: %s, brake: %s, throttle: %s, steering: %s, gear: %s",
740 clear() ?
"true " :
"false",
756 sensor_msgs::Imu out;
757 out.header.stamp = msgs[0]->header.stamp;
759 out.orientation_covariance[0] = -1;
760 if ((uint16_t)ptr_accel->
accel_long == 0x8000) {
761 out.linear_acceleration.x = NAN;
763 out.linear_acceleration.x = (double)ptr_accel->
accel_long * 0.01;
765 if ((uint16_t)ptr_accel->
accel_lat == 0x8000) {
766 out.linear_acceleration.y = NAN;
768 out.linear_acceleration.y = (double)ptr_accel->
accel_lat * -0.01;
770 if ((uint16_t)ptr_gyro->gyro_yaw == 0x8000) {
771 out.angular_velocity.z = NAN;
773 out.angular_velocity.z = (double)ptr_gyro->gyro_yaw * 0.0002;
778 ROS_INFO(
"Time: %u.%u, %u.%u, delta: %fms",
779 msgs[0]->header.stamp.sec, msgs[0]->header.stamp.nsec,
780 msgs[1]->header.stamp.sec, msgs[1]->header.stamp.nsec,
781 labs((msgs[1]->header.stamp - msgs[0]->header.stamp).toNSec()) / 1000000.0);
795 sensor_msgs::NavSatFix msg_fix;
796 msg_fix.header.stamp = msgs[0]->header.stamp;
797 msg_fix.latitude = (
double)ptr1->
latitude / 3e6;
798 msg_fix.longitude = (double)ptr1->
longitude / 3e6;
799 msg_fix.altitude = 0.0;
800 msg_fix.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
801 msg_fix.status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
802 msg_fix.status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
805 sensor_msgs::TimeReference msg_time;
807 unix_time.tm_year = ptr2->utc_year + 100;
808 unix_time.tm_mon = ptr2->utc_month - 1;
809 unix_time.tm_mday = ptr2->utc_day;
810 unix_time.tm_hour = ptr2->utc_hours;
811 unix_time.tm_min = ptr2->utc_minutes;
812 unix_time.tm_sec = ptr2->utc_seconds;
813 msg_time.header.stamp = msgs[0]->header.stamp;
814 msg_time.time_ref.sec = timegm(&unix_time);
815 msg_time.time_ref.nsec = 0;
818 sensor_msgs::NavSatFix msg_fix_dr;
819 msg_fix_dr.header.stamp = msgs[2]->header.stamp;
820 msg_fix_dr.latitude = (double)ptr3->
dr_latitude / 3e6;
821 msg_fix_dr.longitude = (
double)ptr3->
dr_longitude / 3e6;
822 msg_fix_dr.altitude = 0.0;
823 msg_fix_dr.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
824 msg_fix_dr.status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
828 ROS_INFO(
"UTC Time: %04d-%02d-%02d %02d:%02d:%02d",
829 2000 + ptr2->utc_year, ptr2->utc_month, ptr2->utc_day,
830 ptr2->utc_hours, ptr2->utc_minutes, ptr2->utc_seconds);
834 ROS_INFO(
"Time: %u.%u, %u.%u, %u.%u, delta: %fms",
835 msgs[0]->header.stamp.sec, msgs[0]->header.stamp.nsec,
836 msgs[1]->header.stamp.sec, msgs[1]->header.stamp.nsec,
837 msgs[2]->header.stamp.sec, msgs[2]->header.stamp.nsec,
839 labs((msgs[1]->header.stamp - msgs[0]->header.stamp).toNSec()),
840 labs((msgs[2]->header.stamp - msgs[1]->header.stamp).toNSec())),
841 labs((msgs[0]->header.stamp - msgs[2]->header.stamp).toNSec())) / 1000000.0);
848 out.is_extended =
false;
851 memset(ptr, 0x00,
sizeof(*ptr));
855 switch (msg->pedal_cmd_type) {
856 case dbw_fca_msgs::BrakeCmd::CMD_NONE:
858 case dbw_fca_msgs::BrakeCmd::CMD_PEDAL:
859 ptr->
CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_PEDAL;
860 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
865 case dbw_fca_msgs::BrakeCmd::CMD_PERCENT:
867 ptr->
CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_PERCENT;
868 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
870 ptr->
CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_PEDAL;
874 case dbw_fca_msgs::BrakeCmd::CMD_TORQUE:
876 ptr->
CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_TORQUE;
877 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
879 ptr->
CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_PEDAL;
886 case dbw_fca_msgs::BrakeCmd::CMD_TORQUE_RQ:
888 ptr->
CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_TORQUE_RQ;
889 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
891 ROS_WARN_THROTTLE(1.0,
"Module ABS does not support brake command type TORQUE_RQ");
894 case dbw_fca_msgs::BrakeCmd::CMD_DECEL:
896 ptr->
CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_DECEL;
897 ptr->
PCMD = std::clamp<float>(msg->pedal_cmd * 1e3f, 0, 10e3);
903 ROS_WARN(
"Unknown brake command type: %u", msg->pedal_cmd_type);
906 if (
enabled() && msg->enable) {
909 if (
clear() || msg->clear) {
915 ptr->
COUNT = msg->count;
923 out.is_extended =
false;
926 memset(ptr, 0x00,
sizeof(*ptr));
929 switch (msg->pedal_cmd_type) {
930 case dbw_fca_msgs::ThrottleCmd::CMD_NONE:
932 case dbw_fca_msgs::ThrottleCmd::CMD_PEDAL:
933 ptr->
CMD_TYPE = dbw_fca_msgs::ThrottleCmd::CMD_PEDAL;
934 cmd = msg->pedal_cmd;
936 case dbw_fca_msgs::ThrottleCmd::CMD_PERCENT:
938 ptr->
CMD_TYPE = dbw_fca_msgs::ThrottleCmd::CMD_PERCENT;
939 cmd = msg->pedal_cmd;
941 ptr->
CMD_TYPE = dbw_fca_msgs::ThrottleCmd::CMD_PEDAL;
946 ROS_WARN(
"Unknown throttle command type: %u", msg->pedal_cmd_type);
949 ptr->
PCMD = std::clamp<float>(cmd * UINT16_MAX, 0, UINT16_MAX);
950 if (
enabled() && msg->enable) {
953 if (
clear() || msg->clear) {
959 ptr->
COUNT = msg->count;
967 out.is_extended =
false;
970 memset(ptr, 0x00,
sizeof(*ptr));
971 switch (msg->cmd_type) {
972 case dbw_fca_msgs::SteeringCmd::CMD_ANGLE:
973 ptr->
SCMD = std::clamp<float>(msg->steering_wheel_angle_cmd * (float)(180 / M_PI * 10), -INT16_MAX, INT16_MAX);
974 if (fabsf(msg->steering_wheel_angle_velocity) > 0) {
976 ptr->
SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (
float)(180 / M_PI / 4)), 1, 254);
978 ptr->
SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (
float)(180 / M_PI / 2)), 1, 254);
981 ptr->
CMD_TYPE = dbw_fca_msgs::SteeringCmd::CMD_ANGLE;
983 case dbw_fca_msgs::SteeringCmd::CMD_TORQUE:
984 ptr->
SCMD = std::clamp<float>(msg->steering_wheel_torque_cmd * 128, -INT16_MAX, INT16_MAX);
985 ptr->
CMD_TYPE = dbw_fca_msgs::SteeringCmd::CMD_TORQUE;
988 ROS_WARN(
"Unknown steering command type: %u", msg->cmd_type);
991 if (
enabled() && msg->enable) {
994 if (
clear() || msg->clear) {
1003 ptr->
COUNT = msg->count;
1009 can_msgs::Frame out;
1011 out.is_extended =
false;
1014 memset(ptr, 0x00,
sizeof(*ptr));
1016 ptr->
GCMD = msg->cmd.gear;
1018 if (
clear() || msg->clear) {
1031 can_msgs::Frame out;
1033 out.is_extended =
false;
1036 memset(ptr, 0x00,
sizeof(*ptr));
1038 ptr->
TRNCMD = msg->cmd.value;
1039 ptr->
DOORSEL = msg->door.select;
1040 ptr->
DOORCMD = msg->door.action;
1045 ptr->
sync = msg->sync.cmd;
1046 ptr->
max_ac = msg->max_ac.cmd;
1047 ptr->
ac = msg->ac.cmd;
1048 ptr->
ft_hvac = msg->ft_hvac.cmd;
1049 ptr->
auto_md = msg->auto_md.cmd;
1050 ptr->
recirc = msg->recirc.cmd;
1051 ptr->
sync = msg->sync.cmd;
1052 ptr->
r_defr = msg->r_defr.cmd;
1053 ptr->
f_defr = msg->f_defr.cmd;
1054 ptr->
hsw_cmd = msg->heated_steering_wheel.cmd;
1055 ptr->
fl_hs_cmd = msg->fl_heated_seat.value;
1056 ptr->
fl_vs_cmd = msg->fl_vented_seat.value;
1057 ptr->
fr_hs_cmd = msg->fr_heated_seat.value;
1058 ptr->
fr_vs_cmd = msg->fr_vented_seat.value;
1065 bool change =
false;
1080 can_msgs::Frame out;
1081 out.is_extended =
false;
1086 memset(out.data.elems, 0x00, 8);
1094 memset(out.data.elems, 0x00, 8);
1102 memset(out.data.elems, 0x00, 8);
1110 memset(out.data.elems, 0x00, 8);
1122 ROS_WARN(
"DBW system not enabled. Steering calibration fault.");
1125 ROS_WARN(
"DBW system not enabled. Braking fault.");
1128 ROS_WARN(
"DBW system not enabled. Throttle fault.");
1131 ROS_WARN(
"DBW system not enabled. Steering fault.");
1134 ROS_WARN(
"DBW system not enabled. Watchdog fault.");
1141 ROS_INFO(
"DBW system enable requested. Waiting for ready.");
1161 ROS_WARN(
"DBW system disabled. Cancel button pressed.");
1168 if (en && timeout) {
1171 if (en &&
override) {
1177 ROS_WARN(
"DBW system disabled. Driver override on brake/throttle pedal.");
1187 if (en && timeout) {
1190 if (en &&
override) {
1196 ROS_WARN(
"DBW system disabled. Driver override on brake/throttle pedal.");
1206 if (en && timeout) {
1209 if (en &&
override) {
1215 ROS_WARN(
"DBW system disabled. Driver override on steering wheel.");
1225 if (en &&
override) {
1231 ROS_WARN(
"DBW system disabled. Driver override on shifter.");
1241 ROS_WARN(
"Brake subsystem disabled after 100ms command timeout");
1250 ROS_WARN(
"Throttle subsystem disabled after 100ms command timeout");
1259 ROS_WARN(
"Steering subsystem disabled after 100ms command timeout");
1274 ROS_ERROR(
"DBW system disabled. Braking fault.");
1290 ROS_ERROR(
"DBW system disabled. Throttle fault.");
1306 ROS_ERROR(
"DBW system disabled. Steering fault.");
1322 ROS_ERROR(
"DBW system disabled. Steering calibration fault.");
1338 ROS_ERROR(
"DBW system disabled. Watchdog fault.");
1344 ROS_WARN(
"Watchdog event: Alerting driver and applying brakes.");
1346 ROS_INFO(
"Watchdog event: Driver has successfully taken control.");
1350 case dbw_fca_msgs::WatchdogCounter::OTHER_BRAKE:
1351 ROS_WARN(
"Watchdog event: Fault determined by brake controller");
1353 case dbw_fca_msgs::WatchdogCounter::OTHER_THROTTLE:
1354 ROS_WARN(
"Watchdog event: Fault determined by throttle controller");
1356 case dbw_fca_msgs::WatchdogCounter::OTHER_STEERING:
1357 ROS_WARN(
"Watchdog event: Fault determined by steering controller");
1359 case dbw_fca_msgs::WatchdogCounter::BRAKE_COUNTER:
1360 ROS_WARN(
"Watchdog event: Brake command counter failed to increment");
1362 case dbw_fca_msgs::WatchdogCounter::BRAKE_DISABLED:
1363 ROS_WARN(
"Watchdog event: Brake transition to disabled while in gear or moving");
1365 case dbw_fca_msgs::WatchdogCounter::BRAKE_COMMAND:
1366 ROS_WARN(
"Watchdog event: Brake command timeout after 100ms");
1368 case dbw_fca_msgs::WatchdogCounter::BRAKE_REPORT:
1369 ROS_WARN(
"Watchdog event: Brake report timeout after 100ms");
1371 case dbw_fca_msgs::WatchdogCounter::THROTTLE_COUNTER:
1372 ROS_WARN(
"Watchdog event: Throttle command counter failed to increment");
1374 case dbw_fca_msgs::WatchdogCounter::THROTTLE_DISABLED:
1375 ROS_WARN(
"Watchdog event: Throttle transition to disabled while in gear or moving");
1377 case dbw_fca_msgs::WatchdogCounter::THROTTLE_COMMAND:
1378 ROS_WARN(
"Watchdog event: Throttle command timeout after 100ms");
1380 case dbw_fca_msgs::WatchdogCounter::THROTTLE_REPORT:
1381 ROS_WARN(
"Watchdog event: Throttle report timeout after 100ms");
1383 case dbw_fca_msgs::WatchdogCounter::STEERING_COUNTER:
1384 ROS_WARN(
"Watchdog event: Steering command counter failed to increment");
1386 case dbw_fca_msgs::WatchdogCounter::STEERING_DISABLED:
1387 ROS_WARN(
"Watchdog event: Steering transition to disabled while in gear or moving");
1389 case dbw_fca_msgs::WatchdogCounter::STEERING_COMMAND:
1390 ROS_WARN(
"Watchdog event: Steering command timeout after 100ms");
1392 case dbw_fca_msgs::WatchdogCounter::STEERING_REPORT:
1393 ROS_WARN(
"Watchdog event: Steering report timeout after 100ms");
1397 }
else if (!fault) {
1402 ROS_WARN_THROTTLE(2.0,
"Watchdog event: Press left OK button on the steering wheel or cycle power to clear event.");
1412 double dt = (stamp -
joint_state_.header.stamp).toSec();
1414 if (std::isfinite(steering->steering_wheel_angle)) {
1421 if (std::isfinite(steering->speed)) {
bool fault_watchdog_warned_
void recvCAN(const can_msgs::Frame::ConstPtr &msg)
ros::Publisher pub_wheel_speeds_
ros::Publisher pub_gps_fix_
void overrideThrottle(bool override, bool timeout)
ros::Subscriber sub_turn_signal_
ros::Publisher pub_misc_1_
void faultWatchdog(bool fault, uint8_t src, bool braking)
void recvGearCmd(const dbw_fca_msgs::GearCmd::ConstPtr &msg)
void timeoutThrottle(bool timeout, bool enabled)
#define ROS_WARN_THROTTLE(rate,...)
#define ROS_WARN_ONCE_ID(id,...)
void publish(const boost::shared_ptr< M > &message) const
#define ROS_INFO_ONCE(...)
ros::Publisher pub_gps_time_
void overrideGear(bool override)
ros::Subscriber sub_steering_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber sub_throttle_
static const char * platformToString(Platform x)
bool enable_joint_states_
void recvThrottleCmd(const dbw_fca_msgs::ThrottleCmd::ConstPtr &msg)
void recvCanImu(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
uint32_t brake_torque_request
void faultSteering(bool fault)
ros::Subscriber sub_brake_
ros::Publisher pub_wheel_positions_
#define ROS_INFO_ONCE_ID(id,...)
ros::Publisher pub_gps_fix_dr
void recvBrakeCmd(const dbw_fca_msgs::BrakeCmd::ConstPtr &msg)
void processMsg(const Type &msg)
void faultSteeringCal(bool fault)
void faultThrottle(bool fault)
uint32_t brake_torque_actual
struct dbw_fca_can::MsgLicense::@1::@9 vin0
ros::Publisher pub_brake_info_
void recvSteeringCmd(const dbw_fca_msgs::SteeringCmd::ConstPtr &msg)
ros::Subscriber sub_enable_
void recvDisable(const std_msgs::Empty::ConstPtr &msg)
static const char * moduleToString(Module x)
struct dbw_fca_can::MsgLicense::@1::@7 bdate0
ros::Publisher pub_throttle_info_
ros::Publisher pub_brake_
std::map< uint8_t, std::string > bdate_
sensor_msgs::JointState joint_state_
TransportHints & tcpNoDelay(bool nodelay=true)
static float brakePedalFromPercent(float percent)
bool fault_watchdog_using_brakes_
ros::Publisher pub_joint_states_
void timerCallback(const ros::TimerEvent &event)
dataspeed_can_msg_filters::ApproximateTime sync_gps_
ros::Publisher pub_sys_enable_
struct dbw_fca_can::MsgLicense::@1::@6 mac
INLINE Rall1d< T, V, S > atan(const Rall1d< T, V, S > &x)
struct dbw_fca_can::MsgLicense::@1::@8 bdate1
void recvEnable(const std_msgs::Empty::ConstPtr &msg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::Publisher pub_throttle_
static float brakeTorqueFromPedal(float pedal)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void timeoutBrake(bool timeout, bool enabled)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void overrideBrake(bool override, bool timeout)
struct dbw_fca_can::MsgLicense::@1::@10 vin1
void overrideSteering(bool override, bool timeout)
ros::Subscriber sub_gear_
dataspeed_can_msg_filters::ApproximateTime sync_imu_
PlatformMap FIRMWARE_HIGH_RATE_LIMIT({{PlatformVersion(P_FCA_RU, M_STEER, ModuleVersion(1, 1, 0))},{PlatformVersion(P_FCA_WK2, M_STEER, ModuleVersion(0, 2, 0))},})
void recvCanGps(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
struct dbw_fca_can::MsgLicense::@1::@11 vin2
static float brakePedalFromTorque(float torque)
void faultBrakes(bool fault)
ros::Publisher pub_misc_2_
bool getParam(const std::string &key, std::string &s) const
void setInterMessageLowerBound(ros::Duration lower_bound)
#define ROS_WARN_COND(cond,...)
ros::Subscriber sub_disable_
DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
#define ROS_INFO_THROTTLE(rate,...)
ros::Subscriber sub_misc_
static float throttlePedalFromPercent(float percent)
struct dbw_fca_can::MsgLicense::@1::@3 license
void recvTurnSignalCmd(const dbw_fca_msgs::MiscCmd::ConstPtr &msg)
ros::Publisher pub_tire_pressure_
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
ros::Publisher pub_fuel_level_
void publishJointStates(const ros::Time &stamp, const dbw_fca_msgs::SteeringReport *steering)
PlatformMap FIRMWARE_LATEST({{PlatformVersion(P_FCA_RU, M_BPEC, ModuleVersion(1, 4, 2))},{PlatformVersion(P_FCA_RU, M_TPEC, ModuleVersion(1, 4, 2))},{PlatformVersion(P_FCA_RU, M_STEER, ModuleVersion(1, 4, 2))},{PlatformVersion(P_FCA_RU, M_SHIFT, ModuleVersion(1, 4, 2))},{PlatformVersion(P_FCA_WK2, M_TPEC, ModuleVersion(1, 2, 2))},{PlatformVersion(P_FCA_WK2, M_STEER, ModuleVersion(1, 2, 2))},{PlatformVersion(P_FCA_WK2, M_SHIFT, ModuleVersion(1, 2, 2))},{PlatformVersion(P_FCA_WK2, M_ABS, ModuleVersion(1, 2, 2))},})
void recvMiscCmd(const dbw_fca_msgs::MiscCmd::ConstPtr &msg)
void timeoutSteering(bool timeout, bool enabled)
ros::Publisher pub_twist_
ros::Publisher pub_steering_