DbwNode.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018-2019, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include "DbwNode.h"
36 #include <dbw_fca_can/dispatch.h>
37 #include <dbw_fca_can/pedal_lut.h>
38 
39 // Log once per unique identifier, similar to ROS_LOG_ONCE()
40 #define ROS_LOG_ONCE_ID(id, level, name, ...) \
41  do \
42  { \
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)) \
47  { \
48  hit = true; \
49  ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
50  } \
51  } while(false)
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__)
57 
58 namespace dbw_fca_can
59 {
60 
61 // Latest firmware versions
62 PlatformMap FIRMWARE_LATEST({
63  {PlatformVersion(P_FCA_RU, M_BPEC, ModuleVersion(1,6,1))},
64  {PlatformVersion(P_FCA_RU, M_TPEC, ModuleVersion(1,6,1))},
65  {PlatformVersion(P_FCA_RU, M_STEER, ModuleVersion(1,6,1))},
66  {PlatformVersion(P_FCA_RU, M_SHIFT, ModuleVersion(1,6,1))},
67  {PlatformVersion(P_FCA_WK2, M_TPEC, ModuleVersion(1,4,1))},
68  {PlatformVersion(P_FCA_WK2, M_STEER, ModuleVersion(1,4,1))},
69  {PlatformVersion(P_FCA_WK2, M_SHIFT, ModuleVersion(1,4,1))},
70  {PlatformVersion(P_FCA_WK2, M_ABS, ModuleVersion(1,4,1))},
71 });
72 
73 // Minimum firmware versions required for using the new SVEL resolution of 4 deg/s
74 PlatformMap FIRMWARE_HIGH_RATE_LIMIT({
75  {PlatformVersion(P_FCA_RU, M_STEER, ModuleVersion(1,1,0))},
76  {PlatformVersion(P_FCA_WK2, M_STEER, ModuleVersion(0,2,0))},
77 });
78 
80 : sync_imu_(10, boost::bind(&DbwNode::recvCanImu, this, _1), ID_REPORT_ACCEL, ID_REPORT_GYRO)
81 , sync_gps_(10, boost::bind(&DbwNode::recvCanGps, this, _1), ID_REPORT_GPS1, ID_REPORT_GPS2, ID_REPORT_GPS3)
82 {
83  // Reduce synchronization delay
84  sync_imu_.setInterMessageLowerBound(ros::Duration(0.006)); // 20ms period
86 
87  // Initialize enable state machine
88  prev_enable_ = true;
89  enable_ = false;
90  override_brake_ = false;
91  override_throttle_ = false;
92  override_steering_ = false;
93  override_gear_ = false;
94  fault_brakes_ = false;
95  fault_throttle_ = false;
96  fault_steering_ = false;
97  fault_steering_cal_ = false;
98  fault_watchdog_ = false;
100  fault_watchdog_warned_ = false;
101  timeout_brakes_ = false;
102  timeout_throttle_ = false;
103  timeout_steering_ = false;
104  enabled_brakes_ = false;
105  enabled_throttle_ = false;
106  enabled_steering_ = false;
107  gear_warned_ = false;
108 
109  // Frame ID
110  frame_id_ = "base_footprint";
111  priv_nh.getParam("frame_id", frame_id_);
112 
113  // Warn on received commands
114  warn_cmds_ = true;
115  priv_nh.getParam("warn_cmds", warn_cmds_);
116 
117  // Buttons (enable/disable)
118  buttons_ = true;
119  priv_nh.getParam("buttons", buttons_);
120 
121  // Pedal LUTs (local/embedded)
122  pedal_luts_ = false;
123  priv_nh.getParam("pedal_luts", pedal_luts_);
124 
125  // Ackermann steering parameters
126  acker_wheelbase_ = 3.08864; // 121.6 inches
127  acker_track_ = 1.73228; // 68.2 inches
128  steering_ratio_ = 16.2;
129  wheel_radius_ = 0.365;
130  priv_nh.getParam("ackermann_wheelbase", acker_wheelbase_);
131  priv_nh.getParam("ackermann_track", acker_track_);
132  priv_nh.getParam("steering_ratio", steering_ratio_);
133 
134  // Initialize joint states
135  joint_state_.position.resize(JOINT_COUNT);
136  joint_state_.velocity.resize(JOINT_COUNT);
137  joint_state_.effort.resize(JOINT_COUNT);
138  joint_state_.name.resize(JOINT_COUNT);
139  joint_state_.name[JOINT_FL] = "wheel_fl_joint"; // Front Left
140  joint_state_.name[JOINT_FR] = "wheel_fr_joint"; // Front Right
141  joint_state_.name[JOINT_RL] = "wheel_rl_joint"; // Rear Left
142  joint_state_.name[JOINT_RR] = "wheel_rr_joint"; // Rear Right
143  joint_state_.name[JOINT_SL] = "steer_fl_joint";
144  joint_state_.name[JOINT_SR] = "steer_fr_joint";
145 
146  // Setup Publishers
147  pub_can_ = node.advertise<can_msgs::Frame>("can_tx", 10);
148  pub_brake_ = node.advertise<dbw_fca_msgs::BrakeReport>("brake_report", 2);
149  pub_throttle_ = node.advertise<dbw_fca_msgs::ThrottleReport>("throttle_report", 2);
150  pub_steering_ = node.advertise<dbw_fca_msgs::SteeringReport>("steering_report", 2);
151  pub_gear_ = node.advertise<dbw_fca_msgs::GearReport>("gear_report", 2);
152  pub_misc_1_ = node.advertise<dbw_fca_msgs::Misc1Report>("misc_1_report", 2);
153  pub_misc_2_ = node.advertise<dbw_fca_msgs::Misc2Report>("misc_2_report", 2);
154  pub_wheel_speeds_ = node.advertise<dbw_fca_msgs::WheelSpeedReport>("wheel_speed_report", 2);
155  pub_wheel_positions_ = node.advertise<dbw_fca_msgs::WheelPositionReport>("wheel_position_report", 2);
156  pub_tire_pressure_ = node.advertise<dbw_fca_msgs::TirePressureReport>("tire_pressure_report", 2);
157  pub_fuel_level_ = node.advertise<dbw_fca_msgs::FuelLevelReport>("fuel_level_report", 2);
158  pub_brake_info_ = node.advertise<dbw_fca_msgs::BrakeInfoReport>("brake_info_report", 2);
159  pub_throttle_info_ = node.advertise<dbw_fca_msgs::ThrottleInfoReport>("throttle_info_report", 2);
160  pub_imu_ = node.advertise<sensor_msgs::Imu>("imu/data_raw", 10);
161  pub_gps_fix_ = node.advertise<sensor_msgs::NavSatFix>("gps/fix", 10);
162  pub_gps_time_ = node.advertise<sensor_msgs::TimeReference>("gps/time", 10);
163  pub_gps_fix_dr = node.advertise<sensor_msgs::NavSatFix>("gps_dr/fix", 10);
164  pub_twist_ = node.advertise<geometry_msgs::TwistStamped>("twist", 10);
165  pub_vin_ = node.advertise<std_msgs::String>("vin", 1, true);
166  pub_sys_enable_ = node.advertise<std_msgs::Bool>("dbw_enabled", 1, true);
168 
169  // Publish joint states if enabled
170  priv_nh.param("joint_states", enable_joint_states_, true);
171  if (enable_joint_states_) {
172  pub_joint_states_ = node.advertise<sensor_msgs::JointState>("joint_states", 10);
173  }
174 
175  // Setup Subscribers
177  sub_enable_ = node.subscribe("enable", 10, &DbwNode::recvEnable, this, NODELAY);
178  sub_disable_ = node.subscribe("disable", 10, &DbwNode::recvDisable, this, NODELAY);
179  sub_can_ = node.subscribe("can_rx", 100, &DbwNode::recvCAN, this, NODELAY);
180  sub_brake_ = node.subscribe("brake_cmd", 1, &DbwNode::recvBrakeCmd, this, NODELAY);
181  sub_throttle_ = node.subscribe("throttle_cmd", 1, &DbwNode::recvThrottleCmd, this, NODELAY);
182  sub_steering_ = node.subscribe("steering_cmd", 1, &DbwNode::recvSteeringCmd, this, NODELAY);
183  sub_gear_ = node.subscribe("gear_cmd", 1, &DbwNode::recvGearCmd, this, NODELAY);
184  sub_turn_signal_ = node.subscribe("turn_signal_cmd", 1, &DbwNode::recvMiscCmd, this, NODELAY); // Backwards compatiblity
185  sub_misc_ = node.subscribe("misc_cmd", 1, &DbwNode::recvMiscCmd, this, NODELAY);
186 
187  // Setup Timer
188  timer_ = node.createTimer(ros::Duration(1 / 20.0), &DbwNode::timerCallback, this);
189 }
190 
192 {
193 }
194 
195 void DbwNode::recvEnable(const std_msgs::Empty::ConstPtr& msg)
196 {
197  enableSystem();
198 }
199 
200 void DbwNode::recvDisable(const std_msgs::Empty::ConstPtr& msg)
201 {
202  disableSystem();
203 }
204 
205 void DbwNode::recvCAN(const can_msgs::Frame::ConstPtr& msg)
206 {
207  sync_imu_.processMsg(msg);
208  sync_gps_.processMsg(msg);
209  if (!msg->is_rtr && !msg->is_error && !msg->is_extended) {
210  switch (msg->id) {
211  case ID_BRAKE_REPORT:
212  if (msg->dlc >= sizeof(MsgBrakeReport)) {
213  const MsgBrakeReport *ptr = (const MsgBrakeReport*)msg->data.elems;
214  faultBrakes(ptr->FLT1 || ptr->FLT2);
215  faultWatchdog(ptr->FLTWDC, ptr->WDCSRC, ptr->WDCBRK);
216  overrideBrake(ptr->OVERRIDE, ptr->TMOUT);
217  timeoutBrake(ptr->TMOUT, ptr->ENABLED);
218  dbw_fca_msgs::BrakeReport out;
219  out.header.stamp = msg->header.stamp;
220  if (ptr->BTYPE == 0) {
221  // Brake pedal emulator for hybrid electric vehicles
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;
225  out.torque_input = brakeTorqueFromPedal(out.pedal_input);
226  out.torque_cmd = brakeTorqueFromPedal(out.pedal_cmd);
227  out.torque_output = brakeTorqueFromPedal(out.pedal_output);
228  } else if (ptr->BTYPE == 1) {
229  // ACC/AEB braking for non-hybrid vehicles
230  out.torque_input = ptr->PI;
231  out.decel_cmd = ptr->PC * 1e-3f;
232  out.decel_output = ptr->PO * 1e-3f;
233  } else {
234  ROS_WARN_THROTTLE(5.0, "Unsupported brake report type: %u", ptr->BTYPE);
235  }
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;
246  pub_brake_.publish(out);
247  if (ptr->FLT1 || ptr->FLT2 || ptr->FLTPWR) {
248  ROS_WARN_THROTTLE(5.0, "Brake fault. FLT1: %s FLT2: %s FLTPWR: %s",
249  ptr->FLT1 ? "true, " : "false,",
250  ptr->FLT2 ? "true, " : "false,",
251  ptr->FLTPWR ? "true" : "false");
252  }
253  }
254  break;
255 
256  case ID_THROTTLE_REPORT:
257  if (msg->dlc >= sizeof(MsgThrottleReport)) {
258  const MsgThrottleReport *ptr = (const MsgThrottleReport*)msg->data.elems;
259  faultThrottle(ptr->FLT1 || ptr->FLT2);
260  faultWatchdog(ptr->FLTWDC, ptr->WDCSRC);
261  overrideThrottle(ptr->OVERRIDE, ptr->TMOUT);
262  timeoutThrottle(ptr->TMOUT, ptr->ENABLED);
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;
277  pub_throttle_.publish(out);
278  if (ptr->FLT1 || ptr->FLT2 || ptr->FLTPWR) {
279  ROS_WARN_THROTTLE(5.0, "Throttle fault. FLT1: %s FLT2: %s FLTPWR: %s",
280  ptr->FLT1 ? "true, " : "false,",
281  ptr->FLT2 ? "true, " : "false,",
282  ptr->FLTPWR ? "true" : "false");
283  }
284  }
285  break;
286 
287  case ID_STEERING_REPORT:
288  if (msg->dlc >= sizeof(MsgSteeringReport)) {
289  const MsgSteeringReport *ptr = (const MsgSteeringReport*)msg->data.elems;
290  faultSteering(ptr->FLTBUS1 || ptr->FLTBUS2);
291  faultSteeringCal(ptr->FLTCAL);
292  faultWatchdog(ptr->FLTWDC);
293  overrideSteering(ptr->OVERRIDE, ptr->TMOUT);
294  timeoutSteering(ptr->TMOUT, ptr->ENABLED);
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;
299  } else {
300  out.steering_wheel_angle = (float)ptr->ANGLE * (float)(0.1 * M_PI / 180);
301  }
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);
307  } else {
308  out.steering_wheel_cmd = (float)ptr->CMD / 128.0f;
309  }
310  if ((uint8_t)ptr->TORQUE == 0x80) {
311  out.steering_wheel_torque = NAN;
312  } else {
313  out.steering_wheel_torque = (float)ptr->TORQUE * (float)0.0625;
314  }
315  if ((uint16_t)ptr->VEH_VEL == 0x8000) {
316  out.speed = NAN;
317  } else {
318  out.speed = (float)ptr->VEH_VEL * (float)(0.01 / 3.6);
319  }
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;
328  pub_steering_.publish(out);
329  geometry_msgs::TwistStamped twist;
330  twist.header.stamp = out.header.stamp;
331  twist.header.frame_id = frame_id_;
332  twist.twist.linear.x = out.speed;
333  twist.twist.angular.z = out.speed * tan(out.steering_wheel_angle / steering_ratio_) / acker_wheelbase_;
334  pub_twist_.publish(twist);
335  if (enable_joint_states_) {
336  publishJointStates(msg->header.stamp, &out);
337  }
338  if (ptr->FLTBUS1 || ptr->FLTBUS2 || ptr->FLTPWR) {
339  ROS_WARN_THROTTLE(5.0, "Steering fault. FLT1: %s FLT2: %s FLTPWR: %s",
340  ptr->FLTBUS1 ? "true, " : "false,",
341  ptr->FLTBUS2 ? "true, " : "false,",
342  ptr->FLTPWR ? "true" : "false");
343  } else if (ptr->FLTCAL) {
344  ROS_WARN_THROTTLE(5.0, "Steering calibration fault. Drive at least 25 mph for at least 10 seconds in a straight line.");
345  }
346  }
347  break;
348 
349  case ID_GEAR_REPORT:
350  if (msg->dlc >= 1) {
351  const MsgGearReport *ptr = (const MsgGearReport*)msg->data.elems;
352  overrideGear(ptr->OVERRIDE);
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.ready = ptr->READY ? true : false;
358  out.override = ptr->OVERRIDE ? true : false;
359  out.fault_bus = ptr->FLTBUS ? true : false;
360  if (msg->dlc >= sizeof(MsgGearReport)) {
361  out.reject.value = ptr->REJECT;
362  if (out.reject.value == dbw_fca_msgs::GearReject::NONE) {
363  gear_warned_ = false;
364  } else if (!gear_warned_) {
365  gear_warned_ = true;
366  switch (out.reject.value) {
367  case dbw_fca_msgs::GearReject::SHIFT_IN_PROGRESS:
368  ROS_WARN("Gear shift rejected: Shift in progress");
369  break;
370  case dbw_fca_msgs::GearReject::OVERRIDE:
371  ROS_WARN("Gear shift rejected: Override on brake, throttle, or steering");
372  break;
373  case dbw_fca_msgs::GearReject::VEHICLE:
374  ROS_WARN("Gear shift rejected: Rejected by vehicle, try pressing the brakes");
375  break;
376  case dbw_fca_msgs::GearReject::UNSUPPORTED:
377  ROS_WARN("Gear shift rejected: Unsupported gear command");
378  break;
379  case dbw_fca_msgs::GearReject::FAULT:
380  ROS_WARN("Gear shift rejected: System in fault state");
381  break;
382  }
383  }
384  }
385  pub_gear_.publish(out);
386  }
387  break;
388 
389  case ID_MISC_REPORT:
390  if (msg->dlc >= sizeof(MsgMiscReport)) {
391  const MsgMiscReport *ptr = (const MsgMiscReport*)msg->data.elems;
392  if (buttons_) {
393  if (0) {
394  buttonCancel();
395  } else if ((ptr->btn_ld_left && ptr->btn_ld_down)) {
396  enableSystem();
397  }
398  }
399  dbw_fca_msgs::Misc1Report out;
400  out.header.stamp = msg->header.stamp;
401  out.turn_signal.value = ptr->turn_signal;
402  out.high_beam.value = ptr->head_light_hi;
403  out.wiper.status = ptr->wiper_front;
404  out.btn_cc_on_off = ptr->btn_cc_on_off ? true : false;
405  out.btn_cc_res = ptr->btn_cc_res ? true : false;
406  out.btn_cc_cncl = ptr->btn_cc_cncl ? true : false;
407  out.btn_cc_set_inc = ptr->btn_cc_set_inc ? true : false;
408  out.btn_cc_set_dec = ptr->btn_cc_set_dec ? true : false;
409  out.btn_cc_gap_inc = ptr->btn_cc_gap_inc ? true : false;
410  out.btn_cc_gap_dec = ptr->btn_cc_gap_dec ? true : false;
411  out.btn_cc_mode = ptr->btn_cc_mode ? true : false;
412  out.btn_ld_ok = ptr->btn_ld_ok ? true : false;
413  out.btn_ld_up = ptr->btn_ld_up ? true : false;
414  out.btn_ld_down = ptr->btn_ld_down ? true : false;
415  out.btn_ld_left = ptr->btn_ld_left ? true : false;
416  out.btn_ld_right = ptr->btn_ld_right ? true : false;
417  out.fault_bus = ptr->FLTBUS ? true : false;
418  out.door_rear_left = ptr->door_rear_left ? true : false;
419  out.door_rear_right = ptr->door_rear_right ? true : false;
420  out.door_trunk = ptr->door_trunk ? true : false;
421  pub_misc_1_.publish(out);
422  }
423  break;
424 
425  case ID_MISC2_REPORT:
426  if (msg->dlc >= sizeof(MsgMisc2Report)) {
427  const MsgMisc2Report *ptr = (const MsgMisc2Report*)msg->data.elems;
428  dbw_fca_msgs::Misc2Report out;
429  out.header.stamp = msg->header.stamp;
430  out.ft_drv_temp.value = ptr->ft_drv_temp_stat;
431  out.ft_psg_temp.value = ptr->ft_psg_temp_stat;
432  out.ft_fan_speed.value = ptr->ft_fn_sp_stat;
433  out.max_ac = ptr->max_ac ? true : false;
434  out.ac = ptr->ac ? true : false;
435  out.ft_hvac = ptr->ft_hvac ? true : false;
436  out.auto_md = ptr->auto_md ? true : false;
437  out.recirc = ptr->recirc ? true : false;
438  out.sync = ptr->sync ? true : false;
439  out.r_defr = ptr->r_defr ? true : false;
440  out.f_defr = ptr->f_defr ? true : false;
441  out.vent_mode.value = ptr->vent_md_stat;
442  out.heated_steering_wheel = ptr->hsw_stat ? true : false;
443  out.fl_heated_seat.value = ptr->fl_hs_stat;
444  out.fl_vented_seat.value = ptr->fl_vs_stat;
445  out.fr_heated_seat.value = ptr->fr_hs_stat;
446  out.fr_vented_seat.value = ptr->fr_vs_stat;
447  pub_misc_2_.publish(out);
448  }
449  break;
450 
452  if (msg->dlc >= sizeof(MsgReportWheelSpeed)) {
453  const MsgReportWheelSpeed *ptr = (const MsgReportWheelSpeed*)msg->data.elems;
454  dbw_fca_msgs::WheelSpeedReport out;
455  out.header.stamp = msg->header.stamp;
456  if ((uint16_t)ptr->front_left == 0x8000) {
457  out.front_left = NAN;
458  } else {
459  out.front_left = (float)ptr->front_left * 0.01f;
460  }
461  if ((uint16_t)ptr->front_right == 0x8000) {
462  out.front_right = NAN;
463  } else {
464  out.front_right = (float)ptr->front_right * 0.01f;
465  }
466  if ((uint16_t)ptr->rear_left == 0x8000) {
467  out.rear_left = NAN;
468  } else {
469  out.rear_left = (float)ptr->rear_left * 0.01f;
470  }
471  if ((uint16_t)ptr->rear_right == 0x8000) {
472  out.rear_right = NAN;
473  } else {
474  out.rear_right = (float)ptr->rear_right * 0.01f;
475  }
477  }
478  break;
479 
481  if (msg->dlc >= sizeof(MsgReportWheelPosition)) {
482  const MsgReportWheelPosition *ptr = (const MsgReportWheelPosition*)msg->data.elems;
483  dbw_fca_msgs::WheelPositionReport out;
484  out.header.stamp = msg->header.stamp;
485  out.front_left = ptr->front_left;
486  out.front_right = ptr->front_right;
487  out.rear_left = ptr->rear_left;
488  out.rear_right = ptr->rear_right;
490  }
491  break;
492 
494  if (msg->dlc >= sizeof(MsgReportTirePressure)) {
495  const MsgReportTirePressure *ptr = (const MsgReportTirePressure*)msg->data.elems;
496  dbw_fca_msgs::TirePressureReport out;
497  out.header.stamp = msg->header.stamp;
498  if (ptr->front_left == 0xFFFF) {
499  out.front_left = NAN;
500  } else {
501  out.front_left = (float)ptr->front_left;
502  }
503  if (ptr->front_right == 0xFFFF) {
504  out.front_right = NAN;
505  } else {
506  out.front_right = (float)ptr->front_right;
507  }
508  if (ptr->rear_left == 0xFFFF) {
509  out.rear_left = NAN;
510  } else {
511  out.rear_left = (float)ptr->rear_left;
512  }
513  if (ptr->rear_right == 0xFFFF) {
514  out.rear_right = NAN;
515  } else {
516  out.rear_right = (float)ptr->rear_right;
517  }
519  }
520  break;
521 
522 
524  if (msg->dlc >= 2) {
525  const MsgReportFuelLevel *ptr = (const MsgReportFuelLevel*)msg->data.elems;
526  dbw_fca_msgs::FuelLevelReport out;
527  out.header.stamp = msg->header.stamp;
528  out.fuel_level = (float)ptr->fuel_level * 0.108696f;
529  if (msg->dlc >= sizeof(MsgReportFuelLevel)) {
530  out.battery_12v = (float)ptr->battery_12v * 0.0625f;
531  out.odometer = (float)ptr->odometer * 0.1f;
532  }
534  }
535  break;
536 
538  if (msg->dlc >= sizeof(MsgReportBrakeInfo)) {
539  const MsgReportBrakeInfo *ptr = (const MsgReportBrakeInfo*)msg->data.elems;
540  dbw_fca_msgs::BrakeInfoReport out;
541  out.header.stamp = msg->header.stamp;
542  if (ptr->brake_pc == 0xFF) {
543  out.brake_pc = NAN;
544  } else {
545  out.brake_pc = (float)ptr->brake_pc * 0.4f;
546  }
547  if (ptr->brake_torque_request == 0xFFF) {
548  out.brake_torque_request = NAN;
549  } else {
550  out.brake_torque_request = (float)ptr->brake_torque_request * 3.0f;
551  }
552  if (ptr->brake_torque_actual == 0xFFF) {
553  out.brake_torque_actual = NAN;
554  } else {
555  out.brake_torque_actual = (float)ptr->brake_torque_actual * 3.0f;
556  }
557  if (ptr->brake_pressure == 0x7FF) {
558  out.brake_pressure = NAN;
559  } else {
560  out.brake_pressure = (float)ptr->brake_pressure * 0.1f;
561  }
562  out.stationary = ptr->stationary;
564  }
565  break;
566 
568  if (msg->dlc >= sizeof(MsgReportThrottleInfo)) {
569  const MsgReportThrottleInfo *ptr = (const MsgReportThrottleInfo*)msg->data.elems;
570  dbw_fca_msgs::ThrottleInfoReport out;
571  out.header.stamp = msg->header.stamp;
572  if (ptr->throttle_pc == 0xFF) {
573  out.throttle_pc = NAN;
574  } else {
575  out.throttle_pc = (float)ptr->throttle_pc * 0.4f;
576  }
577  if ((uint16_t)ptr->axle_torque == 0xC000) {
578  out.axle_torque = NAN;
579  } else {
580  out.axle_torque = (float)ptr->axle_torque * 1.5625f;
581  }
582  out.gear_num.num = ptr->gear_num;
583  out.ignition.value = ptr->ign_stat;
585  }
586  break;
587 
588  case ID_LICENSE:
589  if (msg->dlc >= sizeof(MsgLicense)) {
590  const MsgLicense *ptr = (const MsgLicense*)msg->data.elems;
591  const Module module = ptr->module ? (Module)ptr->module : M_STEER; // Legacy steering firmware reports zero for module
592  const char * str_m = moduleToString(module);
593  ROS_DEBUG("LICENSE(%x,%02X,%s)", ptr->module, ptr->mux, str_m);
594  if (ptr->ready) {
595  ROS_INFO_ONCE_ID(module, "Licensing: %s ready", str_m);
596  if (ptr->trial) {
597  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  }
599  if (ptr->expired) {
600  ROS_WARN_ONCE_ID(module, "Licensing: %s one or more feature licenses expired due to the firmware build date", str_m);
601  }
602  } else if (module == M_STEER) {
603  ROS_INFO_THROTTLE(10.0, "Licensing: Waiting for VIN...");
604  } else {
605  ROS_INFO_THROTTLE(10.0, "Licensing: Waiting for required info...");
606  }
607  if (ptr->mux == LIC_MUX_LDATE0) {
608  if (ldate_.size() == 0) {
609  ldate_.push_back(ptr->ldate0.ldate0);
610  ldate_.push_back(ptr->ldate0.ldate1);
611  ldate_.push_back(ptr->ldate0.ldate2);
612  ldate_.push_back(ptr->ldate0.ldate3);
613  ldate_.push_back(ptr->ldate0.ldate4);
614  ldate_.push_back(ptr->ldate0.ldate5);
615  }
616  } else if (ptr->mux == LIC_MUX_LDATE1) {
617  if (ldate_.size() == 6) {
618  ldate_.push_back(ptr->ldate1.ldate6);
619  ldate_.push_back(ptr->ldate1.ldate7);
620  ldate_.push_back(ptr->ldate1.ldate8);
621  ldate_.push_back(ptr->ldate1.ldate9);
622  ROS_INFO("Licensing: %s license string date: %s", str_m, ldate_.c_str());
623  }
624  } else if (ptr->mux == LIC_MUX_MAC) {
625  ROS_INFO_ONCE("Licensing: %s MAC: %02X:%02X:%02X:%02X:%02X:%02X", str_m,
626  ptr->mac.addr0, ptr->mac.addr1,
627  ptr->mac.addr2, ptr->mac.addr3,
628  ptr->mac.addr4, ptr->mac.addr5);
629  } else if (ptr->mux == LIC_MUX_BDATE0) {
630  std::string &bdate = bdate_[module];
631  if (bdate.size() == 0) {
632  bdate.push_back(ptr->bdate0.date0);
633  bdate.push_back(ptr->bdate0.date1);
634  bdate.push_back(ptr->bdate0.date2);
635  bdate.push_back(ptr->bdate0.date3);
636  bdate.push_back(ptr->bdate0.date4);
637  bdate.push_back(ptr->bdate0.date5);
638  }
639  } else if (ptr->mux == LIC_MUX_BDATE1) {
640  std::string &bdate = bdate_[module];
641  if (bdate.size() == 6) {
642  bdate.push_back(ptr->bdate1.date6);
643  bdate.push_back(ptr->bdate1.date7);
644  bdate.push_back(ptr->bdate1.date8);
645  bdate.push_back(ptr->bdate1.date9);
646  ROS_INFO("Licensing: %s firmware build date: %s", str_m, bdate.c_str());
647  }
648  } else if (ptr->mux == LIC_MUX_VIN0) {
649  if (vin_.size() == 0) {
650  vin_.push_back(ptr->vin0.vin00);
651  vin_.push_back(ptr->vin0.vin01);
652  vin_.push_back(ptr->vin0.vin02);
653  vin_.push_back(ptr->vin0.vin03);
654  vin_.push_back(ptr->vin0.vin04);
655  vin_.push_back(ptr->vin0.vin05);
656  }
657  } else if (ptr->mux == LIC_MUX_VIN1) {
658  if (vin_.size() == 6) {
659  vin_.push_back(ptr->vin1.vin06);
660  vin_.push_back(ptr->vin1.vin07);
661  vin_.push_back(ptr->vin1.vin08);
662  vin_.push_back(ptr->vin1.vin09);
663  vin_.push_back(ptr->vin1.vin10);
664  vin_.push_back(ptr->vin1.vin11);
665  }
666  } else if (ptr->mux == LIC_MUX_VIN2) {
667  if (vin_.size() == 12) {
668  vin_.push_back(ptr->vin2.vin12);
669  vin_.push_back(ptr->vin2.vin13);
670  vin_.push_back(ptr->vin2.vin14);
671  vin_.push_back(ptr->vin2.vin15);
672  vin_.push_back(ptr->vin2.vin16);
673  std_msgs::String msg; msg.data = vin_;
674  pub_vin_.publish(msg);
675  ROS_INFO("Licensing: VIN: %s", vin_.c_str());
676  }
677  } else if ((LIC_MUX_F0 <= ptr->mux) && (ptr->mux <= LIC_MUX_F7)) {
678  constexpr std::array<const char*, 8> NAME = {"BASE","CONTROL","SENSORS","","","","",""};
679  constexpr std::array<bool, 8> WARN = {true, true, true, false, true, true, true, true};
680  const size_t i = ptr->mux - LIC_MUX_F0;
681  const int id = module * NAME.size() + i;
682  const std::string name = strcmp(NAME[i], "") ? NAME[i] : std::string(1, '0' + i);
683  if (ptr->license.enabled) {
684  ROS_INFO_ONCE_ID(id, "Licensing: %s feature '%s' enabled%s", str_m, name.c_str(), ptr->license.trial ? " as a counted trial" : "");
685  } else if (ptr->ready && !WARN[i]) {
686  ROS_INFO_ONCE_ID(id, "Licensing: %s feature '%s' not licensed.", str_m, name.c_str());
687  } else if (ptr->ready) {
688  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());
689  }
690  if (ptr->ready && (module == M_STEER) && (ptr->license.trial || (!ptr->license.enabled && WARN[i]))) {
691  ROS_INFO_ONCE("Licensing: Feature '%s' trials used: %u, remaining: %u", name.c_str(),
692  ptr->license.trials_used, ptr->license.trials_left);
693  }
694  }
695  }
696  break;
697 
698  case ID_VERSION:
699  if (msg->dlc >= sizeof(MsgVersion)) {
700  const MsgVersion *ptr = (const MsgVersion*)msg->data.elems;
701  const PlatformVersion version((Platform)ptr->platform, (Module)ptr->module, ptr->major, ptr->minor, ptr->build);
702  const ModuleVersion latest = FIRMWARE_LATEST.findModule(version);
703  const char * str_p = platformToString(version.p);
704  const char * str_m = moduleToString(version.m);
705  if (firmware_.findModule(version) != version.v) {
706  firmware_.insert(version);
707  if (latest.valid()) {
708  ROS_INFO("Detected %s %s firmware version %u.%u.%u", str_p, str_m, ptr->major, ptr->minor, ptr->build);
709  } else {
710  ROS_WARN("Detected %s %s firmware version %u.%u.%u, which is unsupported. Platform: 0x%02X, Module: %u", str_p, str_m,
711  ptr->major, ptr->minor, ptr->build, ptr->platform, ptr->module);
712  }
713  if (version < latest) {
714  ROS_WARN("Firmware %s %s has old version %u.%u.%u, updating to %u.%u.%u is suggested.", str_p, str_m,
715  version.v.major(), version.v.minor(), version.v.build(),
716  latest.major(), latest.minor(), latest.build());
717  }
718  }
719  }
720  break;
721 
722  case ID_BRAKE_CMD:
723  ROS_WARN_COND(warn_cmds_ && !((const MsgBrakeCmd*)msg->data.elems)->RES1 && !((const MsgBrakeCmd*)msg->data.elems)->RES2,
724  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Brake. Id: 0x%03X", ID_BRAKE_CMD);
725  break;
726  case ID_THROTTLE_CMD:
727  ROS_WARN_COND(warn_cmds_ && !((const MsgThrottleCmd*)msg->data.elems)->RES1 && !((const MsgThrottleCmd*)msg->data.elems)->RES2,
728  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Throttle. Id: 0x%03X", ID_THROTTLE_CMD);
729  break;
730  case ID_STEERING_CMD:
731  ROS_WARN_COND(warn_cmds_ && !((const MsgSteeringCmd*)msg->data.elems)->RES1 && !((const MsgSteeringCmd*)msg->data.elems)->RES2,
732  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Steering. Id: 0x%03X", ID_STEERING_CMD);
733  break;
734  case ID_GEAR_CMD:
735  ROS_WARN_COND(warn_cmds_ && !((const MsgGearCmd*)msg->data.elems)->RES1 && !((const MsgGearCmd*)msg->data.elems)->RES2,
736  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Shifting. Id: 0x%03X", ID_GEAR_CMD);
737  break;
738  case ID_MISC_CMD:
739  ROS_WARN_COND(warn_cmds_, "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Turn Signals. Id: 0x%03X", ID_MISC_CMD);
740  break;
741  }
742  }
743 #if 0
744  ROS_INFO("ena: %s, clr: %s, brake: %s, throttle: %s, steering: %s, gear: %s",
745  enabled() ? "true " : "false",
746  clear() ? "true " : "false",
747  override_brake_ ? "true " : "false",
748  override_throttle_ ? "true " : "false",
749  override_steering_ ? "true " : "false",
750  override_gear_ ? "true " : "false"
751  );
752 #endif
753 }
754 
755 void DbwNode::recvCanImu(const std::vector<can_msgs::Frame::ConstPtr> &msgs) {
756  ROS_ASSERT(msgs.size() == 2);
757  ROS_ASSERT(msgs[0]->id == ID_REPORT_ACCEL);
758  ROS_ASSERT(msgs[1]->id == ID_REPORT_GYRO);
759  if ((msgs[0]->dlc >= sizeof(MsgReportAccel)) && (msgs[1]->dlc >= sizeof(MsgReportGyro))) {
760  const MsgReportAccel *ptr_accel = (const MsgReportAccel*)msgs[0]->data.elems;
761  const MsgReportGyro *ptr_gyro = (const MsgReportGyro*)msgs[1]->data.elems;
762  sensor_msgs::Imu out;
763  out.header.stamp = msgs[0]->header.stamp;
764  out.header.frame_id = frame_id_;
765  out.orientation_covariance[0] = -1; // Orientation not present
766  if ((uint16_t)ptr_accel->accel_long == 0x8000) {
767  out.linear_acceleration.x = NAN;
768  } else {
769  out.linear_acceleration.x = (double)ptr_accel->accel_long * 0.01;
770  }
771  if ((uint16_t)ptr_accel->accel_lat == 0x8000) {
772  out.linear_acceleration.y = NAN;
773  } else {
774  out.linear_acceleration.y = (double)ptr_accel->accel_lat * -0.01;
775  }
776  if ((uint16_t)ptr_gyro->gyro_yaw == 0x8000) {
777  out.angular_velocity.z = NAN;
778  } else {
779  out.angular_velocity.z = (double)ptr_gyro->gyro_yaw * 0.0002;
780  }
781  pub_imu_.publish(out);
782  }
783 #if 0
784  ROS_INFO("Time: %u.%u, %u.%u, delta: %fms",
785  msgs[0]->header.stamp.sec, msgs[0]->header.stamp.nsec,
786  msgs[1]->header.stamp.sec, msgs[1]->header.stamp.nsec,
787  labs((msgs[1]->header.stamp - msgs[0]->header.stamp).toNSec()) / 1000000.0);
788 #endif
789 }
790 
791 void DbwNode::recvCanGps(const std::vector<can_msgs::Frame::ConstPtr> &msgs) {
792  ROS_ASSERT(msgs.size() == 3);
793  ROS_ASSERT(msgs[0]->id == ID_REPORT_GPS1);
794  ROS_ASSERT(msgs[1]->id == ID_REPORT_GPS2);
795  ROS_ASSERT(msgs[2]->id == ID_REPORT_GPS3);
796  if ((msgs[0]->dlc >= sizeof(MsgReportGps1)) && (msgs[1]->dlc >= sizeof(MsgReportGps2)) && (msgs[2]->dlc >= sizeof(MsgReportGps3))) {
797  const MsgReportGps1 *ptr1 = (const MsgReportGps1*)msgs[0]->data.elems;
798  const MsgReportGps2 *ptr2 = (const MsgReportGps2*)msgs[1]->data.elems;
799  const MsgReportGps3 *ptr3 = (const MsgReportGps3*)msgs[2]->data.elems;
800 
801  sensor_msgs::NavSatFix msg_fix;
802  msg_fix.header.stamp = msgs[0]->header.stamp;
803  msg_fix.latitude = (double)ptr1->latitude / 3e6;
804  msg_fix.longitude = (double)ptr1->longitude / 3e6;
805  msg_fix.altitude = 0.0;
806  msg_fix.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
807  msg_fix.status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
808  msg_fix.status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
809  pub_gps_fix_.publish(msg_fix);
810 
811  sensor_msgs::TimeReference msg_time;
812  struct tm unix_time;
813  unix_time.tm_year = ptr2->utc_year + 100; // [1900] <-- [2000]
814  unix_time.tm_mon = ptr2->utc_month - 1; // [0-11] <-- [1-12]
815  unix_time.tm_mday = ptr2->utc_day; // [1-31] <-- [1-31]
816  unix_time.tm_hour = ptr2->utc_hours; // [0-23] <-- [0-23]
817  unix_time.tm_min = ptr2->utc_minutes; // [0-59] <-- [0-59]
818  unix_time.tm_sec = ptr2->utc_seconds; // [0-59] <-- [0-59]
819  msg_time.header.stamp = msgs[0]->header.stamp;
820  msg_time.time_ref.sec = timegm(&unix_time);
821  msg_time.time_ref.nsec = 0;
822  pub_gps_time_.publish(msg_time);
823 
824  sensor_msgs::NavSatFix msg_fix_dr;
825  msg_fix_dr.header.stamp = msgs[2]->header.stamp;
826  msg_fix_dr.latitude = (double)ptr3->dr_latitude / 3e6;
827  msg_fix_dr.longitude = (double)ptr3->dr_longitude / 3e6;
828  msg_fix_dr.altitude = 0.0;
829  msg_fix_dr.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
830  msg_fix_dr.status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
831  pub_gps_fix_dr.publish(msg_fix_dr);
832 
833 #if 0
834  ROS_INFO("UTC Time: %04d-%02d-%02d %02d:%02d:%02d",
835  2000 + ptr2->utc_year, ptr2->utc_month, ptr2->utc_day,
836  ptr2->utc_hours, ptr2->utc_minutes, ptr2->utc_seconds);
837 #endif
838  }
839 #if 0
840  ROS_INFO("Time: %u.%u, %u.%u, %u.%u, delta: %fms",
841  msgs[0]->header.stamp.sec, msgs[0]->header.stamp.nsec,
842  msgs[1]->header.stamp.sec, msgs[1]->header.stamp.nsec,
843  msgs[2]->header.stamp.sec, msgs[2]->header.stamp.nsec,
844  std::max(std::max(
845  labs((msgs[1]->header.stamp - msgs[0]->header.stamp).toNSec()),
846  labs((msgs[2]->header.stamp - msgs[1]->header.stamp).toNSec())),
847  labs((msgs[0]->header.stamp - msgs[2]->header.stamp).toNSec())) / 1000000.0);
848 #endif
849 }
850 void DbwNode::recvBrakeCmd(const dbw_fca_msgs::BrakeCmd::ConstPtr& msg)
851 {
852  can_msgs::Frame out;
853  out.id = ID_BRAKE_CMD;
854  out.is_extended = false;
855  out.dlc = sizeof(MsgBrakeCmd);
856  MsgBrakeCmd *ptr = (MsgBrakeCmd*)out.data.elems;
857  memset(ptr, 0x00, sizeof(*ptr));
858  bool fwd_abs = firmware_.findModule(M_ABS).valid(); // Does the ABS braking module exist?
859  bool fwd = !pedal_luts_; // Forward command type, or apply pedal LUTs locally
860  fwd |= fwd_abs; // The local pedal LUTs are for the BPEC module, the ABS module requires forwarding
861  switch (msg->pedal_cmd_type) {
862  case dbw_fca_msgs::BrakeCmd::CMD_NONE:
863  break;
864  case dbw_fca_msgs::BrakeCmd::CMD_PEDAL:
865  ptr->CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_PEDAL;
866  ptr->PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
868  ROS_WARN_THROTTLE(1.0, "Module ABS does not support brake command type PEDAL");
869  }
870  break;
871  case dbw_fca_msgs::BrakeCmd::CMD_PERCENT:
872  if (fwd) {
873  ptr->CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_PERCENT;
874  ptr->PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
875  } else {
876  ptr->CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_PEDAL;
877  ptr->PCMD = std::clamp<float>(brakePedalFromPercent(msg->pedal_cmd) * UINT16_MAX, 0, UINT16_MAX);
878  }
879  break;
880  case dbw_fca_msgs::BrakeCmd::CMD_TORQUE:
881  if (fwd) {
882  ptr->CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_TORQUE;
883  ptr->PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
884  } else {
885  ptr->CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_PEDAL;
886  ptr->PCMD = std::clamp<float>(brakePedalFromTorque(msg->pedal_cmd) * UINT16_MAX, 0, UINT16_MAX);
887  }
889  ROS_WARN_THROTTLE(1.0, "Module ABS does not support brake command type TORQUE");
890  }
891  break;
892  case dbw_fca_msgs::BrakeCmd::CMD_TORQUE_RQ:
893  // CMD_TORQUE_RQ must be forwarded, there is no local implementation
894  ptr->CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_TORQUE_RQ;
895  ptr->PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
897  ROS_WARN_THROTTLE(1.0, "Module ABS does not support brake command type TORQUE_RQ");
898  }
899  break;
900  case dbw_fca_msgs::BrakeCmd::CMD_DECEL:
901  // CMD_DECEL must be forwarded, there is no local implementation
902  ptr->CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_DECEL;
903  ptr->PCMD = std::clamp<float>(msg->pedal_cmd * 1e3f, 0, 10e3);
905  ROS_WARN_THROTTLE(1.0, "Module BPEC does not support brake command type DECEL");
906  }
907  break;
908  default:
909  ROS_WARN("Unknown brake command type: %u", msg->pedal_cmd_type);
910  break;
911  }
912  if (enabled() && msg->enable) {
913  ptr->EN = 1;
914  }
915  if (clear() || msg->clear) {
916  ptr->CLEAR = 1;
917  }
918  if (msg->ignore) {
919  ptr->IGNORE = 1;
920  }
921  ptr->COUNT = msg->count;
922  pub_can_.publish(out);
923 }
924 
925 void DbwNode::recvThrottleCmd(const dbw_fca_msgs::ThrottleCmd::ConstPtr& msg)
926 {
927  can_msgs::Frame out;
928  out.id = ID_THROTTLE_CMD;
929  out.is_extended = false;
930  out.dlc = sizeof(MsgThrottleCmd);
931  MsgThrottleCmd *ptr = (MsgThrottleCmd*)out.data.elems;
932  memset(ptr, 0x00, sizeof(*ptr));
933  bool fwd = !pedal_luts_; // Forward command type, or apply pedal LUTs locally
934  float cmd = 0.0;
935  switch (msg->pedal_cmd_type) {
936  case dbw_fca_msgs::ThrottleCmd::CMD_NONE:
937  break;
938  case dbw_fca_msgs::ThrottleCmd::CMD_PEDAL:
939  ptr->CMD_TYPE = dbw_fca_msgs::ThrottleCmd::CMD_PEDAL;
940  cmd = msg->pedal_cmd;
941  break;
942  case dbw_fca_msgs::ThrottleCmd::CMD_PERCENT:
943  if (fwd) {
944  ptr->CMD_TYPE = dbw_fca_msgs::ThrottleCmd::CMD_PERCENT;
945  cmd = msg->pedal_cmd;
946  } else {
947  ptr->CMD_TYPE = dbw_fca_msgs::ThrottleCmd::CMD_PEDAL;
948  cmd = throttlePedalFromPercent(msg->pedal_cmd);
949  }
950  break;
951  default:
952  ROS_WARN("Unknown throttle command type: %u", msg->pedal_cmd_type);
953  break;
954  }
955  ptr->PCMD = std::clamp<float>(cmd * UINT16_MAX, 0, UINT16_MAX);
956  if (enabled() && msg->enable) {
957  ptr->EN = 1;
958  }
959  if (clear() || msg->clear) {
960  ptr->CLEAR = 1;
961  }
962  if (msg->ignore) {
963  ptr->IGNORE = 1;
964  }
965  ptr->COUNT = msg->count;
966  pub_can_.publish(out);
967 }
968 
969 void DbwNode::recvSteeringCmd(const dbw_fca_msgs::SteeringCmd::ConstPtr& msg)
970 {
971  can_msgs::Frame out;
972  out.id = ID_STEERING_CMD;
973  out.is_extended = false;
974  out.dlc = sizeof(MsgSteeringCmd);
975  MsgSteeringCmd *ptr = (MsgSteeringCmd*)out.data.elems;
976  memset(ptr, 0x00, sizeof(*ptr));
977  switch (msg->cmd_type) {
978  case dbw_fca_msgs::SteeringCmd::CMD_ANGLE:
979  ptr->SCMD = std::clamp<float>(msg->steering_wheel_angle_cmd * (float)(180 / M_PI * 10), -INT16_MAX, INT16_MAX);
980  if (fabsf(msg->steering_wheel_angle_velocity) > 0) {
982  ptr->SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (float)(180 / M_PI / 4)), 1, 254);
983  } else {
984  ptr->SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (float)(180 / M_PI / 2)), 1, 254);
985  }
986  }
987  ptr->CMD_TYPE = dbw_fca_msgs::SteeringCmd::CMD_ANGLE;
988  break;
989  case dbw_fca_msgs::SteeringCmd::CMD_TORQUE:
990  ptr->SCMD = std::clamp<float>(msg->steering_wheel_torque_cmd * 128, -INT16_MAX, INT16_MAX);
991  ptr->CMD_TYPE = dbw_fca_msgs::SteeringCmd::CMD_TORQUE;
992  break;
993  default:
994  ROS_WARN("Unknown steering command type: %u", msg->cmd_type);
995  break;
996  }
997  if (enabled() && msg->enable) {
998  ptr->EN = 1;
999  }
1000  if (clear() || msg->clear) {
1001  ptr->CLEAR = 1;
1002  }
1003  if (msg->ignore) {
1004  ptr->IGNORE = 1;
1005  }
1006  if (msg->quiet) {
1007  ptr->QUIET = 1;
1008  }
1009  if (msg->alert) {
1010  ptr->ALERT = 1;
1011  }
1012  ptr->COUNT = msg->count;
1013  pub_can_.publish(out);
1014 }
1015 
1016 void DbwNode::recvGearCmd(const dbw_fca_msgs::GearCmd::ConstPtr& msg)
1017 {
1018  can_msgs::Frame out;
1019  out.id = ID_GEAR_CMD;
1020  out.is_extended = false;
1021  out.dlc = sizeof(MsgGearCmd);
1022  MsgGearCmd *ptr = (MsgGearCmd*)out.data.elems;
1023  memset(ptr, 0x00, sizeof(*ptr));
1024  if (enabled()) {
1025  ptr->GCMD = msg->cmd.gear;
1026  }
1027  if (clear() || msg->clear) {
1028  ptr->CLEAR = 1;
1029  }
1030  pub_can_.publish(out);
1031 }
1032 
1033 void DbwNode::recvMiscCmd(const dbw_fca_msgs::MiscCmd::ConstPtr& msg)
1034 {
1035  can_msgs::Frame out;
1036  out.id = ID_MISC_CMD;
1037  out.is_extended = false;
1038  out.dlc = sizeof(MsgMiscCmd);
1039  MsgMiscCmd *ptr = (MsgMiscCmd*)out.data.elems;
1040  memset(ptr, 0x00, sizeof(*ptr));
1041  if (enabled()) {
1042  ptr->TRNCMD = msg->cmd.value;
1043  ptr->DOORSEL = msg->door.select;
1044  ptr->DOORCMD = msg->door.action;
1045  ptr->vent_md_cmd = msg->vent_mode.value;
1046  ptr->ft_drv_temp_cmd = msg->ft_drv_temp.value;
1047  ptr->ft_psg_temp_cmd = msg->ft_psg_temp.value;
1048  ptr->ft_fn_sp_cmd = msg->ft_fan_speed.value;
1049  ptr->sync = msg->sync.cmd;
1050  ptr->max_ac = msg->max_ac.cmd;
1051  ptr->ac = msg->ac.cmd;
1052  ptr->ft_hvac = msg->ft_hvac.cmd;
1053  ptr->auto_md = msg->auto_md.cmd;
1054  ptr->recirc = msg->recirc.cmd;
1055  ptr->sync = msg->sync.cmd;
1056  ptr->r_defr = msg->r_defr.cmd;
1057  ptr->f_defr = msg->f_defr.cmd;
1058  ptr->hsw_cmd = msg->heated_steering_wheel.cmd;
1059  ptr->fl_hs_cmd = msg->fl_heated_seat.value;
1060  ptr->fl_vs_cmd = msg->fl_vented_seat.value;
1061  ptr->fr_hs_cmd = msg->fr_heated_seat.value;
1062  ptr->fr_vs_cmd = msg->fr_vented_seat.value;
1063  }
1064  pub_can_.publish(out);
1065 }
1066 
1068 {
1069  bool en = enabled();
1070  bool change = prev_enable_ != en;
1071  if (change || force) {
1072  std_msgs::Bool msg;
1073  msg.data = en;
1074  pub_sys_enable_.publish(msg);
1075  }
1076  prev_enable_ = en;
1077  return change;
1078 }
1079 
1081 {
1082  // Publish status periodically, in addition to latched and on change
1083  if (publishDbwEnabled(true)) {
1084  ROS_WARN("DBW system enable status changed unexpectedly");
1085  }
1086 
1087  // Clear override statuses if necessary
1088  if (clear()) {
1089  can_msgs::Frame out;
1090  out.is_extended = false;
1091 
1092  if (override_brake_) {
1093  out.id = ID_BRAKE_CMD;
1094  out.dlc = 4; // Sending the full eight bytes will fault the watchdog counter (if enabled)
1095  memset(out.data.elems, 0x00, 8);
1096  ((MsgBrakeCmd*)out.data.elems)->CLEAR = 1;
1097  pub_can_.publish(out);
1098  }
1099 
1100  if (override_throttle_) {
1101  out.id = ID_THROTTLE_CMD;
1102  out.dlc = 4; // Sending the full eight bytes will fault the watchdog counter (if enabled)
1103  memset(out.data.elems, 0x00, 8);
1104  ((MsgThrottleCmd*)out.data.elems)->CLEAR = 1;
1105  pub_can_.publish(out);
1106  }
1107 
1108  if (override_steering_) {
1109  out.id = ID_STEERING_CMD;
1110  out.dlc = 4; // Sending the full eight bytes will fault the watchdog counter (if enabled)
1111  memset(out.data.elems, 0x00, 8);
1112  ((MsgSteeringCmd*)out.data.elems)->CLEAR = 1;
1113  pub_can_.publish(out);
1114  }
1115 
1116  if (override_gear_) {
1117  out.id = ID_GEAR_CMD;
1118  out.dlc = sizeof(MsgGearCmd);
1119  memset(out.data.elems, 0x00, 8);
1120  ((MsgGearCmd*)out.data.elems)->CLEAR = 1;
1121  pub_can_.publish(out);
1122  }
1123  }
1124 }
1125 
1127 {
1128  if (!enable_) {
1129  if (fault()) {
1130  if (fault_steering_cal_) {
1131  ROS_WARN("DBW system not enabled. Steering calibration fault.");
1132  }
1133  if (fault_brakes_) {
1134  ROS_WARN("DBW system not enabled. Braking fault.");
1135  }
1136  if (fault_throttle_) {
1137  ROS_WARN("DBW system not enabled. Throttle fault.");
1138  }
1139  if (fault_steering_) {
1140  ROS_WARN("DBW system not enabled. Steering fault.");
1141  }
1142  if (fault_watchdog_) {
1143  ROS_WARN("DBW system not enabled. Watchdog fault.");
1144  }
1145  } else {
1146  enable_ = true;
1147  if (publishDbwEnabled()) {
1148  ROS_INFO("DBW system enabled.");
1149  } else {
1150  ROS_INFO("DBW system enable requested. Waiting for ready.");
1151  }
1152  }
1153  }
1154 }
1155 
1157 {
1158  if (enable_) {
1159  enable_ = false;
1161  ROS_WARN("DBW system disabled.");
1162  }
1163 }
1164 
1166 {
1167  if (enable_) {
1168  enable_ = false;
1170  ROS_WARN("DBW system disabled. Cancel button pressed.");
1171  }
1172 }
1173 
1174 void DbwNode::overrideBrake(bool override, bool timeout)
1175 {
1176  bool en = enabled();
1177  if (en && timeout) {
1178  override = false;
1179  }
1180  if (en && override) {
1181  enable_ = false;
1182  }
1183  override_brake_ = override;
1184  if (publishDbwEnabled()) {
1185  if (en) {
1186  ROS_WARN("DBW system disabled. Driver override on brake/throttle pedal.");
1187  } else {
1188  ROS_INFO("DBW system enabled.");
1189  }
1190  }
1191 }
1192 
1193 void DbwNode::overrideThrottle(bool override, bool timeout)
1194 {
1195  bool en = enabled();
1196  if (en && timeout) {
1197  override = false;
1198  }
1199  if (en && override) {
1200  enable_ = false;
1201  }
1202  override_throttle_ = override;
1203  if (publishDbwEnabled()) {
1204  if (en) {
1205  ROS_WARN("DBW system disabled. Driver override on brake/throttle pedal.");
1206  } else {
1207  ROS_INFO("DBW system enabled.");
1208  }
1209  }
1210 }
1211 
1212 void DbwNode::overrideSteering(bool override, bool timeout)
1213 {
1214  bool en = enabled();
1215  if (en && timeout) {
1216  override = false;
1217  }
1218  if (en && override) {
1219  enable_ = false;
1220  }
1221  override_steering_ = override;
1222  if (publishDbwEnabled()) {
1223  if (en) {
1224  ROS_WARN("DBW system disabled. Driver override on steering wheel.");
1225  } else {
1226  ROS_INFO("DBW system enabled.");
1227  }
1228  }
1229 }
1230 
1231 void DbwNode::overrideGear(bool override)
1232 {
1233  bool en = enabled();
1234  if (en && override) {
1235  enable_ = false;
1236  }
1237  override_gear_ = override;
1238  if (publishDbwEnabled()) {
1239  if (en) {
1240  ROS_WARN("DBW system disabled. Driver override on shifter.");
1241  } else {
1242  ROS_INFO("DBW system enabled.");
1243  }
1244  }
1245 }
1246 
1247 void DbwNode::timeoutBrake(bool timeout, bool enabled)
1248 {
1249  if (!timeout_brakes_ && enabled_brakes_ && timeout && !enabled) {
1250  ROS_WARN("Brake subsystem disabled after 100ms command timeout");
1251  }
1252  timeout_brakes_ = timeout;
1254 }
1255 
1256 void DbwNode::timeoutThrottle(bool timeout, bool enabled)
1257 {
1258  if (!timeout_throttle_ && enabled_throttle_ && timeout && !enabled) {
1259  ROS_WARN("Throttle subsystem disabled after 100ms command timeout");
1260  }
1261  timeout_throttle_ = timeout;
1263 }
1264 
1265 void DbwNode::timeoutSteering(bool timeout, bool enabled)
1266 {
1267  if (!timeout_steering_ && enabled_steering_ && timeout && !enabled) {
1268  ROS_WARN("Steering subsystem disabled after 100ms command timeout");
1269  }
1270  timeout_steering_ = timeout;
1272 }
1273 
1275 {
1276  bool en = enabled();
1277  if (fault && en) {
1278  enable_ = false;
1279  }
1280  fault_brakes_ = fault;
1281  if (publishDbwEnabled()) {
1282  if (en) {
1283  ROS_ERROR("DBW system disabled. Braking fault.");
1284  } else {
1285  ROS_INFO("DBW system enabled.");
1286  }
1287  }
1288 }
1289 
1291 {
1292  bool en = enabled();
1293  if (fault && en) {
1294  enable_ = false;
1295  }
1297  if (publishDbwEnabled()) {
1298  if (en) {
1299  ROS_ERROR("DBW system disabled. Throttle fault.");
1300  } else {
1301  ROS_INFO("DBW system enabled.");
1302  }
1303  }
1304 }
1305 
1307 {
1308  bool en = enabled();
1309  if (fault && en) {
1310  enable_ = false;
1311  }
1313  if (publishDbwEnabled()) {
1314  if (en) {
1315  ROS_ERROR("DBW system disabled. Steering fault.");
1316  } else {
1317  ROS_INFO("DBW system enabled.");
1318  }
1319  }
1320 }
1321 
1323 {
1324  bool en = enabled();
1325  if (fault && en) {
1326  enable_ = false;
1327  }
1329  if (publishDbwEnabled()) {
1330  if (en) {
1331  ROS_ERROR("DBW system disabled. Steering calibration fault.");
1332  } else {
1333  ROS_INFO("DBW system enabled.");
1334  }
1335  }
1336 }
1337 
1338 void DbwNode::faultWatchdog(bool fault, uint8_t src, bool braking)
1339 {
1340  bool en = enabled();
1341  if (fault && en) {
1342  enable_ = false;
1343  }
1345  if (publishDbwEnabled()) {
1346  if (en) {
1347  ROS_ERROR("DBW system disabled. Watchdog fault.");
1348  } else {
1349  ROS_INFO("DBW system enabled.");
1350  }
1351  }
1352  if (braking && !fault_watchdog_using_brakes_) {
1353  ROS_WARN("Watchdog event: Alerting driver and applying brakes.");
1354  } else if (!braking && fault_watchdog_using_brakes_) {
1355  ROS_INFO("Watchdog event: Driver has successfully taken control.");
1356  }
1357  if (fault && src && !fault_watchdog_warned_) {
1358  switch (src) {
1359  case dbw_fca_msgs::WatchdogCounter::OTHER_BRAKE:
1360  ROS_WARN("Watchdog event: Fault determined by brake controller");
1361  break;
1362  case dbw_fca_msgs::WatchdogCounter::OTHER_THROTTLE:
1363  ROS_WARN("Watchdog event: Fault determined by throttle controller");
1364  break;
1365  case dbw_fca_msgs::WatchdogCounter::OTHER_STEERING:
1366  ROS_WARN("Watchdog event: Fault determined by steering controller");
1367  break;
1368  case dbw_fca_msgs::WatchdogCounter::BRAKE_COUNTER:
1369  ROS_WARN("Watchdog event: Brake command counter failed to increment");
1370  break;
1371  case dbw_fca_msgs::WatchdogCounter::BRAKE_DISABLED:
1372  ROS_WARN("Watchdog event: Brake transition to disabled while in gear or moving");
1373  break;
1374  case dbw_fca_msgs::WatchdogCounter::BRAKE_COMMAND:
1375  ROS_WARN("Watchdog event: Brake command timeout after 100ms");
1376  break;
1377  case dbw_fca_msgs::WatchdogCounter::BRAKE_REPORT:
1378  ROS_WARN("Watchdog event: Brake report timeout after 100ms");
1379  break;
1380  case dbw_fca_msgs::WatchdogCounter::THROTTLE_COUNTER:
1381  ROS_WARN("Watchdog event: Throttle command counter failed to increment");
1382  break;
1383  case dbw_fca_msgs::WatchdogCounter::THROTTLE_DISABLED:
1384  ROS_WARN("Watchdog event: Throttle transition to disabled while in gear or moving");
1385  break;
1386  case dbw_fca_msgs::WatchdogCounter::THROTTLE_COMMAND:
1387  ROS_WARN("Watchdog event: Throttle command timeout after 100ms");
1388  break;
1389  case dbw_fca_msgs::WatchdogCounter::THROTTLE_REPORT:
1390  ROS_WARN("Watchdog event: Throttle report timeout after 100ms");
1391  break;
1392  case dbw_fca_msgs::WatchdogCounter::STEERING_COUNTER:
1393  ROS_WARN("Watchdog event: Steering command counter failed to increment");
1394  break;
1395  case dbw_fca_msgs::WatchdogCounter::STEERING_DISABLED:
1396  ROS_WARN("Watchdog event: Steering transition to disabled while in gear or moving");
1397  break;
1398  case dbw_fca_msgs::WatchdogCounter::STEERING_COMMAND:
1399  ROS_WARN("Watchdog event: Steering command timeout after 100ms");
1400  break;
1401  case dbw_fca_msgs::WatchdogCounter::STEERING_REPORT:
1402  ROS_WARN("Watchdog event: Steering report timeout after 100ms");
1403  break;
1404  }
1405  fault_watchdog_warned_ = true;
1406  } else if (!fault) {
1407  fault_watchdog_warned_ = false;
1408  }
1409  fault_watchdog_using_brakes_ = braking;
1411  ROS_WARN_THROTTLE(2.0, "Watchdog event: Press left OK button on the steering wheel or cycle power to clear event.");
1412  }
1413 }
1414 
1415 void DbwNode::faultWatchdog(bool fault, uint8_t src) {
1416  faultWatchdog(fault, src, fault_watchdog_using_brakes_); // No change to 'using brakes' status
1417 }
1418 
1419 void DbwNode::publishJointStates(const ros::Time &stamp, const dbw_fca_msgs::SteeringReport *steering)
1420 {
1421  double dt = (stamp - joint_state_.header.stamp).toSec();
1422  if (steering) {
1423  if (std::isfinite(steering->steering_wheel_angle)) {
1424  const double L = acker_wheelbase_;
1425  const double W = acker_track_;
1426  const double r = L / tan(steering->steering_wheel_angle / steering_ratio_);
1427  joint_state_.position[JOINT_SL] = atan(L / (r - W/2));
1428  joint_state_.position[JOINT_SR] = atan(L / (r + W/2));
1429  }
1430  if (std::isfinite(steering->speed)) {
1431  joint_state_.velocity[JOINT_FL] = steering->speed / wheel_radius_;
1432  joint_state_.velocity[JOINT_FR] = steering->speed / wheel_radius_;
1433  joint_state_.velocity[JOINT_RL] = steering->speed / wheel_radius_;
1434  joint_state_.velocity[JOINT_RR] = steering->speed / wheel_radius_;
1435  }
1436  }
1437  if (dt < 0.5) {
1438  for (size_t i = JOINT_FL; i <= JOINT_RR; i++) {
1439  joint_state_.position[i] = fmod(joint_state_.position[i] + dt * joint_state_.velocity[i], 2*M_PI);
1440  }
1441  }
1442  joint_state_.header.stamp = stamp;
1444 }
1445 
1446 } // namespace dbw_fca_can
1447 
double steering_ratio_
Definition: DbwNode.h:177
bool fault_watchdog_warned_
Definition: DbwNode.h:107
void recvCAN(const can_msgs::Frame::ConstPtr &msg)
Definition: DbwNode.cpp:205
ros::Publisher pub_wheel_speeds_
Definition: DbwNode.h:202
ros::Publisher pub_gps_fix_
Definition: DbwNode.h:209
void overrideThrottle(bool override, bool timeout)
Definition: DbwNode.cpp:1193
ros::Subscriber sub_turn_signal_
Definition: DbwNode.h:191
ros::Publisher pub_misc_1_
Definition: DbwNode.h:200
void faultWatchdog(bool fault, uint8_t src, bool braking)
Definition: DbwNode.cpp:1338
ros::Publisher pub_imu_
Definition: DbwNode.h:208
void recvGearCmd(const dbw_fca_msgs::GearCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1016
double acker_wheelbase_
Definition: DbwNode.h:175
void timeoutThrottle(bool timeout, bool enabled)
Definition: DbwNode.cpp:1256
#define ROS_WARN_ONCE_ID(id,...)
Definition: DbwNode.cpp:54
f
#define ROS_INFO_ONCE(...)
ros::Publisher pub_gps_time_
Definition: DbwNode.h:210
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void overrideGear(bool override)
Definition: DbwNode.cpp:1231
ros::Subscriber sub_steering_
Definition: DbwNode.h:189
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_
Definition: DbwNode.h:188
string cmd
static const char * platformToString(Platform x)
bool enable_joint_states_
Definition: DbwNode.h:181
void recvThrottleCmd(const dbw_fca_msgs::ThrottleCmd::ConstPtr &msg)
Definition: DbwNode.cpp:925
void recvCanImu(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
Definition: DbwNode.cpp:755
void faultSteering(bool fault)
Definition: DbwNode.cpp:1306
ros::Subscriber sub_brake_
Definition: DbwNode.h:187
ros::Publisher pub_wheel_positions_
Definition: DbwNode.h:203
#define ROS_INFO_ONCE_ID(id,...)
Definition: DbwNode.cpp:53
ros::Publisher pub_gps_fix_dr
Definition: DbwNode.h:211
void recvBrakeCmd(const dbw_fca_msgs::BrakeCmd::ConstPtr &msg)
Definition: DbwNode.cpp:850
#define ROS_ERROR(...)
std::string vin_
Definition: DbwNode.h:155
void faultSteeringCal(bool fault)
Definition: DbwNode.cpp:1322
void faultThrottle(bool fault)
Definition: DbwNode.cpp:1290
struct dbw_fca_can::MsgLicense::@1::@9 vin0
#define ROS_WARN(...)
ros::Publisher pub_brake_info_
Definition: DbwNode.h:206
void recvSteeringCmd(const dbw_fca_msgs::SteeringCmd::ConstPtr &msg)
Definition: DbwNode.cpp:969
std::string frame_id_
Definition: DbwNode.h:163
ros::Subscriber sub_enable_
Definition: DbwNode.h:184
void recvDisable(const std_msgs::Empty::ConstPtr &msg)
Definition: DbwNode.cpp:200
static const char * moduleToString(Module x)
struct dbw_fca_can::MsgLicense::@1::@7 bdate0
ros::Publisher pub_throttle_info_
Definition: DbwNode.h:207
bool override_throttle_
Definition: DbwNode.h:98
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))}, })
ros::Publisher pub_brake_
Definition: DbwNode.h:196
std::map< uint8_t, std::string > bdate_
Definition: DbwNode.h:157
ros::Subscriber sub_can_
Definition: DbwNode.h:186
sensor_msgs::JointState joint_state_
Definition: DbwNode.h:146
#define ROS_DEBUG(...)
TransportHints & tcpNoDelay(bool nodelay=true)
static float brakePedalFromPercent(float percent)
Definition: pedal_lut.h:111
bool fault_watchdog_using_brakes_
Definition: DbwNode.h:106
ros::Publisher pub_can_
Definition: DbwNode.h:195
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ros::Publisher pub_joint_states_
Definition: DbwNode.h:212
void timerCallback(const ros::TimerEvent &event)
Definition: DbwNode.cpp:1080
PlatformMap firmware_
Definition: DbwNode.h:160
void publish(const boost::shared_ptr< M > &message) const
bool fault_steering_cal_
Definition: DbwNode.h:104
dataspeed_can_msg_filters::ApproximateTime sync_gps_
Definition: DbwNode.h:219
ros::Publisher pub_sys_enable_
Definition: DbwNode.h:215
struct dbw_fca_can::MsgLicense::@1::@6 mac
#define ROS_INFO_THROTTLE(period,...)
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)
Definition: DbwNode.cpp:195
ModuleVersion findModule(Module m) const
Definition: PlatformMap.h:65
uint16_t minor() const
Definition: ModuleVersion.h:63
#define ROS_WARN_THROTTLE(period,...)
#define ROS_INFO(...)
bool getParam(const std::string &key, std::string &s) const
ros::Publisher pub_throttle_
Definition: DbwNode.h:197
static float brakeTorqueFromPedal(float pedal)
Definition: pedal_lut.h:65
void timeoutBrake(bool timeout, bool enabled)
Definition: DbwNode.cpp:1247
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void overrideBrake(bool override, bool timeout)
Definition: DbwNode.cpp:1174
struct dbw_fca_can::MsgLicense::@1::@10 vin1
void overrideSteering(bool override, bool timeout)
Definition: DbwNode.cpp:1212
PlatformVersion findPlatform(Module m) const
Definition: PlatformMap.h:89
ros::Subscriber sub_gear_
Definition: DbwNode.h:190
dataspeed_can_msg_filters::ApproximateTime sync_imu_
Definition: DbwNode.h:218
bool publishDbwEnabled(bool force=false)
Definition: DbwNode.cpp:1067
void recvCanGps(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
Definition: DbwNode.cpp:791
struct dbw_fca_can::MsgLicense::@1::@11 vin2
static float brakePedalFromTorque(float torque)
Definition: pedal_lut.h:88
string NAME
uint16_t build() const
Definition: ModuleVersion.h:64
void faultBrakes(bool fault)
Definition: DbwNode.cpp:1274
ros::Publisher pub_misc_2_
Definition: DbwNode.h:201
void setInterMessageLowerBound(ros::Duration lower_bound)
ros::Publisher pub_gear_
Definition: DbwNode.h:199
#define ROS_WARN_COND(cond,...)
ros::Subscriber sub_disable_
Definition: DbwNode.h:185
DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
Definition: DbwNode.cpp:79
bool override_steering_
Definition: DbwNode.h:99
ros::Subscriber sub_misc_
Definition: DbwNode.h:192
static float throttlePedalFromPercent(float percent)
Definition: pedal_lut.h:115
const std::string header
struct dbw_fca_can::MsgLicense::@1::@3 license
PlatformMap FIRMWARE_LATEST({ {PlatformVersion(P_FCA_RU, M_BPEC, ModuleVersion(1, 6, 1))}, {PlatformVersion(P_FCA_RU, M_TPEC, ModuleVersion(1, 6, 1))}, {PlatformVersion(P_FCA_RU, M_STEER, ModuleVersion(1, 6, 1))}, {PlatformVersion(P_FCA_RU, M_SHIFT, ModuleVersion(1, 6, 1))}, {PlatformVersion(P_FCA_WK2, M_TPEC, ModuleVersion(1, 4, 1))}, {PlatformVersion(P_FCA_WK2, M_STEER, ModuleVersion(1, 4, 1))}, {PlatformVersion(P_FCA_WK2, M_SHIFT, ModuleVersion(1, 4, 1))}, {PlatformVersion(P_FCA_WK2, M_ABS, ModuleVersion(1, 4, 1))}, })
ros::Publisher pub_tire_pressure_
Definition: DbwNode.h:204
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
#define ROS_ASSERT(cond)
std::string ldate_
Definition: DbwNode.h:156
ros::Publisher pub_fuel_level_
Definition: DbwNode.h:205
void insert(Platform p, Module m, ModuleVersion v)
Definition: PlatformMap.h:59
ros::Timer timer_
Definition: DbwNode.h:94
void publishJointStates(const ros::Time &stamp, const dbw_fca_msgs::SteeringReport *steering)
Definition: DbwNode.cpp:1419
void recvMiscCmd(const dbw_fca_msgs::MiscCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1033
void timeoutSteering(bool timeout, bool enabled)
Definition: DbwNode.cpp:1265
ros::Publisher pub_twist_
Definition: DbwNode.h:213
ros::Publisher pub_vin_
Definition: DbwNode.h:214
uint16_t major() const
Definition: ModuleVersion.h:62
ros::Publisher pub_steering_
Definition: DbwNode.h:198
double wheel_radius_
Definition: DbwNode.h:178


dbw_fca_can
Author(s): Kevin Hallenbeck
autogenerated on Fri Jun 16 2023 02:36:28