DbwNode.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015-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_mkz_can/dispatch.h>
37 #include <dbw_mkz_can/pedal_lut.h>
38 #include <dbw_mkz_can/sonar_lut.h>
39 
40 // Log once per unique identifier, similar to ROS_LOG_ONCE()
41 #define ROS_LOG_ONCE_ID(id, level, name, ...) \
42  do \
43  { \
44  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
45  static std::map<int, bool> map; \
46  bool &hit = map[id]; \
47  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(!hit)) \
48  { \
49  hit = true; \
50  ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
51  } \
52  } while(false)
53 #define ROS_DEBUG_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
54 #define ROS_INFO_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
55 #define ROS_WARN_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
56 #define ROS_ERROR_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
57 #define ROS_FATAL_ONCE_ID(id, ...) ROS_LOG_ONCE_ID(id, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
58 
59 namespace dbw_mkz_can
60 {
61 
62 // Latest firmware versions
63 PlatformMap FIRMWARE_LATEST({
64  {PlatformVersion(P_FORD_C1, M_TPEC, ModuleVersion(1,3,3))},
65  {PlatformVersion(P_FORD_C1, M_STEER, ModuleVersion(1,3,3))},
66  {PlatformVersion(P_FORD_C1, M_SHIFT, ModuleVersion(1,3,3))},
67  {PlatformVersion(P_FORD_C1, M_ABS, ModuleVersion(1,3,3))},
68  {PlatformVersion(P_FORD_C1, M_BOO, ModuleVersion(1,3,3))},
69  {PlatformVersion(P_FORD_C1, M_EPS, ModuleVersion(1,3,3))},
70  {PlatformVersion(P_FORD_CD4, M_BPEC, ModuleVersion(2,6,3))},
71  {PlatformVersion(P_FORD_CD4, M_TPEC, ModuleVersion(2,6,3))},
72  {PlatformVersion(P_FORD_CD4, M_STEER, ModuleVersion(2,6,3))},
73  {PlatformVersion(P_FORD_CD4, M_SHIFT, ModuleVersion(2,6,3))},
74  {PlatformVersion(P_FORD_CD5, M_BOO, ModuleVersion(1,2,3))},
75  {PlatformVersion(P_FORD_CD5, M_TPEC, ModuleVersion(1,2,3))},
76  {PlatformVersion(P_FORD_CD5, M_STEER, ModuleVersion(1,2,3))},
77  {PlatformVersion(P_FORD_GE1, M_TPEC, ModuleVersion(1,0,3))},
78  {PlatformVersion(P_FORD_GE1, M_STEER, ModuleVersion(1,0,3))},
79  {PlatformVersion(P_FORD_GE1, M_SHIFT, ModuleVersion(1,0,3))},
80  {PlatformVersion(P_FORD_P5, M_TPEC, ModuleVersion(1,5,3))},
81  {PlatformVersion(P_FORD_P5, M_STEER, ModuleVersion(1,5,3))},
82  {PlatformVersion(P_FORD_P5, M_SHIFT, ModuleVersion(1,5,3))},
83  {PlatformVersion(P_FORD_P5, M_ABS, ModuleVersion(1,5,3))},
84  {PlatformVersion(P_FORD_P5, M_BOO, ModuleVersion(1,5,3))},
85  {PlatformVersion(P_FORD_P702, M_TPEC, ModuleVersion(0,1,3))},
86  {PlatformVersion(P_FORD_P702, M_STEER, ModuleVersion(0,1,3))},
87  {PlatformVersion(P_FORD_P702, M_SHIFT, ModuleVersion(0,1,3))},
88  {PlatformVersion(P_FORD_T6, M_TPEC, ModuleVersion(0,3,3))},
89  {PlatformVersion(P_FORD_T6, M_STEER, ModuleVersion(0,3,3))},
90  {PlatformVersion(P_FORD_T6, M_SHIFT, ModuleVersion(0,3,3))},
91  {PlatformVersion(P_FORD_U6, M_TPEC, ModuleVersion(1,1,3))},
92  {PlatformVersion(P_FORD_U6, M_STEER, ModuleVersion(1,1,3))},
93  {PlatformVersion(P_FORD_U6, M_SHIFT, ModuleVersion(1,1,3))},
94  {PlatformVersion(P_FORD_U6, M_ABS, ModuleVersion(1,1,3))},
95  {PlatformVersion(P_FORD_U6, M_BOO, ModuleVersion(1,1,3))},
96 });
97 
98 // Minimum firmware versions required for the timeout bit
99 PlatformMap FIRMWARE_TIMEOUT({
100  {PlatformVersion(P_FORD_CD4, M_BPEC, ModuleVersion(2,0,0))},
101  {PlatformVersion(P_FORD_CD4, M_TPEC, ModuleVersion(2,0,0))},
102  {PlatformVersion(P_FORD_CD4, M_STEER, ModuleVersion(2,0,0))},
103 });
104 
105 // Minimum firmware versions required for forwarding the command type
106 PlatformMap FIRMWARE_CMDTYPE({
107  {PlatformVersion(P_FORD_CD4, M_BPEC, ModuleVersion(2,0,7))},
108  {PlatformVersion(P_FORD_CD4, M_TPEC, ModuleVersion(2,0,7))},
109 });
110 
111 // Minimum firmware versions required for using the new SVEL resolution of 4 deg/s
112 PlatformMap FIRMWARE_HIGH_RATE_LIMIT({
113  {PlatformVersion(P_FORD_CD4, M_STEER, ModuleVersion(2,2,0))},
114  {PlatformVersion(P_FORD_P5, M_STEER, ModuleVersion(1,1,0))},
115 });
116 
118 : sync_imu_(10, boost::bind(&DbwNode::recvCanImu, this, _1), ID_REPORT_ACCEL, ID_REPORT_GYRO)
119 , sync_gps_(10, boost::bind(&DbwNode::recvCanGps, this, _1), ID_REPORT_GPS1, ID_REPORT_GPS2, ID_REPORT_GPS3)
120 {
121  // Reduce synchronization delay
122  sync_imu_.setInterMessageLowerBound(ros::Duration(0.003)); // 10ms period
124 
125  // Initialize enable state machine
126  prev_enable_ = true;
127  enable_ = false;
128  override_brake_ = false;
129  override_throttle_ = false;
130  override_steering_ = false;
131  override_gear_ = false;
132  fault_brakes_ = false;
133  fault_throttle_ = false;
134  fault_steering_ = false;
135  fault_steering_cal_ = false;
136  fault_watchdog_ = false;
138  fault_watchdog_warned_ = false;
139  timeout_brakes_ = false;
140  timeout_throttle_ = false;
141  timeout_steering_ = false;
142  enabled_brakes_ = false;
143  enabled_throttle_ = false;
144  enabled_steering_ = false;
145  gear_warned_ = false;
146 
147  // Frame ID
148  frame_id_ = "base_footprint";
149  priv_nh.getParam("frame_id", frame_id_);
150 
151  // Warn on received commands
152  warn_cmds_ = true;
153  priv_nh.getParam("warn_cmds", warn_cmds_);
154 
155  // Buttons (enable/disable)
156  buttons_ = true;
157  priv_nh.getParam("buttons", buttons_);
158 
159  // Pedal LUTs (local/embedded)
160  pedal_luts_ = false;
161  priv_nh.getParam("pedal_luts", pedal_luts_);
162 
163  // Ackermann steering parameters
164  acker_wheelbase_ = 2.8498; // 112.2 inches
165  acker_track_ = 1.5824; // 62.3 inches
166  steering_ratio_ = 14.8;
167  priv_nh.getParam("ackermann_wheelbase", acker_wheelbase_);
168  priv_nh.getParam("ackermann_track", acker_track_);
169  priv_nh.getParam("steering_ratio", steering_ratio_);
170 
171  // Initialize joint states
172  joint_state_.position.resize(JOINT_COUNT);
173  joint_state_.velocity.resize(JOINT_COUNT);
174  joint_state_.effort.resize(JOINT_COUNT);
175  joint_state_.name.resize(JOINT_COUNT);
176  joint_state_.name[JOINT_FL] = "wheel_fl_joint"; // Front Left
177  joint_state_.name[JOINT_FR] = "wheel_fr_joint"; // Front Right
178  joint_state_.name[JOINT_RL] = "wheel_rl_joint"; // Rear Left
179  joint_state_.name[JOINT_RR] = "wheel_rr_joint"; // Rear Right
180  joint_state_.name[JOINT_SL] = "steer_fl_joint";
181  joint_state_.name[JOINT_SR] = "steer_fr_joint";
182 
183  // Setup Publishers
184  pub_can_ = node.advertise<can_msgs::Frame>("can_tx", 10);
185  pub_brake_ = node.advertise<dbw_mkz_msgs::BrakeReport>("brake_report", 2);
186  pub_throttle_ = node.advertise<dbw_mkz_msgs::ThrottleReport>("throttle_report", 2);
187  pub_steering_ = node.advertise<dbw_mkz_msgs::SteeringReport>("steering_report", 2);
188  pub_gear_ = node.advertise<dbw_mkz_msgs::GearReport>("gear_report", 2);
189  pub_misc_1_ = node.advertise<dbw_mkz_msgs::Misc1Report>("misc_1_report", 2);
190  pub_wheel_speeds_ = node.advertise<dbw_mkz_msgs::WheelSpeedReport>("wheel_speed_report", 2);
191  pub_wheel_positions_ = node.advertise<dbw_mkz_msgs::WheelPositionReport>("wheel_position_report", 2);
192  pub_tire_pressure_ = node.advertise<dbw_mkz_msgs::TirePressureReport>("tire_pressure_report", 2);
193  pub_fuel_level_ = node.advertise<dbw_mkz_msgs::FuelLevelReport>("fuel_level_report", 2);
194  pub_surround_ = node.advertise<dbw_mkz_msgs::SurroundReport>("surround_report", 2);
195  pub_sonar_cloud_ = node.advertise<sensor_msgs::PointCloud2>("sonar_cloud", 2);
196  pub_brake_info_ = node.advertise<dbw_mkz_msgs::BrakeInfoReport>("brake_info_report", 2);
197  pub_throttle_info_ = node.advertise<dbw_mkz_msgs::ThrottleInfoReport>("throttle_info_report", 2);
198  pub_driver_assist_ = node.advertise<dbw_mkz_msgs::DriverAssistReport>("driver_assist_report", 2);
199  pub_imu_ = node.advertise<sensor_msgs::Imu>("imu/data_raw", 10);
200  pub_gps_fix_ = node.advertise<sensor_msgs::NavSatFix>("gps/fix", 10);
201  pub_gps_vel_ = node.advertise<geometry_msgs::TwistStamped>("gps/vel", 10);
202  pub_gps_time_ = node.advertise<sensor_msgs::TimeReference>("gps/time", 10);
203  pub_twist_ = node.advertise<geometry_msgs::TwistStamped>("twist", 10);
204  pub_vin_ = node.advertise<std_msgs::String>("vin", 1, true);
205  pub_sys_enable_ = node.advertise<std_msgs::Bool>("dbw_enabled", 1, true);
207 
208  // Publish joint states if enabled
209  priv_nh.param("joint_states", enable_joint_states_, true);
210  if (enable_joint_states_) {
211  pub_joint_states_ = node.advertise<sensor_msgs::JointState>("joint_states", 10);
212  }
213 
214  // Setup Subscribers
216  sub_enable_ = node.subscribe("enable", 10, &DbwNode::recvEnable, this, NODELAY);
217  sub_disable_ = node.subscribe("disable", 10, &DbwNode::recvDisable, this, NODELAY);
218  sub_can_ = node.subscribe("can_rx", 100, &DbwNode::recvCAN, this, NODELAY);
219  sub_brake_ = node.subscribe("brake_cmd", 1, &DbwNode::recvBrakeCmd, this, NODELAY);
220  sub_throttle_ = node.subscribe("throttle_cmd", 1, &DbwNode::recvThrottleCmd, this, NODELAY);
221  sub_steering_ = node.subscribe("steering_cmd", 1, &DbwNode::recvSteeringCmd, this, NODELAY);
222  sub_gear_ = node.subscribe("gear_cmd", 1, &DbwNode::recvGearCmd, this, NODELAY);
223  sub_turn_signal_ = node.subscribe("turn_signal_cmd", 1, &DbwNode::recvMiscCmd, this, NODELAY); // Backwards compatiblity
224  sub_misc_ = node.subscribe("misc_cmd", 1, &DbwNode::recvMiscCmd, this, NODELAY);
225 
226  // Setup Timer
227  timer_ = node.createTimer(ros::Duration(1 / 20.0), &DbwNode::timerCallback, this);
228 }
229 
231 {
232 }
233 
234 void DbwNode::recvEnable(const std_msgs::Empty::ConstPtr& msg)
235 {
236  enableSystem();
237 }
238 
239 void DbwNode::recvDisable(const std_msgs::Empty::ConstPtr& msg)
240 {
241  disableSystem();
242 }
243 
244 void DbwNode::recvCAN(const can_msgs::Frame::ConstPtr& msg)
245 {
246  sync_imu_.processMsg(msg);
247  sync_gps_.processMsg(msg);
248  if (!msg->is_rtr && !msg->is_error && !msg->is_extended) {
249  switch (msg->id) {
250  case ID_BRAKE_REPORT:
251  if (msg->dlc >= sizeof(MsgBrakeReport)) {
252  const MsgBrakeReport *ptr = (const MsgBrakeReport*)msg->data.elems;
253  faultBrakes(ptr->FLT1 || ptr->FLT2);
254  faultWatchdog(ptr->FLTWDC, ptr->WDCSRC, ptr->WDCBRK);
255  dbw_mkz_msgs::BrakeReport out;
256  out.header.stamp = msg->header.stamp;
257  if (ptr->BTYPE == 0 || firmware_.findModule(M_BPEC).valid()) {
258  // Brake pedal emulator for hybrid electric vehicles
259  out.pedal_input = (float)ptr->PI / UINT16_MAX;
260  out.pedal_cmd = (float)ptr->PC / UINT16_MAX;
261  out.pedal_output = (float)ptr->PO / UINT16_MAX;
262  out.torque_input = brakeTorqueFromPedal(out.pedal_input);
263  out.torque_cmd = brakeTorqueFromPedal(out.pedal_cmd);
264  out.torque_output = brakeTorqueFromPedal(out.pedal_output);
265  } else if (ptr->BTYPE == 1 || firmware_.findModule(M_ABS).valid()) {
266  // ACC/AEB braking for non-hybrid vehicles
267  out.torque_input = ptr->PI;
268  out.decel_cmd = ptr->PC * 1e-3f;
269  out.decel_output = ptr->PO * 1e-3f;
270  } else if (ptr->BTYPE == 2) {
271  // Brake pedal actuator for vehicles without brake-by-wire
272  out.torque_input = ptr->PI;
273  out.torque_cmd = ptr->PC;
274  out.torque_output = ptr->PO;
275  } else {
276  ROS_WARN_THROTTLE(5.0, "Unsupported brake report type: %u", ptr->BTYPE);
277  }
278  out.boo_cmd = ptr->BC ? true : false;
279  out.enabled = ptr->ENABLED ? true : false;
280  out.override = ptr->OVERRIDE ? true : false;
281  out.driver = ptr->DRIVER ? true : false;
282  out.watchdog_counter.source = ptr->WDCSRC;
283  out.watchdog_braking = ptr->WDCBRK ? true : false;
284  out.fault_wdc = ptr->FLTWDC ? true : false;
285  out.fault_ch1 = ptr->FLT1 ? true : false;
286  out.fault_ch2 = ptr->FLT2 ? true : false;
287  out.fault_power = ptr->FLTPWR ? true : false;
289  timeoutBrake(ptr->TMOUT, ptr->ENABLED);
290  out.timeout = ptr->TMOUT ? true : false;
291  }
292  overrideBrake(ptr->OVERRIDE, out.timeout);
293  pub_brake_.publish(out);
294  if (ptr->FLT1 || ptr->FLT2 || ptr->FLTPWR) {
295  ROS_WARN_THROTTLE(5.0, "Brake fault. FLT1: %s FLT2: %s FLTPWR: %s",
296  ptr->FLT1 ? "true, " : "false,",
297  ptr->FLT2 ? "true, " : "false,",
298  ptr->FLTPWR ? "true" : "false");
299  }
300  }
301  break;
302 
303  case ID_THROTTLE_REPORT:
304  if (msg->dlc >= sizeof(MsgThrottleReport)) {
305  const MsgThrottleReport *ptr = (const MsgThrottleReport*)msg->data.elems;
306  faultThrottle(ptr->FLT1 || ptr->FLT2);
307  faultWatchdog(ptr->FLTWDC, ptr->WDCSRC);
308  dbw_mkz_msgs::ThrottleReport out;
309  out.header.stamp = msg->header.stamp;
310  out.pedal_input = (float)ptr->PI / UINT16_MAX;
311  out.pedal_cmd = (float)ptr->PC / UINT16_MAX;
312  out.pedal_output = (float)ptr->PO / UINT16_MAX;
313  out.enabled = ptr->ENABLED ? true : false;
314  out.override = ptr->OVERRIDE ? true : false;
315  out.driver = ptr->DRIVER ? true : false;
316  out.watchdog_counter.source = ptr->WDCSRC;
317  out.fault_wdc = ptr->FLTWDC ? true : false;
318  out.fault_ch1 = ptr->FLT1 ? true : false;
319  out.fault_ch2 = ptr->FLT2 ? true : false;
320  out.fault_power = ptr->FLTPWR ? true : false;
322  timeoutThrottle(ptr->TMOUT, ptr->ENABLED);
323  out.timeout = ptr->TMOUT ? true : false;
324  }
325  overrideThrottle(ptr->OVERRIDE, out.timeout);
326  pub_throttle_.publish(out);
327  if (ptr->FLT1 || ptr->FLT2 || ptr->FLTPWR) {
328  ROS_WARN_THROTTLE(5.0, "Throttle fault. FLT1: %s FLT2: %s FLTPWR: %s",
329  ptr->FLT1 ? "true, " : "false,",
330  ptr->FLT2 ? "true, " : "false,",
331  ptr->FLTPWR ? "true" : "false");
332  }
333  }
334  break;
335 
336  case ID_STEERING_REPORT:
337  if (msg->dlc >= sizeof(MsgSteeringReport)) {
338  const MsgSteeringReport *ptr = (const MsgSteeringReport*)msg->data.elems;
339  faultSteering(ptr->FLTBUS1 || ptr->FLTBUS2);
340  faultSteeringCal(ptr->FLTCAL && (uint16_t)ptr->ANGLE == 0x8000);
341  faultWatchdog(ptr->FLTWDC);
342  dbw_mkz_msgs::SteeringReport out;
343  out.header.stamp = msg->header.stamp;
344  if ((uint16_t)ptr->ANGLE == 0x8000) {
345  out.steering_wheel_angle = NAN;
346  } else {
347  out.steering_wheel_angle = (float)ptr->ANGLE * (float)(0.1 * M_PI / 180);
348  }
349  out.steering_wheel_cmd_type = ptr->TMODE ? dbw_mkz_msgs::SteeringReport::CMD_TORQUE : dbw_mkz_msgs::SteeringReport::CMD_ANGLE;
350  if ((uint16_t)ptr->CMD == 0xC000) {
351  out.steering_wheel_cmd = NAN;
352  } else if (out.steering_wheel_cmd_type == dbw_mkz_msgs::SteeringReport::CMD_ANGLE) {
353  out.steering_wheel_cmd = (float)ptr->CMD * (float)(0.1 * M_PI / 180);
354  } else {
355  out.steering_wheel_cmd = (float)ptr->CMD / 128.0f;
356  }
357  if ((uint8_t)ptr->TORQUE == 0x80) {
358  out.steering_wheel_torque = NAN;
359  } else {
360  out.steering_wheel_torque = (float)ptr->TORQUE * (float)0.0625;
361  }
362  if ((uint16_t)ptr->VEH_VEL == 0x8000) {
363  out.speed = NAN;
364  } else {
365  out.speed = (float)ptr->VEH_VEL * (float)(0.01 / 3.6);
366  }
367  out.enabled = ptr->ENABLED ? true : false;
368  out.override = ptr->OVERRIDE ? true : false;
369  out.fault_wdc = ptr->FLTWDC ? true : false;
370  out.fault_bus1 = ptr->FLTBUS1 ? true : false;
371  out.fault_bus2 = ptr->FLTBUS2 ? true : false;
372  out.fault_calibration = ptr->FLTCAL ? true : false;
373  out.fault_power = ptr->FLTPWR ? true : false;
375  timeoutSteering(ptr->TMOUT, ptr->ENABLED);
376  out.timeout = ptr->TMOUT ? true : false;
377  }
378  overrideSteering(ptr->OVERRIDE, out.timeout);
379  pub_steering_.publish(out);
380  geometry_msgs::TwistStamped twist;
381  twist.header.stamp = out.header.stamp;
382  twist.header.frame_id = frame_id_;
383  twist.twist.linear.x = out.speed;
384  twist.twist.angular.z = out.speed * tan(out.steering_wheel_angle / steering_ratio_) / acker_wheelbase_;
385  pub_twist_.publish(twist);
386  if (enable_joint_states_) {
387  publishJointStates(msg->header.stamp, NULL, &out);
388  }
389  if (ptr->FLTBUS1 || ptr->FLTBUS2 || ptr->FLTPWR) {
390  ROS_WARN_THROTTLE(5.0, "Steering fault. FLT1: %s FLT2: %s FLTPWR: %s",
391  ptr->FLTBUS1 ? "true, " : "false,",
392  ptr->FLTBUS2 ? "true, " : "false,",
393  ptr->FLTPWR ? "true" : "false");
394  } else if (ptr->FLTCAL && (uint16_t)ptr->ANGLE == 0x8000) {
395  ROS_WARN_THROTTLE(5.0, "Steering calibration fault. Drive at least 25 mph for at least 10 seconds in a straight line.");
396  } else if (ptr->FLTCAL) {
397  ROS_WARN_THROTTLE(5.0, "Steering configuration fault. Contact support@dataspeedinc.com if not resolved in a few minutes.");
398  }
399  }
400  break;
401 
402  case ID_GEAR_REPORT:
403  if (msg->dlc >= 1) {
404  const MsgGearReport *ptr = (const MsgGearReport*)msg->data.elems;
405  overrideGear(ptr->OVERRIDE);
406  dbw_mkz_msgs::GearReport out;
407  out.header.stamp = msg->header.stamp;
408  out.state.gear = ptr->STATE;
409  out.cmd.gear = ptr->CMD;
410  out.ready = ptr->READY ? true : false;
411  out.override = ptr->OVERRIDE ? true : false;
412  out.fault_bus = ptr->FLTBUS ? true : false;
413  if (msg->dlc >= sizeof(MsgGearReport)) {
414  out.reject.value = ptr->REJECT;
415  if (out.reject.value == dbw_mkz_msgs::GearReject::NONE) {
416  gear_warned_ = false;
417  } else if (!gear_warned_) {
418  gear_warned_ = true;
419  switch (out.reject.value) {
420  case dbw_mkz_msgs::GearReject::SHIFT_IN_PROGRESS:
421  ROS_WARN("Gear shift rejected: Shift in progress");
422  break;
423  case dbw_mkz_msgs::GearReject::OVERRIDE:
424  ROS_WARN("Gear shift rejected: Override on brake, throttle, or steering");
425  break;
426  case dbw_mkz_msgs::GearReject::ROTARY_LOW:
427  ROS_WARN("Gear shift rejected: Rotary shifter can't shift to Low");
428  break;
429  case dbw_mkz_msgs::GearReject::ROTARY_PARK:
430  ROS_WARN("Gear shift rejected: Rotary shifter can't shift out of Park");
431  break;
432  case dbw_mkz_msgs::GearReject::VEHICLE:
433  ROS_WARN("Gear shift rejected: Rejected by vehicle, try pressing the brakes");
434  break;
435  case dbw_mkz_msgs::GearReject::UNSUPPORTED:
436  ROS_WARN("Gear shift rejected: Unsupported gear command");
437  break;
438  case dbw_mkz_msgs::GearReject::FAULT:
439  ROS_WARN("Gear shift rejected: System in fault state");
440  break;
441  }
442  }
443  }
444  pub_gear_.publish(out);
445  }
446  break;
447 
448  case ID_MISC_REPORT:
449  if (msg->dlc >= 3) {
450  const MsgMiscReport *ptr = (const MsgMiscReport*)msg->data.elems;
451  if (buttons_) {
452  if (ptr->btn_cc_gap_inc || ptr->btn_cc_cncl) {
453  buttonCancel();
454  } else if ((ptr->btn_cc_set_dec && ptr->btn_cc_gap_dec) || (ptr->btn_cc_set_inc && ptr->btn_cc_off) || (ptr->btn_cc_set_dec && ptr->btn_cc_res)) {
455  enableSystem();
456  }
457  }
458  dbw_mkz_msgs::Misc1Report out;
459  out.header.stamp = msg->header.stamp;
460  out.turn_signal.value = ptr->turn_signal;
461  out.high_beam_headlights = ptr->head_light_hi ? true : false;
462  out.wiper.status = ptr->wiper_front;
463  out.ambient_light.status = ptr->light_ambient;
464  out.btn_cc_on = ptr->btn_cc_on ? true : false;
465  out.btn_cc_off = ptr->btn_cc_off ? true : false;
466  out.btn_cc_on_off = ptr->btn_cc_on_off ? true : false;
467  out.btn_cc_res = ptr->btn_cc_res ? true : false;
468  out.btn_cc_cncl = ptr->btn_cc_cncl ? true : false;
469  out.btn_cc_res_cncl = ptr->btn_cc_res_cncl ? true : false;
470  out.btn_cc_res_inc = ptr->btn_cc_res_inc ? true : false;
471  out.btn_cc_res_dec = ptr->btn_cc_res_dec ? true : false;
472  out.btn_cc_set_inc = ptr->btn_cc_set_inc ? true : false;
473  out.btn_cc_set_dec = ptr->btn_cc_set_dec ? true : false;
474  out.btn_cc_gap_inc = ptr->btn_cc_gap_inc ? true : false;
475  out.btn_cc_gap_dec = ptr->btn_cc_gap_dec ? true : false;
476  out.btn_la_on_off = ptr->btn_la_on_off ? true : false;
477  out.fault_bus = ptr->FLTBUS ? true : false;
478  if (msg->dlc >= 5) {
479  out.door_driver = ptr->door_driver ? true : false;
480  out.door_passenger = ptr->door_passenger ? true : false;
481  out.door_rear_left = ptr->door_rear_left ? true : false;
482  out.door_rear_right = ptr->door_rear_right ? true : false;
483  out.door_hood = ptr->door_hood ? true : false;
484  out.door_trunk = ptr->door_trunk ? true : false;
485  out.passenger_detect = ptr->pasngr_detect ? true : false;
486  out.passenger_airbag = ptr->pasngr_airbag ? true : false;
487  out.buckle_driver = ptr->buckle_driver ? true : false;
488  out.buckle_passenger = ptr->buckle_pasngr ? true : false;
489  out.btn_ld_ok = ptr->btn_ld_ok ? true : false;
490  out.btn_ld_up = ptr->btn_ld_up ? true : false;
491  out.btn_ld_down = ptr->btn_ld_down ? true : false;
492  out.btn_ld_left = ptr->btn_ld_left ? true : false;
493  out.btn_ld_right = ptr->btn_ld_right ? true : false;
494  }
495  if (msg->dlc >= 8) {
496  out.btn_rd_ok = ptr->btn_rd_ok ? true : false;
497  out.btn_rd_up = ptr->btn_rd_up ? true : false;
498  out.btn_rd_down = ptr->btn_rd_down ? true : false;
499  out.btn_rd_left = ptr->btn_rd_left ? true : false;
500  out.btn_rd_right = ptr->btn_rd_right ? true : false;
501  out.btn_vol_inc = ptr->btn_vol_inc ? true : false;
502  out.btn_vol_dec = ptr->btn_vol_dec ? true : false;
503  out.btn_mute = ptr->btn_mute ? true : false;
504  out.btn_media = ptr->btn_media ? true : false;
505  out.btn_prev = ptr->btn_prev ? true : false;
506  out.btn_next = ptr->btn_next ? true : false;
507  out.btn_speak = ptr->btn_speak ? true : false;
508  out.btn_call_start = ptr->btn_call_start ? true : false;
509  out.btn_call_end = ptr->btn_call_end ? true : false;
510  }
511  if ((msg->dlc >= 8) && (ptr->outside_air_temp < 0xFE)) {
512  out.outside_temperature = ((float)ptr->outside_air_temp * 0.5f) - 40.0f;
513  } else {
514  out.outside_temperature = NAN;
515  }
516  pub_misc_1_.publish(out);
517  }
518  break;
519 
521  if (msg->dlc >= sizeof(MsgReportWheelSpeed)) {
522  const MsgReportWheelSpeed *ptr = (const MsgReportWheelSpeed*)msg->data.elems;
523  dbw_mkz_msgs::WheelSpeedReport out;
524  out.header.stamp = msg->header.stamp;
525  if ((uint16_t)ptr->front_left == 0x8000) {
526  out.front_left = NAN;
527  } else {
528  out.front_left = (float)ptr->front_left * 0.01f;
529  }
530  if ((uint16_t)ptr->front_right == 0x8000) {
531  out.front_right = NAN;
532  } else {
533  out.front_right = (float)ptr->front_right * 0.01f;
534  }
535  if ((uint16_t)ptr->rear_left == 0x8000) {
536  out.rear_left = NAN;
537  } else {
538  out.rear_left = (float)ptr->rear_left * 0.01f;
539  }
540  if ((uint16_t)ptr->rear_right == 0x8000) {
541  out.rear_right = NAN;
542  } else {
543  out.rear_right = (float)ptr->rear_right * 0.01f;
544  }
546  if (enable_joint_states_) {
547  publishJointStates(msg->header.stamp, &out, NULL);
548  }
549  }
550  break;
551 
553  if (msg->dlc >= sizeof(MsgReportWheelPosition)) {
554  const MsgReportWheelPosition *ptr = (const MsgReportWheelPosition*)msg->data.elems;
555  dbw_mkz_msgs::WheelPositionReport out;
556  out.header.stamp = msg->header.stamp;
557  out.front_left = ptr->front_left;
558  out.front_right = ptr->front_right;
559  out.rear_left = ptr->rear_left;
560  out.rear_right = ptr->rear_right;
562  }
563  break;
564 
566  if (msg->dlc >= sizeof(MsgReportTirePressure)) {
567  const MsgReportTirePressure *ptr = (const MsgReportTirePressure*)msg->data.elems;
568  dbw_mkz_msgs::TirePressureReport out;
569  out.header.stamp = msg->header.stamp;
570  if (ptr->front_left == 0xFFFF) {
571  out.front_left = NAN;
572  } else {
573  out.front_left = (float)ptr->front_left;
574  }
575  if (ptr->front_right == 0xFFFF) {
576  out.front_right = NAN;
577  } else {
578  out.front_right = (float)ptr->front_right;
579  }
580  if (ptr->rear_left == 0xFFFF) {
581  out.rear_left = NAN;
582  } else {
583  out.rear_left = (float)ptr->rear_left;
584  }
585  if (ptr->rear_right == 0xFFFF) {
586  out.rear_right = NAN;
587  } else {
588  out.rear_right = (float)ptr->rear_right;
589  }
591  }
592  break;
593 
595  if (msg->dlc >= 2) {
596  const MsgReportFuelLevel *ptr = (const MsgReportFuelLevel*)msg->data.elems;
597  dbw_mkz_msgs::FuelLevelReport out;
598  out.header.stamp = msg->header.stamp;
599  out.fuel_level = (float)ptr->fuel_level * 0.108696f;
600  if (msg->dlc >= sizeof(MsgReportFuelLevel)) {
601  out.battery_12v = (float)ptr->battery_12v * 0.0625f;
602  out.battery_hev = (float)ptr->battery_hev * 0.5f;
603  out.odometer = (float)ptr->odometer * 0.1f;
604  }
606  }
607  break;
608 
609  case ID_REPORT_SURROUND:
610  if (msg->dlc >= sizeof(MsgReportSurround)) {
611  const MsgReportSurround *ptr = (const MsgReportSurround*)msg->data.elems;
612  dbw_mkz_msgs::SurroundReport out;
613  out.header.stamp = msg->header.stamp;
614  out.cta_left_alert = ptr->l_cta_alert ? true : false;
615  out.cta_right_alert = ptr->r_cta_alert ? true : false;
616  out.cta_left_enabled = ptr->l_cta_enabled ? true : false;
617  out.cta_right_enabled = ptr->r_cta_enabled ? true : false;
618  out.blis_left_alert = ptr->l_blis_alert ? true : false;
619  out.blis_right_alert = ptr->r_blis_alert ? true : false;
620  out.blis_left_enabled = ptr->l_blis_enabled ? true : false;
621  out.blis_right_enabled = ptr->r_blis_enabled ? true : false;
622  out.sonar_enabled = ptr->sonar_enabled ? true : false;
623  out.sonar_fault = ptr->sonar_fault ? true : false;
624  if (out.sonar_enabled) {
625  out.sonar[0] = sonarMetersFromBits(ptr->sonar_00);
626  out.sonar[1] = sonarMetersFromBits(ptr->sonar_01);
627  out.sonar[2] = sonarMetersFromBits(ptr->sonar_02);
628  out.sonar[3] = sonarMetersFromBits(ptr->sonar_03);
629  out.sonar[4] = sonarMetersFromBits(ptr->sonar_04);
630  out.sonar[5] = sonarMetersFromBits(ptr->sonar_05);
631  out.sonar[6] = sonarMetersFromBits(ptr->sonar_06);
632  out.sonar[7] = sonarMetersFromBits(ptr->sonar_07);
633  out.sonar[8] = sonarMetersFromBits(ptr->sonar_08);
634  out.sonar[9] = sonarMetersFromBits(ptr->sonar_09);
635  out.sonar[10] = sonarMetersFromBits(ptr->sonar_10);
636  out.sonar[11] = sonarMetersFromBits(ptr->sonar_11);
637  }
638  pub_surround_.publish(out);
639  sensor_msgs::PointCloud2 cloud;
640  sonarBuildPointCloud2(cloud, out);
641  pub_sonar_cloud_.publish(cloud);
642  }
643  break;
644 
646  if (msg->dlc >= sizeof(MsgReportBrakeInfo)) {
647  const MsgReportBrakeInfo *ptr = (const MsgReportBrakeInfo*)msg->data.elems;
648  dbw_mkz_msgs::BrakeInfoReport out;
649  out.header.stamp = msg->header.stamp;
650  if (ptr->brake_torque_request == 0xFFF) {
651  out.brake_torque_request = NAN;
652  } else {
653  out.brake_torque_request = (float)ptr->brake_torque_request * 4.0f;
654  }
655  if (ptr->brake_torque_actual == 0xFFF) {
656  out.brake_torque_actual = NAN;
657  } else {
658  out.brake_torque_actual = (float)ptr->brake_torque_actual * 4.0f;
659  }
660  if ((uint16_t)ptr->wheel_torque == 0xE000) {
661  out.wheel_torque_actual = NAN;
662  } else {
663  out.wheel_torque_actual = (float)ptr->wheel_torque * 4.0f;
664  }
665  if ((uint16_t)ptr->accel_over_ground_est == 0xE00) {
666  out.accel_over_ground = NAN;
667  } else {
668  out.accel_over_ground = (float)ptr->accel_over_ground_est * 0.035f;
669  }
670  out.brake_pedal_qf.value = ptr->bped_qf;
671  out.hsa.status = ptr->hsa_stat;
672  out.hsa.mode = ptr->hsa_mode;
673  out.abs_active = ptr->abs_active ? true : false;
674  out.abs_enabled = ptr->abs_enabled ? true : false;
675  out.stab_active = ptr->stab_active ? true : false;
676  out.stab_enabled = ptr->stab_enabled ? true : false;
677  out.trac_active = ptr->trac_active ? true : false;
678  out.trac_enabled = ptr->trac_enabled ? true : false;
679  out.parking_brake.status = ptr->parking_brake;
680  out.stationary = ptr->stationary;
682  if (ptr->bped_qf != dbw_mkz_msgs::QualityFactor::OK) {
683  ROS_WARN_THROTTLE(5.0, "Brake pedal limp-home: %u", ptr->bped_qf);
684  }
685  }
686  break;
687 
689  if (msg->dlc >= sizeof(MsgReportThrottleInfo)) {
690  const MsgReportThrottleInfo *ptr = (const MsgReportThrottleInfo*)msg->data.elems;
691  dbw_mkz_msgs::ThrottleInfoReport out;
692  out.header.stamp = msg->header.stamp;
693  if (ptr->throttle_pc == 0x3FF) {
694  out.throttle_pc = NAN;
695  } else {
696  out.throttle_pc = (float)ptr->throttle_pc * 1e-3f;
697  }
698  if ((uint8_t)ptr->throttle_rate == 0x80) {
699  out.throttle_rate = NAN;
700  } else {
701  out.throttle_rate = (float)ptr->throttle_rate * 4e-4f;
702  }
703  out.throttle_pedal_qf.value = ptr->aped_qf;
704  if (ptr->engine_rpm == 0xFFFF) {
705  out.engine_rpm = NAN;
706  } else {
707  out.engine_rpm = (float)ptr->engine_rpm * 0.25f;
708  }
709  out.gear_num.num = ptr->gear_num;
710  out.ignition.value = ptr->ign_stat;
711  if ((uint16_t)ptr->batt_curr == 0xE000) {
712  out.batt_curr = NAN;
713  } else {
714  out.batt_curr = (float)ptr->batt_curr * 0.0625f;
715  }
717  if (ptr->aped_qf != dbw_mkz_msgs::QualityFactor::OK) {
718  ROS_WARN_THROTTLE(5.0, "Throttle pedal limp-home: %u", ptr->aped_qf);
719  }
720  }
721  break;
722 
724  if (msg->dlc >= sizeof(MsgReportDriverAssist)) {
725  const MsgReportDriverAssist *ptr = (const MsgReportDriverAssist*)msg->data.elems;
726  dbw_mkz_msgs::DriverAssistReport out;
727  out.header.stamp = msg->header.stamp;
728  out.decel = (float)ptr->decel * 0.0625f;
729  out.decel_src = ptr->decel_src;
730  out.fcw_enabled = ptr->fcw_enabled;
731  out.fcw_active = ptr->fcw_active;
732  out.aeb_enabled = ptr->aeb_enabled;
733  out.aeb_precharge = ptr->aeb_precharge;
734  out.aeb_braking = ptr->aeb_braking;
735  out.acc_enabled = ptr->acc_enabled;
736  out.acc_braking = ptr->acc_braking;
738  if (out.fcw_active) {
739  ROS_WARN_THROTTLE(5.0, "Forward collision warning activated!");
740  }
741  if (out.aeb_braking) {
742  ROS_WARN_THROTTLE(5.0, "Automatic emergency braking activated!");
743  }
744  }
745  break;
746 
747  case ID_LICENSE:
748  if (msg->dlc >= sizeof(MsgLicense)) {
749  const MsgLicense *ptr = (const MsgLicense*)msg->data.elems;
750  const Module module = ptr->module ? (Module)ptr->module : M_STEER; // Legacy steering firmware reports zero for module
751  const char * str_m = moduleToString(module);
752  ROS_DEBUG("LICENSE(%x,%02X,%s)", ptr->module, ptr->mux, str_m);
753  if (ptr->ready) {
754  ROS_INFO_ONCE_ID(module, "Licensing: %s ready", str_m);
755  if (ptr->trial) {
756  ROS_WARN_ONCE_ID(module, "Licensing: %s one or more features licensed as a counted trial. Visit https://www.dataspeedinc.com/products/maintenance-subscription/ to request a full license.", str_m);
757  }
758  if (ptr->expired) {
759  ROS_WARN_ONCE_ID(module, "Licensing: %s one or more feature licenses expired due to the firmware build date", str_m);
760  }
761  } else if (module == M_STEER) {
762  ROS_INFO_THROTTLE(10.0, "Licensing: Waiting for VIN...");
763  } else {
764  ROS_INFO_THROTTLE(10.0, "Licensing: Waiting for required info...");
765  }
766  if (ptr->mux == LIC_MUX_LDATE0) {
767  if (ldate_.size() == 0) {
768  ldate_.push_back(ptr->ldate0.ldate0);
769  ldate_.push_back(ptr->ldate0.ldate1);
770  ldate_.push_back(ptr->ldate0.ldate2);
771  ldate_.push_back(ptr->ldate0.ldate3);
772  ldate_.push_back(ptr->ldate0.ldate4);
773  ldate_.push_back(ptr->ldate0.ldate5);
774  }
775  } else if (ptr->mux == LIC_MUX_LDATE1) {
776  if (ldate_.size() == 6) {
777  ldate_.push_back(ptr->ldate1.ldate6);
778  ldate_.push_back(ptr->ldate1.ldate7);
779  ldate_.push_back(ptr->ldate1.ldate8);
780  ldate_.push_back(ptr->ldate1.ldate9);
781  ROS_INFO("Licensing: %s license string date: %s", str_m, ldate_.c_str());
782  }
783  } else if (ptr->mux == LIC_MUX_MAC) {
784  ROS_INFO_ONCE("Licensing: %s MAC: %02X:%02X:%02X:%02X:%02X:%02X", str_m,
785  ptr->mac.addr0, ptr->mac.addr1,
786  ptr->mac.addr2, ptr->mac.addr3,
787  ptr->mac.addr4, ptr->mac.addr5);
788  } else if (ptr->mux == LIC_MUX_BDATE0) {
789  std::string &bdate = bdate_[module];
790  if (bdate.size() == 0) {
791  bdate.push_back(ptr->bdate0.date0);
792  bdate.push_back(ptr->bdate0.date1);
793  bdate.push_back(ptr->bdate0.date2);
794  bdate.push_back(ptr->bdate0.date3);
795  bdate.push_back(ptr->bdate0.date4);
796  bdate.push_back(ptr->bdate0.date5);
797  }
798  } else if (ptr->mux == LIC_MUX_BDATE1) {
799  std::string &bdate = bdate_[module];
800  if (bdate.size() == 6) {
801  bdate.push_back(ptr->bdate1.date6);
802  bdate.push_back(ptr->bdate1.date7);
803  bdate.push_back(ptr->bdate1.date8);
804  bdate.push_back(ptr->bdate1.date9);
805  ROS_INFO("Licensing: %s firmware build date: %s", str_m, bdate.c_str());
806  }
807  } else if (ptr->mux == LIC_MUX_VIN0) {
808  if (vin_.size() == 0) {
809  vin_.push_back(ptr->vin0.vin00);
810  vin_.push_back(ptr->vin0.vin01);
811  vin_.push_back(ptr->vin0.vin02);
812  vin_.push_back(ptr->vin0.vin03);
813  vin_.push_back(ptr->vin0.vin04);
814  vin_.push_back(ptr->vin0.vin05);
815  }
816  } else if (ptr->mux == LIC_MUX_VIN1) {
817  if (vin_.size() == 6) {
818  vin_.push_back(ptr->vin1.vin06);
819  vin_.push_back(ptr->vin1.vin07);
820  vin_.push_back(ptr->vin1.vin08);
821  vin_.push_back(ptr->vin1.vin09);
822  vin_.push_back(ptr->vin1.vin10);
823  vin_.push_back(ptr->vin1.vin11);
824  }
825  } else if (ptr->mux == LIC_MUX_VIN2) {
826  if (vin_.size() == 12) {
827  vin_.push_back(ptr->vin2.vin12);
828  vin_.push_back(ptr->vin2.vin13);
829  vin_.push_back(ptr->vin2.vin14);
830  vin_.push_back(ptr->vin2.vin15);
831  vin_.push_back(ptr->vin2.vin16);
832  std_msgs::String msg; msg.data = vin_;
833  pub_vin_.publish(msg);
834  ROS_INFO("Licensing: VIN: %s", vin_.c_str());
835  }
836  } else if ((LIC_MUX_F0 <= ptr->mux) && (ptr->mux <= LIC_MUX_F7)) {
837  constexpr std::array<const char*, 8> NAME = {"BASE","CONTROL","SENSORS","REMOTE","","","",""};
838  constexpr std::array<bool, 8> WARN = {true, true, true, false, true, true, true, true};
839  const size_t i = ptr->mux - LIC_MUX_F0;
840  const int id = module * NAME.size() + i;
841  const std::string name = strcmp(NAME[i], "") ? NAME[i] : std::string(1, '0' + i);
842  if (ptr->license.enabled) {
843  ROS_INFO_ONCE_ID(id, "Licensing: %s feature '%s' enabled%s", str_m, name.c_str(), ptr->license.trial ? " as a counted trial" : "");
844  } else if (ptr->ready && !WARN[i]) {
845  ROS_INFO_ONCE_ID(id, "Licensing: %s feature '%s' not licensed.", str_m, name.c_str());
846  } else if (ptr->ready) {
847  ROS_WARN_ONCE_ID(id, "Licensing: %s feature '%s' not licensed. Visit https://www.dataspeedinc.com/products/maintenance-subscription/ to request a license.", str_m, name.c_str());
848  }
849  if (ptr->ready && (module == M_STEER) && (ptr->license.trial || (!ptr->license.enabled && WARN[i]))) {
850  ROS_INFO_ONCE("Licensing: Feature '%s' trials used: %u, remaining: %u", name.c_str(),
851  ptr->license.trials_used, ptr->license.trials_left);
852  }
853  }
854  }
855  break;
856 
857  case ID_VERSION:
858  if (msg->dlc >= sizeof(MsgVersion)) {
859  const MsgVersion *ptr = (const MsgVersion*)msg->data.elems;
860  const PlatformVersion version((Platform)ptr->platform, (Module)ptr->module, ptr->major, ptr->minor, ptr->build);
861  const ModuleVersion latest = FIRMWARE_LATEST.findModule(version);
862  const char * str_p = platformToString(version.p);
863  const char * str_m = moduleToString(version.m);
864  if (firmware_.findModule(version) != version.v) {
865  firmware_.insert(version);
866  if (latest.valid()) {
867  ROS_INFO("Detected %s %s firmware version %u.%u.%u", str_p, str_m, ptr->major, ptr->minor, ptr->build);
868  } else {
869  ROS_WARN("Detected %s %s firmware version %u.%u.%u, which is unsupported. Platform: 0x%02X, Module: %u", str_p, str_m,
870  ptr->major, ptr->minor, ptr->build, ptr->platform, ptr->module);
871  }
872  if (version < latest) {
873  ROS_WARN("Firmware %s %s has old version %u.%u.%u, updating to %u.%u.%u is suggested.", str_p, str_m,
874  version.v.major(), version.v.minor(), version.v.build(),
875  latest.major(), latest.minor(), latest.build());
876  }
877  }
878  }
879  break;
880 
881  case ID_BRAKE_CMD:
882  ROS_WARN_COND(warn_cmds_ && !((const MsgBrakeCmd*)msg->data.elems)->RES1 && !((const MsgBrakeCmd*)msg->data.elems)->RES2,
883  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Brake. Id: 0x%03X", ID_BRAKE_CMD);
884  break;
885  case ID_THROTTLE_CMD:
886  ROS_WARN_COND(warn_cmds_ && !((const MsgThrottleCmd*)msg->data.elems)->RES1 && !((const MsgThrottleCmd*)msg->data.elems)->RES2,
887  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Throttle. Id: 0x%03X", ID_THROTTLE_CMD);
888  break;
889  case ID_STEERING_CMD:
890  ROS_WARN_COND(warn_cmds_ && !((const MsgSteeringCmd*)msg->data.elems)->RES1 && !((const MsgSteeringCmd*)msg->data.elems)->RES2,
891  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Steering. Id: 0x%03X", ID_STEERING_CMD);
892  break;
893  case ID_GEAR_CMD:
894  ROS_WARN_COND(warn_cmds_ && !((const MsgGearCmd*)msg->data.elems)->RES1 && !((const MsgGearCmd*)msg->data.elems)->RES2,
895  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Shifting. Id: 0x%03X", ID_GEAR_CMD);
896  break;
897  case ID_MISC_CMD:
898  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);
899  break;
900  }
901  }
902 #if 0
903  ROS_INFO("ena: %s, clr: %s, brake: %s, throttle: %s, steering: %s, gear: %s",
904  enabled() ? "true " : "false",
905  clear() ? "true " : "false",
906  override_brake_ ? "true " : "false",
907  override_throttle_ ? "true " : "false",
908  override_steering_ ? "true " : "false",
909  override_gear_ ? "true " : "false"
910  );
911 #endif
912 }
913 
914 void DbwNode::recvCanImu(const std::vector<can_msgs::Frame::ConstPtr> &msgs) {
915  ROS_ASSERT(msgs.size() == 2);
916  ROS_ASSERT(msgs[0]->id == ID_REPORT_ACCEL);
917  ROS_ASSERT(msgs[1]->id == ID_REPORT_GYRO);
918  if ((msgs[0]->dlc >= sizeof(MsgReportAccel)) && (msgs[1]->dlc >= sizeof(MsgReportGyro))) {
919  const MsgReportAccel *ptr_accel = (const MsgReportAccel*)msgs[0]->data.elems;
920  const MsgReportGyro *ptr_gyro = (const MsgReportGyro*)msgs[1]->data.elems;
921  sensor_msgs::Imu out;
922  out.header.stamp = msgs[0]->header.stamp;
923  out.header.frame_id = frame_id_;
924  out.orientation_covariance[0] = -1; // Orientation not present
925  if ((uint16_t)ptr_accel->accel_long == 0x8000) {
926  out.linear_acceleration.x = NAN;
927  } else {
928  out.linear_acceleration.x = (double)ptr_accel->accel_long * 0.01;
929  }
930  if ((uint16_t)ptr_accel->accel_lat == 0x8000) {
931  out.linear_acceleration.y = NAN;
932  } else {
933  out.linear_acceleration.y = (double)ptr_accel->accel_lat * -0.01;
934  }
935  if ((uint16_t)ptr_accel->accel_vert == 0x8000) {
936  out.linear_acceleration.z = NAN;
937  } else {
938  out.linear_acceleration.z = (double)ptr_accel->accel_vert * -0.01;
939  }
940  if ((uint16_t)ptr_gyro->gyro_roll == 0x8000) {
941  out.angular_velocity.x = NAN;
942  } else {
943  out.angular_velocity.x = (double)ptr_gyro->gyro_roll * 0.0002;
944  }
945  if ((uint16_t)ptr_gyro->gyro_yaw == 0x8000) {
946  out.angular_velocity.z = NAN;
947  } else {
948  out.angular_velocity.z = (double)ptr_gyro->gyro_yaw * 0.0002;
949  }
950  pub_imu_.publish(out);
951  }
952 #if 0
953  ROS_INFO("Time: %u.%u, %u.%u, delta: %fms",
954  msgs[0]->header.stamp.sec, msgs[0]->header.stamp.nsec,
955  msgs[1]->header.stamp.sec, msgs[1]->header.stamp.nsec,
956  labs((msgs[1]->header.stamp - msgs[0]->header.stamp).toNSec()) / 1000000.0);
957 #endif
958 }
959 
960 void DbwNode::recvCanGps(const std::vector<can_msgs::Frame::ConstPtr> &msgs) {
961  ROS_ASSERT(msgs.size() == 3);
962  ROS_ASSERT(msgs[0]->id == ID_REPORT_GPS1);
963  ROS_ASSERT(msgs[1]->id == ID_REPORT_GPS2);
964  ROS_ASSERT(msgs[2]->id == ID_REPORT_GPS3);
965  if ((msgs[0]->dlc >= sizeof(MsgReportGps1)) && (msgs[1]->dlc >= sizeof(MsgReportGps2)) && (msgs[2]->dlc >= sizeof(MsgReportGps3))) {
966  const MsgReportGps1 *ptr1 = (const MsgReportGps1*)msgs[0]->data.elems;
967  const MsgReportGps2 *ptr2 = (const MsgReportGps2*)msgs[1]->data.elems;
968  const MsgReportGps3 *ptr3 = (const MsgReportGps3*)msgs[2]->data.elems;
969 
970  sensor_msgs::NavSatFix msg_fix;
971  msg_fix.header.stamp = msgs[0]->header.stamp;
972  msg_fix.latitude = (double)ptr1->latitude / 3e6;
973  msg_fix.longitude = (double)ptr1->longitude / 3e6;
974  msg_fix.altitude = (double)ptr3->altitude * 0.25;
975  msg_fix.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
976  msg_fix.status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
977  switch (ptr3->quality) {
978  case 0:
979  default:
980  msg_fix.status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
981  break;
982  case 1:
983  case 2:
984  msg_fix.status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
985  break;
986  }
987  pub_gps_fix_.publish(msg_fix);
988 
989  geometry_msgs::TwistStamped msg_vel;
990  msg_vel.header.stamp = msgs[0]->header.stamp;
991  double heading = (double)ptr3->heading * (0.01 * M_PI / 180);
992  double speed = (double)ptr3->speed * 0.44704;
993  msg_vel.twist.linear.x = cos(heading) * speed;
994  msg_vel.twist.linear.y = sin(heading) * speed;
995  pub_gps_vel_.publish(msg_vel);
996 
997  sensor_msgs::TimeReference msg_time;
998  struct tm unix_time;
999  unix_time.tm_year = ptr2->utc_year + 100; // [1900] <-- [2000]
1000  unix_time.tm_mon = ptr2->utc_month - 1; // [0-11] <-- [1-12]
1001  unix_time.tm_mday = ptr2->utc_day; // [1-31] <-- [1-31]
1002  unix_time.tm_hour = ptr2->utc_hours; // [0-23] <-- [0-23]
1003  unix_time.tm_min = ptr2->utc_minutes; // [0-59] <-- [0-59]
1004  unix_time.tm_sec = ptr2->utc_seconds; // [0-59] <-- [0-59]
1005  msg_time.header.stamp = msgs[0]->header.stamp;
1006  msg_time.time_ref.sec = timegm(&unix_time);
1007  msg_time.time_ref.nsec = 0;
1008  pub_gps_time_.publish(msg_time);
1009 
1010 #if 0
1011  ROS_INFO("UTC Time: %04d-%02d-%02d %02d:%02d:%02d",
1012  2000 + ptr2->utc_year, ptr2->utc_month, ptr2->utc_day,
1013  ptr2->utc_hours, ptr2->utc_minutes, ptr2->utc_seconds);
1014 #endif
1015  }
1016 #if 0
1017  ROS_INFO("Time: %u.%u, %u.%u, %u.%u, delta: %fms",
1018  msgs[0]->header.stamp.sec, msgs[0]->header.stamp.nsec,
1019  msgs[1]->header.stamp.sec, msgs[1]->header.stamp.nsec,
1020  msgs[2]->header.stamp.sec, msgs[2]->header.stamp.nsec,
1021  std::max(std::max(
1022  labs((msgs[1]->header.stamp - msgs[0]->header.stamp).toNSec()),
1023  labs((msgs[2]->header.stamp - msgs[1]->header.stamp).toNSec())),
1024  labs((msgs[0]->header.stamp - msgs[2]->header.stamp).toNSec())) / 1000000.0);
1025 #endif
1026 }
1027 
1028 void DbwNode::recvBrakeCmd(const dbw_mkz_msgs::BrakeCmd::ConstPtr& msg)
1029 {
1030  can_msgs::Frame out;
1031  out.id = ID_BRAKE_CMD;
1032  out.is_extended = false;
1033  out.dlc = sizeof(MsgBrakeCmd);
1034  MsgBrakeCmd *ptr = (MsgBrakeCmd*)out.data.elems;
1035  memset(ptr, 0x00, sizeof(*ptr));
1036  bool fwd_abs = firmware_.findModule(M_ABS).valid(); // Does the ABS braking module exist?
1037  bool fwd_bpe = firmware_.findPlatform(M_BPEC) >= FIRMWARE_CMDTYPE; // Minimum required BPEC firmware version
1038  bool fwd = !pedal_luts_; // Forward command type, or apply pedal LUTs locally
1039  fwd |= fwd_abs; // The local pedal LUTs are for the BPEC module, the ABS module requires forwarding
1040  fwd &= fwd_bpe; // Only modern BPEC firmware supports forwarding the command type
1041  switch (msg->pedal_cmd_type) {
1042  case dbw_mkz_msgs::BrakeCmd::CMD_NONE:
1043  break;
1044  case dbw_mkz_msgs::BrakeCmd::CMD_PEDAL:
1045  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1046  ptr->PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
1048  ROS_WARN_THROTTLE(1.0, "Module ABS does not support brake command type PEDAL");
1049  }
1050  break;
1051  case dbw_mkz_msgs::BrakeCmd::CMD_PERCENT:
1052  if (fwd) {
1053  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PERCENT;
1054  ptr->PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
1055  } else {
1056  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1057  ptr->PCMD = std::clamp<float>(brakePedalFromPercent(msg->pedal_cmd) * UINT16_MAX, 0, UINT16_MAX);
1058  }
1059  break;
1060  case dbw_mkz_msgs::BrakeCmd::CMD_TORQUE:
1061  if (fwd) {
1062  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE;
1063  ptr->PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1064  } else {
1065  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1066  ptr->PCMD = std::clamp<float>(brakePedalFromTorque(msg->pedal_cmd) * UINT16_MAX, 0, UINT16_MAX);
1067  }
1069  ROS_WARN_THROTTLE(1.0, "Module ABS does not support brake command type TORQUE");
1070  }
1071  break;
1072  case dbw_mkz_msgs::BrakeCmd::CMD_TORQUE_RQ:
1073  if (fwd_abs || fwd_bpe) {
1074  // CMD_TORQUE_RQ must be forwarded, there is no local implementation
1075  fwd = true;
1076  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE_RQ;
1077  ptr->PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1078  } else if (fwd) {
1079  // Fallback to forwarded CMD_TORQUE
1080  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE;
1081  ptr->PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1082  } else {
1083  // Fallback to local CMD_TORQUE
1084  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1085  ptr->PCMD = std::clamp<float>(brakePedalFromTorque(msg->pedal_cmd) * UINT16_MAX, 0, UINT16_MAX);
1086  }
1088  ROS_WARN_THROTTLE(1.0, "Module ABS does not support brake command type TORQUE_RQ");
1089  }
1090  break;
1091  case dbw_mkz_msgs::BrakeCmd::CMD_DECEL:
1092  // CMD_DECEL must be forwarded, there is no local implementation
1093  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_DECEL;
1094  ptr->PCMD = std::clamp<float>(msg->pedal_cmd * 1e3f, 0, 10e3);
1096  ROS_WARN_THROTTLE(1.0, "Module BPEC does not support brake command type DECEL");
1097  }
1098  break;
1099  default:
1100  ROS_WARN("Unknown brake command type: %u", msg->pedal_cmd_type);
1101  break;
1102  }
1103 #if 1 // Manually implement auto BOO control (brake lights) for legacy firmware
1104  ptr->ABOO = 1;
1105  const PlatformVersion firmware_bpec = firmware_.findPlatform(M_BPEC);
1106  if (firmware_bpec.v.valid() && (firmware_bpec < FIRMWARE_CMDTYPE)) {
1107  const uint16_t BOO_THRESH_LO = 0.20 * UINT16_MAX;
1108  const uint16_t BOO_THRESH_HI = 0.22 * UINT16_MAX;
1109  static bool boo_status_ = false;
1110  if (boo_status_) {
1111  ptr->BCMD = 1;
1112  }
1113  if (!boo_status_ && (ptr->PCMD > BOO_THRESH_HI)) {
1114  ptr->BCMD = 1;
1115  boo_status_ = true;
1116  } else if (boo_status_ && (ptr->PCMD < BOO_THRESH_LO)) {
1117  ptr->BCMD = 0;
1118  boo_status_ = false;
1119  }
1120  }
1121 #endif
1122  if (enabled() && msg->enable) {
1123  ptr->EN = 1;
1124  }
1125  if (clear() || msg->clear) {
1126  ptr->CLEAR = 1;
1127  }
1128  if (msg->ignore) {
1129  ptr->IGNORE = 1;
1130  }
1131  ptr->COUNT = msg->count;
1132  pub_can_.publish(out);
1133 }
1134 
1135 void DbwNode::recvThrottleCmd(const dbw_mkz_msgs::ThrottleCmd::ConstPtr& msg)
1136 {
1137  can_msgs::Frame out;
1138  out.id = ID_THROTTLE_CMD;
1139  out.is_extended = false;
1140  out.dlc = sizeof(MsgThrottleCmd);
1141  MsgThrottleCmd *ptr = (MsgThrottleCmd*)out.data.elems;
1142  memset(ptr, 0x00, sizeof(*ptr));
1143  bool fwd = !pedal_luts_; // Forward command type, or apply pedal LUTs locally
1144  fwd &= firmware_.findPlatform(M_TPEC) >= FIRMWARE_CMDTYPE; // Minimum required firmware version
1145  float cmd = 0.0;
1146  switch (msg->pedal_cmd_type) {
1147  case dbw_mkz_msgs::ThrottleCmd::CMD_NONE:
1148  break;
1149  case dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL:
1150  ptr->CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL;
1151  cmd = msg->pedal_cmd;
1152  break;
1153  case dbw_mkz_msgs::ThrottleCmd::CMD_PERCENT:
1154  if (fwd) {
1155  ptr->CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PERCENT;
1156  cmd = msg->pedal_cmd;
1157  } else {
1158  ptr->CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL;
1159  cmd = throttlePedalFromPercent(msg->pedal_cmd);
1160  }
1161  break;
1162  default:
1163  ROS_WARN("Unknown throttle command type: %u", msg->pedal_cmd_type);
1164  break;
1165  }
1166  ptr->PCMD = std::clamp<float>(cmd * UINT16_MAX, 0, UINT16_MAX);
1167  if (enabled() && msg->enable) {
1168  ptr->EN = 1;
1169  }
1170  if (clear() || msg->clear) {
1171  ptr->CLEAR = 1;
1172  }
1173  if (msg->ignore) {
1174  ptr->IGNORE = 1;
1175  }
1176  ptr->COUNT = msg->count;
1177  pub_can_.publish(out);
1178 }
1179 
1180 void DbwNode::recvSteeringCmd(const dbw_mkz_msgs::SteeringCmd::ConstPtr& msg)
1181 {
1182  can_msgs::Frame out;
1183  out.id = ID_STEERING_CMD;
1184  out.is_extended = false;
1185  out.dlc = sizeof(MsgSteeringCmd);
1186  MsgSteeringCmd *ptr = (MsgSteeringCmd*)out.data.elems;
1187  memset(ptr, 0x00, sizeof(*ptr));
1188  switch (msg->cmd_type) {
1189  case dbw_mkz_msgs::SteeringCmd::CMD_ANGLE:
1190  ptr->SCMD = std::clamp<float>(msg->steering_wheel_angle_cmd * (float)(180 / M_PI * 10), -INT16_MAX, INT16_MAX);
1191  if (fabsf(msg->steering_wheel_angle_velocity) > 0) {
1193  ptr->SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (float)(180 / M_PI / 4)), 1, 254);
1194  } else {
1195  ptr->SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (float)(180 / M_PI / 2)), 1, 254);
1196  }
1197  }
1198  ptr->CMD_TYPE = dbw_mkz_msgs::SteeringCmd::CMD_ANGLE;
1199  break;
1200  case dbw_mkz_msgs::SteeringCmd::CMD_TORQUE:
1201  ptr->SCMD = std::clamp<float>(msg->steering_wheel_torque_cmd * 128, -INT16_MAX, INT16_MAX);
1202  ptr->CMD_TYPE = dbw_mkz_msgs::SteeringCmd::CMD_TORQUE;
1204  ROS_WARN_THROTTLE(1.0, "Module STEER does not support steering command type TORQUE");
1205  }
1206  break;
1207  default:
1208  ROS_WARN("Unknown steering command type: %u", msg->cmd_type);
1209  break;
1210  }
1211  if (enabled() && msg->enable) {
1212  ptr->EN = 1;
1213  }
1214  if (clear() || msg->clear) {
1215  ptr->CLEAR = 1;
1216  }
1217  if (msg->ignore) {
1218  ptr->IGNORE = 1;
1219  }
1220  if (msg->quiet) {
1221  ptr->QUIET = 1;
1222  }
1223  if (msg->alert) {
1224  ptr->ALERT = 1;
1225  }
1226  ptr->COUNT = msg->count;
1227  pub_can_.publish(out);
1228 }
1229 
1230 void DbwNode::recvGearCmd(const dbw_mkz_msgs::GearCmd::ConstPtr& msg)
1231 {
1232  can_msgs::Frame out;
1233  out.id = ID_GEAR_CMD;
1234  out.is_extended = false;
1235  out.dlc = sizeof(MsgGearCmd);
1236  MsgGearCmd *ptr = (MsgGearCmd*)out.data.elems;
1237  memset(ptr, 0x00, sizeof(*ptr));
1238  if (enabled()) {
1239  ptr->GCMD = msg->cmd.gear;
1240  }
1241  if (clear() || msg->clear) {
1242  ptr->CLEAR = 1;
1243  }
1244  pub_can_.publish(out);
1245 }
1246 
1247 void DbwNode::recvMiscCmd(const dbw_mkz_msgs::MiscCmd::ConstPtr& msg)
1248 {
1249  can_msgs::Frame out;
1250  out.id = ID_MISC_CMD;
1251  out.is_extended = false;
1252  out.dlc = sizeof(MsgMiscCmd);
1253  MsgMiscCmd *ptr = (MsgMiscCmd*)out.data.elems;
1254  memset(ptr, 0x00, sizeof(*ptr));
1255  if (enabled()) {
1256  ptr->TRNCMD = msg->cmd.value;
1257  ptr->PBRKCMD = msg->pbrk.cmd;
1258  }
1259  pub_can_.publish(out);
1260 }
1261 
1263 {
1264  bool en = enabled();
1265  bool change = prev_enable_ != en;
1266  if (change || force) {
1267  std_msgs::Bool msg;
1268  msg.data = en;
1269  pub_sys_enable_.publish(msg);
1270  }
1271  prev_enable_ = en;
1272  return change;
1273 }
1274 
1276 {
1277  // Publish status periodically, in addition to latched and on change
1278  if (publishDbwEnabled(true)) {
1279  ROS_WARN("DBW system enable status changed unexpectedly");
1280  }
1281 
1282  // Clear override statuses if necessary
1283  if (clear()) {
1284  can_msgs::Frame out;
1285  out.is_extended = false;
1286 
1287  if (override_brake_) {
1288  out.id = ID_BRAKE_CMD;
1289  out.dlc = 4; // Sending the full eight bytes will fault the watchdog counter (if enabled)
1290  memset(out.data.elems, 0x00, 8);
1291  ((MsgBrakeCmd*)out.data.elems)->CLEAR = 1;
1292  pub_can_.publish(out);
1293  }
1294 
1295  if (override_throttle_) {
1296  out.id = ID_THROTTLE_CMD;
1297  out.dlc = 4; // Sending the full eight bytes will fault the watchdog counter (if enabled)
1298  memset(out.data.elems, 0x00, 8);
1299  ((MsgThrottleCmd*)out.data.elems)->CLEAR = 1;
1300  pub_can_.publish(out);
1301  }
1302 
1303  if (override_steering_) {
1304  out.id = ID_STEERING_CMD;
1305  out.dlc = 4; // Sending the full eight bytes will fault the watchdog counter (if enabled)
1306  memset(out.data.elems, 0x00, 8);
1307  ((MsgSteeringCmd*)out.data.elems)->CLEAR = 1;
1308  pub_can_.publish(out);
1309  }
1310 
1311  if (override_gear_) {
1312  out.id = ID_GEAR_CMD;
1313  out.dlc = sizeof(MsgGearCmd);
1314  memset(out.data.elems, 0x00, 8);
1315  ((MsgGearCmd*)out.data.elems)->CLEAR = 1;
1316  pub_can_.publish(out);
1317  }
1318  }
1319 }
1320 
1322 {
1323  if (!enable_) {
1324  if (fault()) {
1325  if (fault_steering_cal_) {
1326  ROS_WARN("DBW system not enabled. Steering calibration fault.");
1327  }
1328  if (fault_brakes_) {
1329  ROS_WARN("DBW system not enabled. Braking fault.");
1330  }
1331  if (fault_throttle_) {
1332  ROS_WARN("DBW system not enabled. Throttle fault.");
1333  }
1334  if (fault_steering_) {
1335  ROS_WARN("DBW system not enabled. Steering fault.");
1336  }
1337  if (fault_watchdog_) {
1338  ROS_WARN("DBW system not enabled. Watchdog fault.");
1339  }
1340  } else {
1341  enable_ = true;
1342  if (publishDbwEnabled()) {
1343  ROS_INFO("DBW system enabled.");
1344  } else {
1345  ROS_INFO("DBW system enable requested. Waiting for ready.");
1346  }
1347  }
1348  }
1349 }
1350 
1352 {
1353  if (enable_) {
1354  enable_ = false;
1356  ROS_WARN("DBW system disabled.");
1357  }
1358 }
1359 
1361 {
1362  if (enable_) {
1363  enable_ = false;
1365  ROS_WARN("DBW system disabled. Cancel button pressed.");
1366  }
1367 }
1368 
1369 void DbwNode::overrideBrake(bool override, bool timeout)
1370 {
1371  bool en = enabled();
1372  if (en && timeout) {
1373  override = false;
1374  }
1375  if (en && override) {
1376  enable_ = false;
1377  }
1378  override_brake_ = override;
1379  if (publishDbwEnabled()) {
1380  if (en) {
1381  ROS_WARN("DBW system disabled. Driver override on brake/throttle pedal.");
1382  } else {
1383  ROS_INFO("DBW system enabled.");
1384  }
1385  }
1386 }
1387 
1388 void DbwNode::overrideThrottle(bool override, bool timeout)
1389 {
1390  bool en = enabled();
1391  if (en && timeout) {
1392  override = false;
1393  }
1394  if (en && override) {
1395  enable_ = false;
1396  }
1397  override_throttle_ = override;
1398  if (publishDbwEnabled()) {
1399  if (en) {
1400  ROS_WARN("DBW system disabled. Driver override on brake/throttle pedal.");
1401  } else {
1402  ROS_INFO("DBW system enabled.");
1403  }
1404  }
1405 }
1406 
1407 void DbwNode::overrideSteering(bool override, bool timeout)
1408 {
1409  bool en = enabled();
1410  if (en && timeout) {
1411  override = false;
1412  }
1413  if (en && override) {
1414  enable_ = false;
1415  }
1416  override_steering_ = override;
1417  if (publishDbwEnabled()) {
1418  if (en) {
1419  ROS_WARN("DBW system disabled. Driver override on steering wheel.");
1420  } else {
1421  ROS_INFO("DBW system enabled.");
1422  }
1423  }
1424 }
1425 
1426 void DbwNode::overrideGear(bool override)
1427 {
1428  bool en = enabled();
1429  if (en && override) {
1430  enable_ = false;
1431  }
1432  override_gear_ = override;
1433  if (publishDbwEnabled()) {
1434  if (en) {
1435  ROS_WARN("DBW system disabled. Driver override on shifter.");
1436  } else {
1437  ROS_INFO("DBW system enabled.");
1438  }
1439  }
1440 }
1441 
1442 void DbwNode::timeoutBrake(bool timeout, bool enabled)
1443 {
1444  if (!timeout_brakes_ && enabled_brakes_ && timeout && !enabled) {
1445  ROS_WARN("Brake subsystem disabled after 100ms command timeout");
1446  }
1447  timeout_brakes_ = timeout;
1449 }
1450 
1451 void DbwNode::timeoutThrottle(bool timeout, bool enabled)
1452 {
1453  if (!timeout_throttle_ && enabled_throttle_ && timeout && !enabled) {
1454  ROS_WARN("Throttle subsystem disabled after 100ms command timeout");
1455  }
1456  timeout_throttle_ = timeout;
1458 }
1459 
1460 void DbwNode::timeoutSteering(bool timeout, bool enabled)
1461 {
1462  if (!timeout_steering_ && enabled_steering_ && timeout && !enabled) {
1463  ROS_WARN("Steering subsystem disabled after 100ms command timeout");
1464  }
1465  timeout_steering_ = timeout;
1467 }
1468 
1470 {
1471  bool en = enabled();
1472  if (fault && en) {
1473  enable_ = false;
1474  }
1475  fault_brakes_ = fault;
1476  if (publishDbwEnabled()) {
1477  if (en) {
1478  ROS_ERROR("DBW system disabled. Braking fault.");
1479  } else {
1480  ROS_INFO("DBW system enabled.");
1481  }
1482  }
1483 }
1484 
1486 {
1487  bool en = enabled();
1488  if (fault && en) {
1489  enable_ = false;
1490  }
1492  if (publishDbwEnabled()) {
1493  if (en) {
1494  ROS_ERROR("DBW system disabled. Throttle fault.");
1495  } else {
1496  ROS_INFO("DBW system enabled.");
1497  }
1498  }
1499 }
1500 
1502 {
1503  bool en = enabled();
1504  if (fault && en) {
1505  enable_ = false;
1506  }
1508  if (publishDbwEnabled()) {
1509  if (en) {
1510  ROS_ERROR("DBW system disabled. Steering fault.");
1511  } else {
1512  ROS_INFO("DBW system enabled.");
1513  }
1514  }
1515 }
1516 
1518 {
1519  bool en = enabled();
1520  if (fault && en) {
1521  enable_ = false;
1522  }
1524  if (publishDbwEnabled()) {
1525  if (en) {
1526  ROS_ERROR("DBW system disabled. Steering calibration fault.");
1527  } else {
1528  ROS_INFO("DBW system enabled.");
1529  }
1530  }
1531 }
1532 
1533 void DbwNode::faultWatchdog(bool fault, uint8_t src, bool braking)
1534 {
1535  bool en = enabled();
1536  if (fault && en) {
1537  enable_ = false;
1538  }
1540  if (publishDbwEnabled()) {
1541  if (en) {
1542  ROS_ERROR("DBW system disabled. Watchdog fault.");
1543  } else {
1544  ROS_INFO("DBW system enabled.");
1545  }
1546  }
1547  if (braking && !fault_watchdog_using_brakes_) {
1548  ROS_WARN("Watchdog event: Alerting driver and applying brakes.");
1549  } else if (!braking && fault_watchdog_using_brakes_) {
1550  ROS_INFO("Watchdog event: Driver has successfully taken control.");
1551  }
1552  if (fault && src && !fault_watchdog_warned_) {
1553  switch (src) {
1554  case dbw_mkz_msgs::WatchdogCounter::OTHER_BRAKE:
1555  ROS_WARN("Watchdog event: Fault determined by brake controller");
1556  break;
1557  case dbw_mkz_msgs::WatchdogCounter::OTHER_THROTTLE:
1558  ROS_WARN("Watchdog event: Fault determined by throttle controller");
1559  break;
1560  case dbw_mkz_msgs::WatchdogCounter::OTHER_STEERING:
1561  ROS_WARN("Watchdog event: Fault determined by steering controller");
1562  break;
1563  case dbw_mkz_msgs::WatchdogCounter::BRAKE_COUNTER:
1564  ROS_WARN("Watchdog event: Brake command counter failed to increment");
1565  break;
1566  case dbw_mkz_msgs::WatchdogCounter::BRAKE_DISABLED:
1567  ROS_WARN("Watchdog event: Brake transition to disabled while in gear or moving");
1568  break;
1569  case dbw_mkz_msgs::WatchdogCounter::BRAKE_COMMAND:
1570  ROS_WARN("Watchdog event: Brake command timeout after 100ms");
1571  break;
1572  case dbw_mkz_msgs::WatchdogCounter::BRAKE_REPORT:
1573  ROS_WARN("Watchdog event: Brake report timeout after 100ms");
1574  break;
1575  case dbw_mkz_msgs::WatchdogCounter::THROTTLE_COUNTER:
1576  ROS_WARN("Watchdog event: Throttle command counter failed to increment");
1577  break;
1578  case dbw_mkz_msgs::WatchdogCounter::THROTTLE_DISABLED:
1579  ROS_WARN("Watchdog event: Throttle transition to disabled while in gear or moving");
1580  break;
1581  case dbw_mkz_msgs::WatchdogCounter::THROTTLE_COMMAND:
1582  ROS_WARN("Watchdog event: Throttle command timeout after 100ms");
1583  break;
1584  case dbw_mkz_msgs::WatchdogCounter::THROTTLE_REPORT:
1585  ROS_WARN("Watchdog event: Throttle report timeout after 100ms");
1586  break;
1587  case dbw_mkz_msgs::WatchdogCounter::STEERING_COUNTER:
1588  ROS_WARN("Watchdog event: Steering command counter failed to increment");
1589  break;
1590  case dbw_mkz_msgs::WatchdogCounter::STEERING_DISABLED:
1591  ROS_WARN("Watchdog event: Steering transition to disabled while in gear or moving");
1592  break;
1593  case dbw_mkz_msgs::WatchdogCounter::STEERING_COMMAND:
1594  ROS_WARN("Watchdog event: Steering command timeout after 100ms");
1595  break;
1596  case dbw_mkz_msgs::WatchdogCounter::STEERING_REPORT:
1597  ROS_WARN("Watchdog event: Steering report timeout after 100ms");
1598  break;
1599  }
1600  fault_watchdog_warned_ = true;
1601  } else if (!fault) {
1602  fault_watchdog_warned_ = false;
1603  }
1604  fault_watchdog_using_brakes_ = braking;
1606  ROS_WARN_THROTTLE(2.0, "Watchdog event: Press left OK button on the steering wheel or cycle power to clear event.");
1607  }
1608 }
1609 
1610 void DbwNode::faultWatchdog(bool fault, uint8_t src) {
1611  faultWatchdog(fault, src, fault_watchdog_using_brakes_); // No change to 'using brakes' status
1612 }
1613 
1614 void DbwNode::publishJointStates(const ros::Time &stamp, const dbw_mkz_msgs::WheelSpeedReport *wheels, const dbw_mkz_msgs::SteeringReport *steering)
1615 {
1616  double dt = (stamp - joint_state_.header.stamp).toSec();
1617  if (wheels) {
1618  if (std::isfinite(wheels->front_left)) {
1619  joint_state_.velocity[JOINT_FL] = wheels->front_left;
1620  }
1621  if (std::isfinite(wheels->front_right)) {
1622  joint_state_.velocity[JOINT_FR] = wheels->front_right;
1623  }
1624  if (std::isfinite(wheels->rear_left)) {
1625  joint_state_.velocity[JOINT_RL] = wheels->rear_left;
1626  }
1627  if (std::isfinite(wheels->rear_right)) {
1628  joint_state_.velocity[JOINT_RR] = wheels->rear_right;
1629  }
1630  }
1631  if (steering) {
1632  if (std::isfinite(steering->steering_wheel_angle)) {
1633  const double L = acker_wheelbase_;
1634  const double W = acker_track_;
1635  const double r = L / tan(steering->steering_wheel_angle / steering_ratio_);
1636  joint_state_.position[JOINT_SL] = atan(L / (r - W/2));
1637  joint_state_.position[JOINT_SR] = atan(L / (r + W/2));
1638  }
1639  }
1640  if (dt < 0.5) {
1641  for (size_t i = JOINT_FL; i <= JOINT_RR; i++) {
1642  joint_state_.position[i] = fmod(joint_state_.position[i] + dt * joint_state_.velocity[i], 2*M_PI);
1643  }
1644  }
1645  joint_state_.header.stamp = stamp;
1647 }
1648 
1649 } // namespace dbw_mkz_can
1650 
void recvSteeringCmd(const dbw_mkz_msgs::SteeringCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1180
PlatformVersion findPlatform(Module m) const
Definition: PlatformMap.h:89
void insert(Platform p, Module m, ModuleVersion v)
Definition: PlatformMap.h:59
ros::Publisher pub_wheel_positions_
Definition: DbwNode.h:203
void overrideBrake(bool override, bool timeout)
Definition: DbwNode.cpp:1369
ros::Publisher pub_joint_states_
Definition: DbwNode.h:215
ros::Publisher pub_sys_enable_
Definition: DbwNode.h:218
void recvDisable(const std_msgs::Empty::ConstPtr &msg)
Definition: DbwNode.cpp:239
static float brakeTorqueFromPedal(float pedal)
Definition: pedal_lut.h:64
static float brakePedalFromPercent(float percent)
Definition: pedal_lut.h:110
#define ROS_WARN_ONCE_ID(id,...)
Definition: DbwNode.cpp:55
struct dbw_mkz_can::MsgLicense::@1::@9 vin0
PlatformMap FIRMWARE_CMDTYPE({ {PlatformVersion(P_FORD_CD4, M_BPEC, ModuleVersion(2, 0, 7))}, {PlatformVersion(P_FORD_CD4, M_TPEC, ModuleVersion(2, 0, 7))}, })
ros::Subscriber sub_throttle_
Definition: DbwNode.h:189
f
#define ROS_INFO_ONCE(...)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
double acker_wheelbase_
Definition: DbwNode.h:177
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
string cmd
bool fault_watchdog_using_brakes_
Definition: DbwNode.h:108
void faultSteering(bool fault)
Definition: DbwNode.cpp:1501
ros::Subscriber sub_enable_
Definition: DbwNode.h:185
void overrideThrottle(bool override, bool timeout)
Definition: DbwNode.cpp:1388
#define ROS_INFO_ONCE_ID(id,...)
Definition: DbwNode.cpp:54
ros::Subscriber sub_disable_
Definition: DbwNode.h:186
ros::Subscriber sub_gear_
Definition: DbwNode.h:191
void faultSteeringCal(bool fault)
Definition: DbwNode.cpp:1517
#define ROS_ERROR(...)
ros::Publisher pub_vin_
Definition: DbwNode.h:217
#define ROS_WARN(...)
ros::Subscriber sub_can_
Definition: DbwNode.h:187
ros::Publisher pub_steering_
Definition: DbwNode.h:199
ros::Subscriber sub_misc_
Definition: DbwNode.h:193
PlatformMap FIRMWARE_LATEST({ {PlatformVersion(P_FORD_C1, M_TPEC, ModuleVersion(1, 3, 3))}, {PlatformVersion(P_FORD_C1, M_STEER, ModuleVersion(1, 3, 3))}, {PlatformVersion(P_FORD_C1, M_SHIFT, ModuleVersion(1, 3, 3))}, {PlatformVersion(P_FORD_C1, M_ABS, ModuleVersion(1, 3, 3))}, {PlatformVersion(P_FORD_C1, M_BOO, ModuleVersion(1, 3, 3))}, {PlatformVersion(P_FORD_C1, M_EPS, ModuleVersion(1, 3, 3))}, {PlatformVersion(P_FORD_CD4, M_BPEC, ModuleVersion(2, 6, 3))}, {PlatformVersion(P_FORD_CD4, M_TPEC, ModuleVersion(2, 6, 3))}, {PlatformVersion(P_FORD_CD4, M_STEER, ModuleVersion(2, 6, 3))}, {PlatformVersion(P_FORD_CD4, M_SHIFT, ModuleVersion(2, 6, 3))}, {PlatformVersion(P_FORD_CD5, M_BOO, ModuleVersion(1, 2, 3))}, {PlatformVersion(P_FORD_CD5, M_TPEC, ModuleVersion(1, 2, 3))}, {PlatformVersion(P_FORD_CD5, M_STEER, ModuleVersion(1, 2, 3))}, {PlatformVersion(P_FORD_GE1, M_TPEC, ModuleVersion(1, 0, 3))}, {PlatformVersion(P_FORD_GE1, M_STEER, ModuleVersion(1, 0, 3))}, {PlatformVersion(P_FORD_GE1, M_SHIFT, ModuleVersion(1, 0, 3))}, {PlatformVersion(P_FORD_P5, M_TPEC, ModuleVersion(1, 5, 3))}, {PlatformVersion(P_FORD_P5, M_STEER, ModuleVersion(1, 5, 3))}, {PlatformVersion(P_FORD_P5, M_SHIFT, ModuleVersion(1, 5, 3))}, {PlatformVersion(P_FORD_P5, M_ABS, ModuleVersion(1, 5, 3))}, {PlatformVersion(P_FORD_P5, M_BOO, ModuleVersion(1, 5, 3))}, {PlatformVersion(P_FORD_P702, M_TPEC, ModuleVersion(0, 1, 3))}, {PlatformVersion(P_FORD_P702, M_STEER, ModuleVersion(0, 1, 3))}, {PlatformVersion(P_FORD_P702, M_SHIFT, ModuleVersion(0, 1, 3))}, {PlatformVersion(P_FORD_T6, M_TPEC, ModuleVersion(0, 3, 3))}, {PlatformVersion(P_FORD_T6, M_STEER, ModuleVersion(0, 3, 3))}, {PlatformVersion(P_FORD_T6, M_SHIFT, ModuleVersion(0, 3, 3))}, {PlatformVersion(P_FORD_U6, M_TPEC, ModuleVersion(1, 1, 3))}, {PlatformVersion(P_FORD_U6, M_STEER, ModuleVersion(1, 1, 3))}, {PlatformVersion(P_FORD_U6, M_SHIFT, ModuleVersion(1, 1, 3))}, {PlatformVersion(P_FORD_U6, M_ABS, ModuleVersion(1, 1, 3))}, {PlatformVersion(P_FORD_U6, M_BOO, ModuleVersion(1, 1, 3))}, })
static float sonarMetersFromBits(uint8_t bits)
Definition: sonar_lut.h:58
PlatformMap FIRMWARE_HIGH_RATE_LIMIT({ {PlatformVersion(P_FORD_CD4, M_STEER, ModuleVersion(2, 2, 0))}, {PlatformVersion(P_FORD_P5, M_STEER, ModuleVersion(1, 1, 0))}, })
void timeoutThrottle(bool timeout, bool enabled)
Definition: DbwNode.cpp:1451
struct dbw_mkz_can::MsgLicense::@1::@7 bdate0
ros::Publisher pub_gear_
Definition: DbwNode.h:200
#define ROS_DEBUG(...)
struct dbw_mkz_can::MsgLicense::@1::@6 mac
ros::Publisher pub_gps_vel_
Definition: DbwNode.h:213
static const char * moduleToString(Module x)
bool publishDbwEnabled(bool force=false)
Definition: DbwNode.cpp:1262
TransportHints & tcpNoDelay(bool nodelay=true)
void timeoutBrake(bool timeout, bool enabled)
Definition: DbwNode.cpp:1442
ros::Publisher pub_driver_assist_
Definition: DbwNode.h:210
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void faultBrakes(bool fault)
Definition: DbwNode.cpp:1469
void publish(const boost::shared_ptr< M > &message) const
std::map< uint8_t, std::string > bdate_
Definition: DbwNode.h:159
static const char * platformToString(Platform x)
bool fault_watchdog_warned_
Definition: DbwNode.h:109
#define ROS_INFO_THROTTLE(period,...)
void recvCanGps(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
Definition: DbwNode.cpp:960
INLINE Rall1d< T, V, S > atan(const Rall1d< T, V, S > &x)
ros::Publisher pub_surround_
Definition: DbwNode.h:206
void recvEnable(const std_msgs::Empty::ConstPtr &msg)
Definition: DbwNode.cpp:234
ros::Publisher pub_imu_
Definition: DbwNode.h:211
#define ROS_WARN_THROTTLE(period,...)
void recvCanImu(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
Definition: DbwNode.cpp:914
double steering_ratio_
Definition: DbwNode.h:179
ros::Publisher pub_throttle_
Definition: DbwNode.h:198
#define ROS_INFO(...)
bool getParam(const std::string &key, std::string &s) const
PlatformMap FIRMWARE_TIMEOUT({ {PlatformVersion(P_FORD_CD4, M_BPEC, ModuleVersion(2, 0, 0))}, {PlatformVersion(P_FORD_CD4, M_TPEC, ModuleVersion(2, 0, 0))}, {PlatformVersion(P_FORD_CD4, M_STEER, ModuleVersion(2, 0, 0))}, })
uint16_t major() const
Definition: ModuleVersion.h:62
ros::Publisher pub_brake_
Definition: DbwNode.h:197
void publishJointStates(const ros::Time &stamp, const dbw_mkz_msgs::WheelSpeedReport *wheels, const dbw_mkz_msgs::SteeringReport *steering)
Definition: DbwNode.cpp:1614
uint16_t minor() const
Definition: ModuleVersion.h:63
static float throttlePedalFromPercent(float percent)
Definition: pedal_lut.h:113
ros::Subscriber sub_turn_signal_
Definition: DbwNode.h:192
ros::Publisher pub_fuel_level_
Definition: DbwNode.h:205
void faultWatchdog(bool fault, uint8_t src, bool braking)
Definition: DbwNode.cpp:1533
void faultThrottle(bool fault)
Definition: DbwNode.cpp:1485
struct dbw_mkz_can::MsgLicense::@1::@10 vin1
void recvGearCmd(const dbw_mkz_msgs::GearCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1230
void overrideGear(bool override)
Definition: DbwNode.cpp:1426
struct dbw_mkz_can::MsgLicense::@1::@11 vin2
void recvBrakeCmd(const dbw_mkz_msgs::BrakeCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1028
bool enable_joint_states_
Definition: DbwNode.h:182
static float brakePedalFromTorque(float torque)
Definition: pedal_lut.h:87
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher pub_misc_1_
Definition: DbwNode.h:201
ros::Publisher pub_wheel_speeds_
Definition: DbwNode.h:202
PlatformMap firmware_
Definition: DbwNode.h:162
ros::Publisher pub_sonar_cloud_
Definition: DbwNode.h:207
ros::Publisher pub_throttle_info_
Definition: DbwNode.h:209
void recvMiscCmd(const dbw_mkz_msgs::MiscCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1247
struct dbw_mkz_can::MsgLicense::@1::@3 license
ros::Publisher pub_gps_time_
Definition: DbwNode.h:214
ros::Publisher pub_twist_
Definition: DbwNode.h:216
string NAME
void recvThrottleCmd(const dbw_mkz_msgs::ThrottleCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1135
void recvCAN(const can_msgs::Frame::ConstPtr &msg)
Definition: DbwNode.cpp:244
ros::Timer timer_
Definition: DbwNode.h:96
std::string vin_
Definition: DbwNode.h:157
struct dbw_mkz_can::MsgLicense::@1::@8 bdate1
void setInterMessageLowerBound(ros::Duration lower_bound)
sensor_msgs::JointState joint_state_
Definition: DbwNode.h:148
uint16_t build() const
Definition: ModuleVersion.h:64
#define ROS_WARN_COND(cond,...)
ros::Publisher pub_brake_info_
Definition: DbwNode.h:208
std::string ldate_
Definition: DbwNode.h:158
static void sonarBuildPointCloud2(sensor_msgs::PointCloud2 &cloud, const dbw_mkz_msgs::SurroundReport &surround)
Definition: sonar_lut.h:70
ros::Publisher pub_tire_pressure_
Definition: DbwNode.h:204
const std::string header
std::string frame_id_
Definition: DbwNode.h:165
void timerCallback(const ros::TimerEvent &event)
Definition: DbwNode.cpp:1275
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
void overrideSteering(bool override, bool timeout)
Definition: DbwNode.cpp:1407
#define ROS_ASSERT(cond)
bool fault_steering_cal_
Definition: DbwNode.h:106
dataspeed_can_msg_filters::ApproximateTime sync_gps_
Definition: DbwNode.h:222
ros::Subscriber sub_steering_
Definition: DbwNode.h:190
dataspeed_can_msg_filters::ApproximateTime sync_imu_
Definition: DbwNode.h:221
ros::Subscriber sub_brake_
Definition: DbwNode.h:188
ros::Publisher pub_gps_fix_
Definition: DbwNode.h:212
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
ModuleVersion findModule(Module m) const
Definition: PlatformMap.h:65
void timeoutSteering(bool timeout, bool enabled)
Definition: DbwNode.cpp:1460
ros::Publisher pub_can_
Definition: DbwNode.h:196
DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
Definition: DbwNode.cpp:117


dbw_mkz_can
Author(s): Kevin Hallenbeck
autogenerated on Fri Jun 16 2023 02:54:50