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,4,2))},
64  {PlatformVersion(P_FCA_RU, M_TPEC, ModuleVersion(1,4,2))},
65  {PlatformVersion(P_FCA_RU, M_STEER, ModuleVersion(1,4,2))},
66  {PlatformVersion(P_FCA_RU, M_SHIFT, ModuleVersion(1,4,2))},
67  {PlatformVersion(P_FCA_WK2, M_TPEC, ModuleVersion(1,2,2))},
68  {PlatformVersion(P_FCA_WK2, M_STEER, ModuleVersion(1,2,2))},
69  {PlatformVersion(P_FCA_WK2, M_SHIFT, ModuleVersion(1,2,2))},
70  {PlatformVersion(P_FCA_WK2, M_ABS, ModuleVersion(1,2,2))},
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::recvTurnSignalCmd, 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 (ptr->SPEED == 0xFFFF) {
316  out.speed = NAN;
317  } else {
318  out.speed = (float)ptr->SPEED * (float)(0.01 / 3.6) * (float)speedSign();
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.override = ptr->OVERRIDE ? true : false;
358  out.fault_bus = ptr->FLTBUS ? true : false;
359  if (msg->dlc >= sizeof(MsgGearReport)) {
360  out.reject.value = ptr->REJECT;
361  if (out.reject.value == dbw_fca_msgs::GearReject::NONE) {
362  gear_warned_ = false;
363  } else if (!gear_warned_) {
364  gear_warned_ = true;
365  switch (out.reject.value) {
366  case dbw_fca_msgs::GearReject::SHIFT_IN_PROGRESS:
367  ROS_WARN("Gear shift rejected: Shift in progress");
368  break;
369  case dbw_fca_msgs::GearReject::OVERRIDE:
370  ROS_WARN("Gear shift rejected: Override on brake, throttle, or steering");
371  break;
372  case dbw_fca_msgs::GearReject::VEHICLE:
373  ROS_WARN("Gear shift rejected: Rejected by vehicle, try pressing the brakes");
374  break;
375  case dbw_fca_msgs::GearReject::UNSUPPORTED:
376  ROS_WARN("Gear shift rejected: Unsupported gear command");
377  break;
378  case dbw_fca_msgs::GearReject::FAULT:
379  ROS_WARN("Gear shift rejected: System in fault state");
380  break;
381  }
382  }
383  }
384  pub_gear_.publish(out);
385  }
386  break;
387 
388  case ID_MISC_REPORT:
389  if (msg->dlc >= sizeof(MsgMiscReport)) {
390  const MsgMiscReport *ptr = (const MsgMiscReport*)msg->data.elems;
391  if (buttons_) {
392  if (0) {
393  buttonCancel();
394  } else if ((ptr->btn_ld_left && ptr->btn_ld_down)) {
395  enableSystem();
396  }
397  }
398  dbw_fca_msgs::Misc1Report out;
399  out.header.stamp = msg->header.stamp;
400  out.turn_signal.value = ptr->turn_signal;
401  out.high_beam.value = ptr->head_light_hi;
402  out.wiper.status = ptr->wiper_front;
403  out.btn_cc_on_off = ptr->btn_cc_on_off ? true : false;
404  out.btn_cc_res = ptr->btn_cc_res ? true : false;
405  out.btn_cc_cncl = ptr->btn_cc_cncl ? true : false;
406  out.btn_cc_set_inc = ptr->btn_cc_set_inc ? true : false;
407  out.btn_cc_set_dec = ptr->btn_cc_set_dec ? true : false;
408  out.btn_cc_gap_inc = ptr->btn_cc_gap_inc ? true : false;
409  out.btn_cc_gap_dec = ptr->btn_cc_gap_dec ? true : false;
410  out.btn_cc_mode = ptr->btn_cc_mode ? true : false;
411  out.btn_ld_ok = ptr->btn_ld_ok ? true : false;
412  out.btn_ld_up = ptr->btn_ld_up ? true : false;
413  out.btn_ld_down = ptr->btn_ld_down ? true : false;
414  out.btn_ld_left = ptr->btn_ld_left ? true : false;
415  out.btn_ld_right = ptr->btn_ld_right ? true : false;
416  out.fault_bus = ptr->FLTBUS ? true : false;
417  out.door_rear_left = ptr->door_rear_left ? true : false;
418  out.door_rear_right = ptr->door_rear_right ? true : false;
419  out.door_trunk = ptr->door_trunk ? true : false;
420  pub_misc_1_.publish(out);
421  }
422  break;
423 
424  case ID_MISC2_REPORT:
425  if (msg->dlc >= sizeof(MsgMisc2Report)) {
426  const MsgMisc2Report *ptr = (const MsgMisc2Report*)msg->data.elems;
427  dbw_fca_msgs::Misc2Report out;
428  out.header.stamp = msg->header.stamp;
429  out.ft_drv_temp.value = ptr->ft_drv_temp_stat;
430  out.ft_psg_temp.value = ptr->ft_psg_temp_stat;
431  out.ft_fan_speed.value = ptr->ft_fn_sp_stat;
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;
440  out.vent_mode.value = ptr->vent_md_stat;
441  out.heated_steering_wheel = ptr->hsw_stat ? true : false;
442  out.fl_heated_seat.value = ptr->fl_hs_stat;
443  out.fl_vented_seat.value = ptr->fl_vs_stat;
444  out.fr_heated_seat.value = ptr->fr_hs_stat;
445  out.fr_vented_seat.value = ptr->fr_vs_stat;
446  pub_misc_2_.publish(out);
447  }
448  break;
449 
451  if (msg->dlc >= sizeof(MsgReportWheelSpeed)) {
452  const MsgReportWheelSpeed *ptr = (const MsgReportWheelSpeed*)msg->data.elems;
453  dbw_fca_msgs::WheelSpeedReport out;
454  out.header.stamp = msg->header.stamp;
455  if ((uint16_t)ptr->front_left == 0x8000) {
456  out.front_left = NAN;
457  } else {
458  out.front_left = (float)ptr->front_left * 0.01f;
459  }
460  if ((uint16_t)ptr->front_right == 0x8000) {
461  out.front_right = NAN;
462  } else {
463  out.front_right = (float)ptr->front_right * 0.01f;
464  }
465  if ((uint16_t)ptr->rear_left == 0x8000) {
466  out.rear_left = NAN;
467  } else {
468  out.rear_left = (float)ptr->rear_left * 0.01f;
469  }
470  if ((uint16_t)ptr->rear_right == 0x8000) {
471  out.rear_right = NAN;
472  } else {
473  out.rear_right = (float)ptr->rear_right * 0.01f;
474  }
476  }
477  break;
478 
480  if (msg->dlc >= sizeof(MsgReportWheelPosition)) {
481  const MsgReportWheelPosition *ptr = (const MsgReportWheelPosition*)msg->data.elems;
482  dbw_fca_msgs::WheelPositionReport out;
483  out.header.stamp = msg->header.stamp;
484  out.front_left = ptr->front_left;
485  out.front_right = ptr->front_right;
486  out.rear_left = ptr->rear_left;
487  out.rear_right = ptr->rear_right;
489  }
490  break;
491 
493  if (msg->dlc >= sizeof(MsgReportTirePressure)) {
494  const MsgReportTirePressure *ptr = (const MsgReportTirePressure*)msg->data.elems;
495  dbw_fca_msgs::TirePressureReport out;
496  out.header.stamp = msg->header.stamp;
497  if (ptr->front_left == 0xFFFF) {
498  out.front_left = NAN;
499  } else {
500  out.front_left = (float)ptr->front_left;
501  }
502  if (ptr->front_right == 0xFFFF) {
503  out.front_right = NAN;
504  } else {
505  out.front_right = (float)ptr->front_right;
506  }
507  if (ptr->rear_left == 0xFFFF) {
508  out.rear_left = NAN;
509  } else {
510  out.rear_left = (float)ptr->rear_left;
511  }
512  if (ptr->rear_right == 0xFFFF) {
513  out.rear_right = NAN;
514  } else {
515  out.rear_right = (float)ptr->rear_right;
516  }
518  }
519  break;
520 
521 
523  if (msg->dlc >= 2) {
524  const MsgReportFuelLevel *ptr = (const MsgReportFuelLevel*)msg->data.elems;
525  dbw_fca_msgs::FuelLevelReport out;
526  out.header.stamp = msg->header.stamp;
527  out.fuel_level = (float)ptr->fuel_level * 0.108696f;
528  if (msg->dlc >= sizeof(MsgReportFuelLevel)) {
529  out.battery_12v = (float)ptr->battery_12v * 0.0625f;
530  out.odometer = (float)ptr->odometer * 0.1f;
531  }
533  }
534  break;
535 
537  if (msg->dlc >= sizeof(MsgReportBrakeInfo)) {
538  const MsgReportBrakeInfo *ptr = (const MsgReportBrakeInfo*)msg->data.elems;
539  dbw_fca_msgs::BrakeInfoReport out;
540  out.header.stamp = msg->header.stamp;
541  if (ptr->brake_pc == 0xFF) {
542  out.brake_pc = NAN;
543  } else {
544  out.brake_pc = (float)ptr->brake_pc * 0.4f;
545  }
546  if (ptr->brake_torque_request == 0xFFF) {
547  out.brake_torque_request = NAN;
548  } else {
549  out.brake_torque_request = (float)ptr->brake_torque_request * 3.0f;
550  }
551  if (ptr->brake_torque_actual == 0xFFF) {
552  out.brake_torque_actual = NAN;
553  } else {
554  out.brake_torque_actual = (float)ptr->brake_torque_actual * 3.0f;
555  }
556  if (ptr->brake_pressure == 0x7FF) {
557  out.brake_pressure = NAN;
558  } else {
559  out.brake_pressure = (float)ptr->brake_pressure * 0.1f;
560  }
561  out.stationary = ptr->stationary;
563  }
564  break;
565 
567  if (msg->dlc >= sizeof(MsgReportThrottleInfo)) {
568  const MsgReportThrottleInfo *ptr = (const MsgReportThrottleInfo*)msg->data.elems;
569  dbw_fca_msgs::ThrottleInfoReport out;
570  out.header.stamp = msg->header.stamp;
571  if (ptr->throttle_pc == 0xFF) {
572  out.throttle_pc = NAN;
573  } else {
574  out.throttle_pc = (float)ptr->throttle_pc * 0.4f;
575  }
576  if ((uint16_t)ptr->axle_torque == 0xC000) {
577  out.axle_torque = NAN;
578  } else {
579  out.axle_torque = (float)ptr->axle_torque * 1.5625f;
580  }
581  out.gear_num.num = ptr->gear_num;
583  }
584  break;
585 
586  case ID_LICENSE:
587  if (msg->dlc >= sizeof(MsgLicense)) {
588  const MsgLicense *ptr = (const MsgLicense*)msg->data.elems;
589  const Module module = ptr->module ? (Module)ptr->module : M_STEER; // Legacy steering firmware reports zero for module
590  const char * str_m = moduleToString(module);
591  ROS_DEBUG("LICENSE(%x,%02X,%s)", ptr->module, ptr->mux, str_m);
592  if (ptr->ready) {
593  ROS_INFO_ONCE_ID(module, "Licensing: %s ready", str_m);
594  if (ptr->trial) {
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);
596  }
597  if (ptr->expired) {
598  ROS_WARN_ONCE_ID(module, "Licensing: %s one or more feature licenses expired due to the firmware build date", str_m);
599  }
600  } else if (module == M_STEER) {
601  ROS_INFO_THROTTLE(10.0, "Licensing: Waiting for VIN...");
602  } else {
603  ROS_INFO_THROTTLE(10.0, "Licensing: Waiting for required info...");
604  }
605  if (ptr->mux == LIC_MUX_LDATE0) {
606  if (ldate_.size() == 0) {
607  ldate_.push_back(ptr->ldate0.ldate0);
608  ldate_.push_back(ptr->ldate0.ldate1);
609  ldate_.push_back(ptr->ldate0.ldate2);
610  ldate_.push_back(ptr->ldate0.ldate3);
611  ldate_.push_back(ptr->ldate0.ldate4);
612  ldate_.push_back(ptr->ldate0.ldate5);
613  }
614  } else if (ptr->mux == LIC_MUX_LDATE1) {
615  if (ldate_.size() == 6) {
616  ldate_.push_back(ptr->ldate1.ldate6);
617  ldate_.push_back(ptr->ldate1.ldate7);
618  ldate_.push_back(ptr->ldate1.ldate8);
619  ldate_.push_back(ptr->ldate1.ldate9);
620  ROS_INFO("Licensing: %s license string date: %s", str_m, ldate_.c_str());
621  }
622  } else if (ptr->mux == LIC_MUX_MAC) {
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);
627  } else if (ptr->mux == LIC_MUX_BDATE0) {
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);
636  }
637  } else if (ptr->mux == LIC_MUX_BDATE1) {
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());
645  }
646  } else if (ptr->mux == LIC_MUX_VIN0) {
647  if (vin_.size() == 0) {
648  vin_.push_back(ptr->vin0.vin00);
649  vin_.push_back(ptr->vin0.vin01);
650  vin_.push_back(ptr->vin0.vin02);
651  vin_.push_back(ptr->vin0.vin03);
652  vin_.push_back(ptr->vin0.vin04);
653  vin_.push_back(ptr->vin0.vin05);
654  }
655  } else if (ptr->mux == LIC_MUX_VIN1) {
656  if (vin_.size() == 6) {
657  vin_.push_back(ptr->vin1.vin06);
658  vin_.push_back(ptr->vin1.vin07);
659  vin_.push_back(ptr->vin1.vin08);
660  vin_.push_back(ptr->vin1.vin09);
661  vin_.push_back(ptr->vin1.vin10);
662  vin_.push_back(ptr->vin1.vin11);
663  }
664  } else if (ptr->mux == LIC_MUX_VIN2) {
665  if (vin_.size() == 12) {
666  vin_.push_back(ptr->vin2.vin12);
667  vin_.push_back(ptr->vin2.vin13);
668  vin_.push_back(ptr->vin2.vin14);
669  vin_.push_back(ptr->vin2.vin15);
670  vin_.push_back(ptr->vin2.vin16);
671  std_msgs::String msg; msg.data = vin_;
672  pub_vin_.publish(msg);
673  ROS_INFO("Licensing: VIN: %s", vin_.c_str());
674  }
675  } else if ((LIC_MUX_F0 <= ptr->mux) && (ptr->mux <= LIC_MUX_F7)) {
676  constexpr std::array<const char*, 8> NAME = {"BASE","CONTROL","SENSORS","","","","",""};
677  const size_t i = ptr->mux - LIC_MUX_F0;
678  const int id = module * NAME.size() + i;
679  if (ptr->license.enabled) {
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]);
683  }
684  if (ptr->ready && (module == M_STEER) && (ptr->license.trial || !ptr->license.enabled)) {
685  ROS_INFO_ONCE("Licensing: Feature '%s' trials used: %u, remaining: %u", NAME[i],
686  ptr->license.trials_used, ptr->license.trials_left);
687  }
688  }
689  }
690  break;
691 
692  case ID_VERSION:
693  if (msg->dlc >= sizeof(MsgVersion)) {
694  const MsgVersion *ptr = (const MsgVersion*)msg->data.elems;
695  const PlatformVersion version((Platform)ptr->platform, (Module)ptr->module, ptr->major, ptr->minor, ptr->build);
696  const ModuleVersion latest = FIRMWARE_LATEST.findModule(version);
697  const char * str_p = platformToString(version.p);
698  const char * str_m = moduleToString(version.m);
699  if (firmware_.findModule(version) != version.v) {
700  firmware_.insert(version);
701  if (latest.valid()) {
702  ROS_INFO("Detected %s %s firmware version %u.%u.%u", str_p, str_m, ptr->major, ptr->minor, ptr->build);
703  } else {
704  ROS_WARN("Detected %s %s firmware version %u.%u.%u, which is unsupported. Platform: 0x%02X, Module: %u", str_p, str_m,
705  ptr->major, ptr->minor, ptr->build, ptr->platform, ptr->module);
706  }
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(),
710  latest.major(), latest.minor(), latest.build());
711  }
712  }
713  }
714  break;
715 
716  case ID_BRAKE_CMD:
717  ROS_WARN_COND(warn_cmds_ && !((const MsgBrakeCmd*)msg->data.elems)->RES1,
718  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Brake. Id: 0x%03X", ID_BRAKE_CMD);
719  break;
720  case ID_THROTTLE_CMD:
721  ROS_WARN_COND(warn_cmds_ && !((const MsgThrottleCmd*)msg->data.elems)->RES1,
722  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Throttle. Id: 0x%03X", ID_THROTTLE_CMD);
723  break;
724  case ID_STEERING_CMD:
725  ROS_WARN_COND(warn_cmds_ && !((const MsgSteeringCmd*)msg->data.elems)->RES1,
726  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Steering. Id: 0x%03X", ID_STEERING_CMD);
727  break;
728  case ID_GEAR_CMD:
729  ROS_WARN_COND(warn_cmds_ && !((const MsgGearCmd*)msg->data.elems)->RES1,
730  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Shifting. Id: 0x%03X", ID_GEAR_CMD);
731  break;
732  case ID_MISC_CMD:
733  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);
734  break;
735  }
736  }
737 #if 0
738  ROS_INFO("ena: %s, clr: %s, brake: %s, throttle: %s, steering: %s, gear: %s",
739  enabled() ? "true " : "false",
740  clear() ? "true " : "false",
741  override_brake_ ? "true " : "false",
742  override_throttle_ ? "true " : "false",
743  override_steering_ ? "true " : "false",
744  override_gear_ ? "true " : "false"
745  );
746 #endif
747 }
748 
749 void DbwNode::recvCanImu(const std::vector<can_msgs::Frame::ConstPtr> &msgs) {
750  ROS_ASSERT(msgs.size() == 2);
751  ROS_ASSERT(msgs[0]->id == ID_REPORT_ACCEL);
752  ROS_ASSERT(msgs[1]->id == ID_REPORT_GYRO);
753  if ((msgs[0]->dlc >= sizeof(MsgReportAccel)) && (msgs[1]->dlc >= sizeof(MsgReportGyro))) {
754  const MsgReportAccel *ptr_accel = (const MsgReportAccel*)msgs[0]->data.elems;
755  const MsgReportGyro *ptr_gyro = (const MsgReportGyro*)msgs[1]->data.elems;
756  sensor_msgs::Imu out;
757  out.header.stamp = msgs[0]->header.stamp;
758  out.header.frame_id = frame_id_;
759  out.orientation_covariance[0] = -1; // Orientation not present
760  if ((uint16_t)ptr_accel->accel_long == 0x8000) {
761  out.linear_acceleration.x = NAN;
762  } else {
763  out.linear_acceleration.x = (double)ptr_accel->accel_long * 0.01;
764  }
765  if ((uint16_t)ptr_accel->accel_lat == 0x8000) {
766  out.linear_acceleration.y = NAN;
767  } else {
768  out.linear_acceleration.y = (double)ptr_accel->accel_lat * -0.01;
769  }
770  if ((uint16_t)ptr_gyro->gyro_yaw == 0x8000) {
771  out.angular_velocity.z = NAN;
772  } else {
773  out.angular_velocity.z = (double)ptr_gyro->gyro_yaw * 0.0002;
774  }
775  pub_imu_.publish(out);
776  }
777 #if 0
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);
782 #endif
783 }
784 
785 void DbwNode::recvCanGps(const std::vector<can_msgs::Frame::ConstPtr> &msgs) {
786  ROS_ASSERT(msgs.size() == 3);
787  ROS_ASSERT(msgs[0]->id == ID_REPORT_GPS1);
788  ROS_ASSERT(msgs[1]->id == ID_REPORT_GPS2);
789  ROS_ASSERT(msgs[2]->id == ID_REPORT_GPS3);
790  if ((msgs[0]->dlc >= sizeof(MsgReportGps1)) && (msgs[1]->dlc >= sizeof(MsgReportGps2)) && (msgs[2]->dlc >= sizeof(MsgReportGps3))) {
791  const MsgReportGps1 *ptr1 = (const MsgReportGps1*)msgs[0]->data.elems;
792  const MsgReportGps2 *ptr2 = (const MsgReportGps2*)msgs[1]->data.elems;
793  const MsgReportGps3 *ptr3 = (const MsgReportGps3*)msgs[2]->data.elems;
794 
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;
803  pub_gps_fix_.publish(msg_fix);
804 
805  sensor_msgs::TimeReference msg_time;
806  struct tm unix_time;
807  unix_time.tm_year = ptr2->utc_year + 100; // [1900] <-- [2000]
808  unix_time.tm_mon = ptr2->utc_month - 1; // [0-11] <-- [1-12]
809  unix_time.tm_mday = ptr2->utc_day; // [1-31] <-- [1-31]
810  unix_time.tm_hour = ptr2->utc_hours; // [0-23] <-- [0-23]
811  unix_time.tm_min = ptr2->utc_minutes; // [0-59] <-- [0-59]
812  unix_time.tm_sec = ptr2->utc_seconds; // [0-59] <-- [0-59]
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;
816  pub_gps_time_.publish(msg_time);
817 
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;
825  pub_gps_fix_dr.publish(msg_fix_dr);
826 
827 #if 0
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);
831 #endif
832  }
833 #if 0
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,
838  std::max(std::max(
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);
842 #endif
843 }
844 void DbwNode::recvBrakeCmd(const dbw_fca_msgs::BrakeCmd::ConstPtr& msg)
845 {
846  can_msgs::Frame out;
847  out.id = ID_BRAKE_CMD;
848  out.is_extended = false;
849  out.dlc = sizeof(MsgBrakeCmd);
850  MsgBrakeCmd *ptr = (MsgBrakeCmd*)out.data.elems;
851  memset(ptr, 0x00, sizeof(*ptr));
852  bool fwd_abs = firmware_.findModule(M_ABS).valid(); // Does the ABS braking module exist?
853  bool fwd = !pedal_luts_; // Forward command type, or apply pedal LUTs locally
854  fwd |= fwd_abs; // The local pedal LUTs are for the BPEC module, the ABS module requires forwarding
855  switch (msg->pedal_cmd_type) {
856  case dbw_fca_msgs::BrakeCmd::CMD_NONE:
857  break;
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);
862  ROS_WARN_THROTTLE(1.0, "Module ABS does not support brake command type PEDAL");
863  }
864  break;
865  case dbw_fca_msgs::BrakeCmd::CMD_PERCENT:
866  if (fwd) {
867  ptr->CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_PERCENT;
868  ptr->PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
869  } else {
870  ptr->CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_PEDAL;
871  ptr->PCMD = std::clamp<float>(brakePedalFromPercent(msg->pedal_cmd) * UINT16_MAX, 0, UINT16_MAX);
872  }
873  break;
874  case dbw_fca_msgs::BrakeCmd::CMD_TORQUE:
875  if (fwd) {
876  ptr->CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_TORQUE;
877  ptr->PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
878  } else {
879  ptr->CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_PEDAL;
880  ptr->PCMD = std::clamp<float>(brakePedalFromTorque(msg->pedal_cmd) * UINT16_MAX, 0, UINT16_MAX);
881  }
883  ROS_WARN_THROTTLE(1.0, "Module ABS does not support brake command type TORQUE");
884  }
885  break;
886  case dbw_fca_msgs::BrakeCmd::CMD_TORQUE_RQ:
887  // CMD_TORQUE_RQ must be forwarded, there is no local implementation
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");
892  }
893  break;
894  case dbw_fca_msgs::BrakeCmd::CMD_DECEL:
895  // CMD_DECEL must be forwarded, there is no local implementation
896  ptr->CMD_TYPE = dbw_fca_msgs::BrakeCmd::CMD_DECEL;
897  ptr->PCMD = std::clamp<float>(msg->pedal_cmd * 1e3f, 0, 10e3);
899  ROS_WARN_THROTTLE(1.0, "Module BPEC does not support brake command type DECEL");
900  }
901  break;
902  default:
903  ROS_WARN("Unknown brake command type: %u", msg->pedal_cmd_type);
904  break;
905  }
906  if (enabled() && msg->enable) {
907  ptr->EN = 1;
908  }
909  if (clear() || msg->clear) {
910  ptr->CLEAR = 1;
911  }
912  if (msg->ignore) {
913  ptr->IGNORE = 1;
914  }
915  ptr->COUNT = msg->count;
916  pub_can_.publish(out);
917 }
918 
919 void DbwNode::recvThrottleCmd(const dbw_fca_msgs::ThrottleCmd::ConstPtr& msg)
920 {
921  can_msgs::Frame out;
922  out.id = ID_THROTTLE_CMD;
923  out.is_extended = false;
924  out.dlc = sizeof(MsgThrottleCmd);
925  MsgThrottleCmd *ptr = (MsgThrottleCmd*)out.data.elems;
926  memset(ptr, 0x00, sizeof(*ptr));
927  bool fwd = !pedal_luts_; // Forward command type, or apply pedal LUTs locally
928  float cmd = 0.0;
929  switch (msg->pedal_cmd_type) {
930  case dbw_fca_msgs::ThrottleCmd::CMD_NONE:
931  break;
932  case dbw_fca_msgs::ThrottleCmd::CMD_PEDAL:
933  ptr->CMD_TYPE = dbw_fca_msgs::ThrottleCmd::CMD_PEDAL;
934  cmd = msg->pedal_cmd;
935  break;
936  case dbw_fca_msgs::ThrottleCmd::CMD_PERCENT:
937  if (fwd) {
938  ptr->CMD_TYPE = dbw_fca_msgs::ThrottleCmd::CMD_PERCENT;
939  cmd = msg->pedal_cmd;
940  } else {
941  ptr->CMD_TYPE = dbw_fca_msgs::ThrottleCmd::CMD_PEDAL;
942  cmd = throttlePedalFromPercent(msg->pedal_cmd);
943  }
944  break;
945  default:
946  ROS_WARN("Unknown throttle command type: %u", msg->pedal_cmd_type);
947  break;
948  }
949  ptr->PCMD = std::clamp<float>(cmd * UINT16_MAX, 0, UINT16_MAX);
950  if (enabled() && msg->enable) {
951  ptr->EN = 1;
952  }
953  if (clear() || msg->clear) {
954  ptr->CLEAR = 1;
955  }
956  if (msg->ignore) {
957  ptr->IGNORE = 1;
958  }
959  ptr->COUNT = msg->count;
960  pub_can_.publish(out);
961 }
962 
963 void DbwNode::recvSteeringCmd(const dbw_fca_msgs::SteeringCmd::ConstPtr& msg)
964 {
965  can_msgs::Frame out;
966  out.id = ID_STEERING_CMD;
967  out.is_extended = false;
968  out.dlc = sizeof(MsgSteeringCmd);
969  MsgSteeringCmd *ptr = (MsgSteeringCmd*)out.data.elems;
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);
977  } else {
978  ptr->SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (float)(180 / M_PI / 2)), 1, 254);
979  }
980  }
981  ptr->CMD_TYPE = dbw_fca_msgs::SteeringCmd::CMD_ANGLE;
982  break;
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;
986  break;
987  default:
988  ROS_WARN("Unknown steering command type: %u", msg->cmd_type);
989  break;
990  }
991  if (enabled() && msg->enable) {
992  ptr->EN = 1;
993  }
994  if (clear() || msg->clear) {
995  ptr->CLEAR = 1;
996  }
997  if (msg->ignore) {
998  ptr->IGNORE = 1;
999  }
1000  if (msg->quiet) {
1001  ptr->QUIET = 1;
1002  }
1003  ptr->COUNT = msg->count;
1004  pub_can_.publish(out);
1005 }
1006 
1007 void DbwNode::recvGearCmd(const dbw_fca_msgs::GearCmd::ConstPtr& msg)
1008 {
1009  can_msgs::Frame out;
1010  out.id = ID_GEAR_CMD;
1011  out.is_extended = false;
1012  out.dlc = sizeof(MsgGearCmd);
1013  MsgGearCmd *ptr = (MsgGearCmd*)out.data.elems;
1014  memset(ptr, 0x00, sizeof(*ptr));
1015  if (enabled()) {
1016  ptr->GCMD = msg->cmd.gear;
1017  }
1018  if (clear() || msg->clear) {
1019  ptr->CLEAR = 1;
1020  }
1021  pub_can_.publish(out);
1022 }
1023 
1024 void DbwNode::recvTurnSignalCmd(const dbw_fca_msgs::MiscCmd::ConstPtr& msg)
1025 {
1026  recvMiscCmd(msg);
1027 }
1028 
1029 void DbwNode::recvMiscCmd(const dbw_fca_msgs::MiscCmd::ConstPtr& msg)
1030 {
1031  can_msgs::Frame out;
1032  out.id = ID_MISC_CMD;
1033  out.is_extended = false;
1034  out.dlc = sizeof(MsgMiscCmd);
1035  MsgMiscCmd *ptr = (MsgMiscCmd*)out.data.elems;
1036  memset(ptr, 0x00, sizeof(*ptr));
1037  if (enabled()) {
1038  ptr->TRNCMD = msg->cmd.value;
1039  ptr->DOORSEL = msg->door.select;
1040  ptr->DOORCMD = msg->door.action;
1041  ptr->vent_md_cmd = msg->vent_mode.value;
1042  ptr->ft_drv_temp_cmd = msg->ft_drv_temp.value;
1043  ptr->ft_psg_temp_cmd = msg->ft_psg_temp.value;
1044  ptr->ft_fn_sp_cmd = msg->ft_fan_speed.value;
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;
1059  }
1060  pub_can_.publish(out);
1061 }
1062 
1064 {
1065  bool change = false;
1066  bool en = enabled();
1067  if (prev_enable_ != en) {
1068  std_msgs::Bool msg;
1069  msg.data = en;
1070  pub_sys_enable_.publish(msg);
1071  change = true;
1072  }
1073  prev_enable_ = en;
1074  return change;
1075 }
1076 
1078 {
1079  if (clear()) {
1080  can_msgs::Frame out;
1081  out.is_extended = false;
1082 
1083  if (override_brake_) {
1084  out.id = ID_BRAKE_CMD;
1085  out.dlc = 4; // Sending the full eight bytes will fault the watchdog counter (if enabled)
1086  memset(out.data.elems, 0x00, 8);
1087  ((MsgBrakeCmd*)out.data.elems)->CLEAR = 1;
1088  pub_can_.publish(out);
1089  }
1090 
1091  if (override_throttle_) {
1092  out.id = ID_THROTTLE_CMD;
1093  out.dlc = 4; // Sending the full eight bytes will fault the watchdog counter (if enabled)
1094  memset(out.data.elems, 0x00, 8);
1095  ((MsgThrottleCmd*)out.data.elems)->CLEAR = 1;
1096  pub_can_.publish(out);
1097  }
1098 
1099  if (override_steering_) {
1100  out.id = ID_STEERING_CMD;
1101  out.dlc = 4; // Sending the full eight bytes will fault the watchdog counter (if enabled)
1102  memset(out.data.elems, 0x00, 8);
1103  ((MsgSteeringCmd*)out.data.elems)->CLEAR = 1;
1104  pub_can_.publish(out);
1105  }
1106 
1107  if (override_gear_) {
1108  out.id = ID_GEAR_CMD;
1109  out.dlc = sizeof(MsgGearCmd);
1110  memset(out.data.elems, 0x00, 8);
1111  ((MsgGearCmd*)out.data.elems)->CLEAR = 1;
1112  pub_can_.publish(out);
1113  }
1114  }
1115 }
1116 
1118 {
1119  if (!enable_) {
1120  if (fault()) {
1121  if (fault_steering_cal_) {
1122  ROS_WARN("DBW system not enabled. Steering calibration fault.");
1123  }
1124  if (fault_brakes_) {
1125  ROS_WARN("DBW system not enabled. Braking fault.");
1126  }
1127  if (fault_throttle_) {
1128  ROS_WARN("DBW system not enabled. Throttle fault.");
1129  }
1130  if (fault_steering_) {
1131  ROS_WARN("DBW system not enabled. Steering fault.");
1132  }
1133  if (fault_watchdog_) {
1134  ROS_WARN("DBW system not enabled. Watchdog fault.");
1135  }
1136  } else {
1137  enable_ = true;
1138  if (publishDbwEnabled()) {
1139  ROS_INFO("DBW system enabled.");
1140  } else {
1141  ROS_INFO("DBW system enable requested. Waiting for ready.");
1142  }
1143  }
1144  }
1145 }
1146 
1148 {
1149  if (enable_) {
1150  enable_ = false;
1152  ROS_WARN("DBW system disabled.");
1153  }
1154 }
1155 
1157 {
1158  if (enable_) {
1159  enable_ = false;
1161  ROS_WARN("DBW system disabled. Cancel button pressed.");
1162  }
1163 }
1164 
1165 void DbwNode::overrideBrake(bool override, bool timeout)
1166 {
1167  bool en = enabled();
1168  if (en && timeout) {
1169  override = false;
1170  }
1171  if (en && override) {
1172  enable_ = false;
1173  }
1174  override_brake_ = override;
1175  if (publishDbwEnabled()) {
1176  if (en) {
1177  ROS_WARN("DBW system disabled. Driver override on brake/throttle pedal.");
1178  } else {
1179  ROS_INFO("DBW system enabled.");
1180  }
1181  }
1182 }
1183 
1184 void DbwNode::overrideThrottle(bool override, bool timeout)
1185 {
1186  bool en = enabled();
1187  if (en && timeout) {
1188  override = false;
1189  }
1190  if (en && override) {
1191  enable_ = false;
1192  }
1193  override_throttle_ = override;
1194  if (publishDbwEnabled()) {
1195  if (en) {
1196  ROS_WARN("DBW system disabled. Driver override on brake/throttle pedal.");
1197  } else {
1198  ROS_INFO("DBW system enabled.");
1199  }
1200  }
1201 }
1202 
1203 void DbwNode::overrideSteering(bool override, bool timeout)
1204 {
1205  bool en = enabled();
1206  if (en && timeout) {
1207  override = false;
1208  }
1209  if (en && override) {
1210  enable_ = false;
1211  }
1212  override_steering_ = override;
1213  if (publishDbwEnabled()) {
1214  if (en) {
1215  ROS_WARN("DBW system disabled. Driver override on steering wheel.");
1216  } else {
1217  ROS_INFO("DBW system enabled.");
1218  }
1219  }
1220 }
1221 
1222 void DbwNode::overrideGear(bool override)
1223 {
1224  bool en = enabled();
1225  if (en && override) {
1226  enable_ = false;
1227  }
1228  override_gear_ = override;
1229  if (publishDbwEnabled()) {
1230  if (en) {
1231  ROS_WARN("DBW system disabled. Driver override on shifter.");
1232  } else {
1233  ROS_INFO("DBW system enabled.");
1234  }
1235  }
1236 }
1237 
1238 void DbwNode::timeoutBrake(bool timeout, bool enabled)
1239 {
1240  if (!timeout_brakes_ && enabled_brakes_ && timeout && !enabled) {
1241  ROS_WARN("Brake subsystem disabled after 100ms command timeout");
1242  }
1243  timeout_brakes_ = timeout;
1245 }
1246 
1247 void DbwNode::timeoutThrottle(bool timeout, bool enabled)
1248 {
1249  if (!timeout_throttle_ && enabled_throttle_ && timeout && !enabled) {
1250  ROS_WARN("Throttle subsystem disabled after 100ms command timeout");
1251  }
1252  timeout_throttle_ = timeout;
1254 }
1255 
1256 void DbwNode::timeoutSteering(bool timeout, bool enabled)
1257 {
1258  if (!timeout_steering_ && enabled_steering_ && timeout && !enabled) {
1259  ROS_WARN("Steering subsystem disabled after 100ms command timeout");
1260  }
1261  timeout_steering_ = timeout;
1263 }
1264 
1266 {
1267  bool en = enabled();
1268  if (fault && en) {
1269  enable_ = false;
1270  }
1271  fault_brakes_ = fault;
1272  if (publishDbwEnabled()) {
1273  if (en) {
1274  ROS_ERROR("DBW system disabled. Braking fault.");
1275  } else {
1276  ROS_INFO("DBW system enabled.");
1277  }
1278  }
1279 }
1280 
1282 {
1283  bool en = enabled();
1284  if (fault && en) {
1285  enable_ = false;
1286  }
1288  if (publishDbwEnabled()) {
1289  if (en) {
1290  ROS_ERROR("DBW system disabled. Throttle fault.");
1291  } else {
1292  ROS_INFO("DBW system enabled.");
1293  }
1294  }
1295 }
1296 
1298 {
1299  bool en = enabled();
1300  if (fault && en) {
1301  enable_ = false;
1302  }
1304  if (publishDbwEnabled()) {
1305  if (en) {
1306  ROS_ERROR("DBW system disabled. Steering fault.");
1307  } else {
1308  ROS_INFO("DBW system enabled.");
1309  }
1310  }
1311 }
1312 
1314 {
1315  bool en = enabled();
1316  if (fault && en) {
1317  enable_ = false;
1318  }
1320  if (publishDbwEnabled()) {
1321  if (en) {
1322  ROS_ERROR("DBW system disabled. Steering calibration fault.");
1323  } else {
1324  ROS_INFO("DBW system enabled.");
1325  }
1326  }
1327 }
1328 
1329 void DbwNode::faultWatchdog(bool fault, uint8_t src, bool braking)
1330 {
1331  bool en = enabled();
1332  if (fault && en) {
1333  enable_ = false;
1334  }
1336  if (publishDbwEnabled()) {
1337  if (en) {
1338  ROS_ERROR("DBW system disabled. Watchdog fault.");
1339  } else {
1340  ROS_INFO("DBW system enabled.");
1341  }
1342  }
1343  if (braking && !fault_watchdog_using_brakes_) {
1344  ROS_WARN("Watchdog event: Alerting driver and applying brakes.");
1345  } else if (!braking && fault_watchdog_using_brakes_) {
1346  ROS_INFO("Watchdog event: Driver has successfully taken control.");
1347  }
1348  if (fault && src && !fault_watchdog_warned_) {
1349  switch (src) {
1350  case dbw_fca_msgs::WatchdogCounter::OTHER_BRAKE:
1351  ROS_WARN("Watchdog event: Fault determined by brake controller");
1352  break;
1353  case dbw_fca_msgs::WatchdogCounter::OTHER_THROTTLE:
1354  ROS_WARN("Watchdog event: Fault determined by throttle controller");
1355  break;
1356  case dbw_fca_msgs::WatchdogCounter::OTHER_STEERING:
1357  ROS_WARN("Watchdog event: Fault determined by steering controller");
1358  break;
1359  case dbw_fca_msgs::WatchdogCounter::BRAKE_COUNTER:
1360  ROS_WARN("Watchdog event: Brake command counter failed to increment");
1361  break;
1362  case dbw_fca_msgs::WatchdogCounter::BRAKE_DISABLED:
1363  ROS_WARN("Watchdog event: Brake transition to disabled while in gear or moving");
1364  break;
1365  case dbw_fca_msgs::WatchdogCounter::BRAKE_COMMAND:
1366  ROS_WARN("Watchdog event: Brake command timeout after 100ms");
1367  break;
1368  case dbw_fca_msgs::WatchdogCounter::BRAKE_REPORT:
1369  ROS_WARN("Watchdog event: Brake report timeout after 100ms");
1370  break;
1371  case dbw_fca_msgs::WatchdogCounter::THROTTLE_COUNTER:
1372  ROS_WARN("Watchdog event: Throttle command counter failed to increment");
1373  break;
1374  case dbw_fca_msgs::WatchdogCounter::THROTTLE_DISABLED:
1375  ROS_WARN("Watchdog event: Throttle transition to disabled while in gear or moving");
1376  break;
1377  case dbw_fca_msgs::WatchdogCounter::THROTTLE_COMMAND:
1378  ROS_WARN("Watchdog event: Throttle command timeout after 100ms");
1379  break;
1380  case dbw_fca_msgs::WatchdogCounter::THROTTLE_REPORT:
1381  ROS_WARN("Watchdog event: Throttle report timeout after 100ms");
1382  break;
1383  case dbw_fca_msgs::WatchdogCounter::STEERING_COUNTER:
1384  ROS_WARN("Watchdog event: Steering command counter failed to increment");
1385  break;
1386  case dbw_fca_msgs::WatchdogCounter::STEERING_DISABLED:
1387  ROS_WARN("Watchdog event: Steering transition to disabled while in gear or moving");
1388  break;
1389  case dbw_fca_msgs::WatchdogCounter::STEERING_COMMAND:
1390  ROS_WARN("Watchdog event: Steering command timeout after 100ms");
1391  break;
1392  case dbw_fca_msgs::WatchdogCounter::STEERING_REPORT:
1393  ROS_WARN("Watchdog event: Steering report timeout after 100ms");
1394  break;
1395  }
1396  fault_watchdog_warned_ = true;
1397  } else if (!fault) {
1398  fault_watchdog_warned_ = false;
1399  }
1400  fault_watchdog_using_brakes_ = braking;
1402  ROS_WARN_THROTTLE(2.0, "Watchdog event: Press left OK button on the steering wheel or cycle power to clear event.");
1403  }
1404 }
1405 
1406 void DbwNode::faultWatchdog(bool fault, uint8_t src) {
1407  faultWatchdog(fault, src, fault_watchdog_using_brakes_); // No change to 'using brakes' status
1408 }
1409 
1410 void DbwNode::publishJointStates(const ros::Time &stamp, const dbw_fca_msgs::SteeringReport *steering)
1411 {
1412  double dt = (stamp - joint_state_.header.stamp).toSec();
1413  if (steering) {
1414  if (std::isfinite(steering->steering_wheel_angle)) {
1415  const double L = acker_wheelbase_;
1416  const double W = acker_track_;
1417  const double r = L / tan(steering->steering_wheel_angle / steering_ratio_);
1418  joint_state_.position[JOINT_SL] = atan(L / (r - W/2));
1419  joint_state_.position[JOINT_SR] = atan(L / (r + W/2));
1420  }
1421  if (std::isfinite(steering->speed)) {
1422  joint_state_.velocity[JOINT_FL] = steering->speed / wheel_radius_;
1423  joint_state_.velocity[JOINT_FR] = steering->speed / wheel_radius_;
1424  joint_state_.velocity[JOINT_RL] = steering->speed / wheel_radius_;
1425  joint_state_.velocity[JOINT_RR] = steering->speed / wheel_radius_;
1426  }
1427  }
1428  if (dt < 0.5) {
1429  for (size_t i = JOINT_FL; i <= JOINT_RR; i++) {
1430  joint_state_.position[i] = fmod(joint_state_.position[i] + dt * joint_state_.velocity[i], 2*M_PI);
1431  }
1432  }
1433  joint_state_.header.stamp = stamp;
1435 }
1436 
1437 } // namespace dbw_fca_can
1438 
double steering_ratio_
Definition: DbwNode.h:184
bool fault_watchdog_warned_
Definition: DbwNode.h:108
void recvCAN(const can_msgs::Frame::ConstPtr &msg)
Definition: DbwNode.cpp:205
ros::Publisher pub_wheel_speeds_
Definition: DbwNode.h:209
ros::Publisher pub_gps_fix_
Definition: DbwNode.h:216
void overrideThrottle(bool override, bool timeout)
Definition: DbwNode.cpp:1184
ros::Subscriber sub_turn_signal_
Definition: DbwNode.h:198
PlatformVersion findPlatform(Module m) const
Definition: PlatformMap.h:89
ros::Publisher pub_misc_1_
Definition: DbwNode.h:207
void faultWatchdog(bool fault, uint8_t src, bool braking)
Definition: DbwNode.cpp:1329
ros::Publisher pub_imu_
Definition: DbwNode.h:215
void recvGearCmd(const dbw_fca_msgs::GearCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1007
double acker_wheelbase_
Definition: DbwNode.h:182
void timeoutThrottle(bool timeout, bool enabled)
Definition: DbwNode.cpp:1247
#define ROS_WARN_THROTTLE(rate,...)
uint16_t minor() const
Definition: ModuleVersion.h:63
#define ROS_WARN_ONCE_ID(id,...)
Definition: DbwNode.cpp:54
void publish(const boost::shared_ptr< M > &message) const
f
#define ROS_INFO_ONCE(...)
ros::Publisher pub_gps_time_
Definition: DbwNode.h:217
void overrideGear(bool override)
Definition: DbwNode.cpp:1222
ros::Subscriber sub_steering_
Definition: DbwNode.h:196
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:195
string cmd
static const char * platformToString(Platform x)
bool enable_joint_states_
Definition: DbwNode.h:188
void recvThrottleCmd(const dbw_fca_msgs::ThrottleCmd::ConstPtr &msg)
Definition: DbwNode.cpp:919
void recvCanImu(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
Definition: DbwNode.cpp:749
void faultSteering(bool fault)
Definition: DbwNode.cpp:1297
ros::Subscriber sub_brake_
Definition: DbwNode.h:194
ros::Publisher pub_wheel_positions_
Definition: DbwNode.h:210
#define ROS_INFO_ONCE_ID(id,...)
Definition: DbwNode.cpp:53
ros::Publisher pub_gps_fix_dr
Definition: DbwNode.h:218
void recvBrakeCmd(const dbw_fca_msgs::BrakeCmd::ConstPtr &msg)
Definition: DbwNode.cpp:844
std::string vin_
Definition: DbwNode.h:162
void faultSteeringCal(bool fault)
Definition: DbwNode.cpp:1313
void faultThrottle(bool fault)
Definition: DbwNode.cpp:1281
struct dbw_fca_can::MsgLicense::@1::@9 vin0
ros::Publisher pub_brake_info_
Definition: DbwNode.h:213
void recvSteeringCmd(const dbw_fca_msgs::SteeringCmd::ConstPtr &msg)
Definition: DbwNode.cpp:963
std::string frame_id_
Definition: DbwNode.h:170
ros::Subscriber sub_enable_
Definition: DbwNode.h:191
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
#define ROS_WARN(...)
ros::Publisher pub_throttle_info_
Definition: DbwNode.h:214
bool override_throttle_
Definition: DbwNode.h:99
ros::Publisher pub_brake_
Definition: DbwNode.h:203
std::map< uint8_t, std::string > bdate_
Definition: DbwNode.h:164
ros::Subscriber sub_can_
Definition: DbwNode.h:193
sensor_msgs::JointState joint_state_
Definition: DbwNode.h:147
uint16_t build() const
Definition: ModuleVersion.h:64
ModuleVersion findModule(Module m) const
Definition: PlatformMap.h:65
TransportHints & tcpNoDelay(bool nodelay=true)
static float brakePedalFromPercent(float percent)
Definition: pedal_lut.h:111
bool fault_watchdog_using_brakes_
Definition: DbwNode.h:107
ros::Publisher pub_can_
Definition: DbwNode.h:202
ros::Publisher pub_joint_states_
Definition: DbwNode.h:219
void timerCallback(const ros::TimerEvent &event)
Definition: DbwNode.cpp:1077
PlatformMap firmware_
Definition: DbwNode.h:167
bool fault_steering_cal_
Definition: DbwNode.h:105
dataspeed_can_msg_filters::ApproximateTime sync_gps_
Definition: DbwNode.h:226
ros::Publisher pub_sys_enable_
Definition: DbwNode.h:222
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)
Definition: DbwNode.cpp:195
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ros::Publisher pub_throttle_
Definition: DbwNode.h:204
static float brakeTorqueFromPedal(float pedal)
Definition: pedal_lut.h:65
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void timeoutBrake(bool timeout, bool enabled)
Definition: DbwNode.cpp:1238
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void overrideBrake(bool override, bool timeout)
Definition: DbwNode.cpp:1165
struct dbw_fca_can::MsgLicense::@1::@10 vin1
void overrideSteering(bool override, bool timeout)
Definition: DbwNode.cpp:1203
ros::Subscriber sub_gear_
Definition: DbwNode.h:197
dataspeed_can_msg_filters::ApproximateTime sync_imu_
Definition: DbwNode.h:225
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)
Definition: DbwNode.cpp:785
float speedSign() const
Definition: DbwNode.h:156
struct dbw_fca_can::MsgLicense::@1::@11 vin2
static float brakePedalFromTorque(float torque)
Definition: pedal_lut.h:88
string NAME
void faultBrakes(bool fault)
Definition: DbwNode.cpp:1265
ros::Publisher pub_misc_2_
Definition: DbwNode.h:208
bool getParam(const std::string &key, std::string &s) const
void setInterMessageLowerBound(ros::Duration lower_bound)
ros::Publisher pub_gear_
Definition: DbwNode.h:206
#define ROS_WARN_COND(cond,...)
ros::Subscriber sub_disable_
Definition: DbwNode.h:192
DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
Definition: DbwNode.cpp:79
#define ROS_INFO_THROTTLE(rate,...)
ros::Subscriber sub_misc_
Definition: DbwNode.h:199
static float throttlePedalFromPercent(float percent)
Definition: pedal_lut.h:115
struct dbw_fca_can::MsgLicense::@1::@3 license
void recvTurnSignalCmd(const dbw_fca_msgs::MiscCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1024
uint16_t major() const
Definition: ModuleVersion.h:62
ros::Publisher pub_tire_pressure_
Definition: DbwNode.h:211
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
#define ROS_ASSERT(cond)
std::string ldate_
Definition: DbwNode.h:163
ros::Publisher pub_fuel_level_
Definition: DbwNode.h:212
void insert(Platform p, Module m, ModuleVersion v)
Definition: PlatformMap.h:59
ros::Timer timer_
Definition: DbwNode.h:95
void publishJointStates(const ros::Time &stamp, const dbw_fca_msgs::SteeringReport *steering)
Definition: DbwNode.cpp:1410
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))},})
#define ROS_ERROR(...)
void recvMiscCmd(const dbw_fca_msgs::MiscCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1029
void timeoutSteering(bool timeout, bool enabled)
Definition: DbwNode.cpp:1256
ros::Publisher pub_twist_
Definition: DbwNode.h:220
ros::Publisher pub_vin_
Definition: DbwNode.h:221
#define ROS_DEBUG(...)
ros::Publisher pub_steering_
Definition: DbwNode.h:205
double wheel_radius_
Definition: DbwNode.h:185


dbw_fca_can
Author(s): Kevin Hallenbeck
autogenerated on Wed May 12 2021 02:14:05