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


dbw_mkz_can
Author(s): Kevin Hallenbeck
autogenerated on Fri May 14 2021 02:47:08