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,4))},
65  {PlatformVersion(P_FORD_C1, M_STEER, ModuleVersion(1,3,4))},
66  {PlatformVersion(P_FORD_C1, M_SHIFT, ModuleVersion(1,3,4))},
67  {PlatformVersion(P_FORD_C1, M_ABS, ModuleVersion(1,3,4))},
68  {PlatformVersion(P_FORD_C1, M_BOO, ModuleVersion(1,3,4))},
69  {PlatformVersion(P_FORD_C1, M_EPS, ModuleVersion(1,3,4))},
70  {PlatformVersion(P_FORD_CD4, M_BPEC, ModuleVersion(2,6,4))},
71  {PlatformVersion(P_FORD_CD4, M_TPEC, ModuleVersion(2,6,4))},
72  {PlatformVersion(P_FORD_CD4, M_STEER, ModuleVersion(2,6,4))},
73  {PlatformVersion(P_FORD_CD4, M_SHIFT, ModuleVersion(2,6,4))},
74  {PlatformVersion(P_FORD_CD5, M_BOO, ModuleVersion(1,2,4))},
75  {PlatformVersion(P_FORD_CD5, M_TPEC, ModuleVersion(1,2,4))},
76  {PlatformVersion(P_FORD_CD5, M_STEER, ModuleVersion(1,2,4))},
77  {PlatformVersion(P_FORD_GE1, M_TPEC, ModuleVersion(1,0,4))},
78  {PlatformVersion(P_FORD_GE1, M_STEER, ModuleVersion(1,0,4))},
79  {PlatformVersion(P_FORD_GE1, M_SHIFT, ModuleVersion(1,0,4))},
80  {PlatformVersion(P_FORD_P5, M_TPEC, ModuleVersion(1,5,4))},
81  {PlatformVersion(P_FORD_P5, M_STEER, ModuleVersion(1,5,4))},
82  {PlatformVersion(P_FORD_P5, M_SHIFT, ModuleVersion(1,5,4))},
83  {PlatformVersion(P_FORD_P5, M_ABS, ModuleVersion(1,5,4))},
84  {PlatformVersion(P_FORD_P5, M_BOO, ModuleVersion(1,5,4))},
85  {PlatformVersion(P_FORD_P702, M_TPEC, ModuleVersion(0,1,4))},
86  {PlatformVersion(P_FORD_P702, M_STEER, ModuleVersion(0,1,4))},
87  {PlatformVersion(P_FORD_P702, M_SHIFT, ModuleVersion(0,1,4))},
88  {PlatformVersion(P_FORD_T6, M_TPEC, ModuleVersion(0,3,4))},
89  {PlatformVersion(P_FORD_T6, M_STEER, ModuleVersion(0,3,4))},
90  {PlatformVersion(P_FORD_T6, M_SHIFT, ModuleVersion(0,3,4))},
91  {PlatformVersion(P_FORD_U6, M_TPEC, ModuleVersion(1,1,4))},
92  {PlatformVersion(P_FORD_U6, M_STEER, ModuleVersion(1,1,4))},
93  {PlatformVersion(P_FORD_U6, M_SHIFT, ModuleVersion(1,1,4))},
94  {PlatformVersion(P_FORD_U6, M_ABS, ModuleVersion(1,1,4))},
95  {PlatformVersion(P_FORD_U6, M_BOO, ModuleVersion(1,1,4))},
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  out.one_pedal.value = ptr->one_pedal_drive;
705  if (ptr->engine_rpm == 0xFFFF) {
706  out.engine_rpm = NAN;
707  } else {
708  out.engine_rpm = (float)ptr->engine_rpm * 0.25f;
709  }
710  out.gear_num.num = ptr->gear_num;
711  out.ignition.value = ptr->ign_stat;
712  if ((uint16_t)ptr->batt_curr == 0xE000) {
713  out.batt_curr = NAN;
714  } else {
715  out.batt_curr = (float)ptr->batt_curr * 0.0625f;
716  }
718  if (ptr->aped_qf != dbw_mkz_msgs::QualityFactor::OK) {
719  ROS_WARN_THROTTLE(5.0, "Throttle pedal limp-home: %u", ptr->aped_qf);
720  }
721  }
722  break;
723 
725  if (msg->dlc >= sizeof(MsgReportDriverAssist)) {
726  const MsgReportDriverAssist *ptr = (const MsgReportDriverAssist*)msg->data.elems;
727  dbw_mkz_msgs::DriverAssistReport out;
728  out.header.stamp = msg->header.stamp;
729  out.decel = (float)ptr->decel * 0.0625f;
730  out.decel_src = ptr->decel_src;
731  out.fcw_enabled = ptr->fcw_enabled;
732  out.fcw_active = ptr->fcw_active;
733  out.aeb_enabled = ptr->aeb_enabled;
734  out.aeb_precharge = ptr->aeb_precharge;
735  out.aeb_braking = ptr->aeb_braking;
736  out.acc_enabled = ptr->acc_enabled;
737  out.acc_braking = ptr->acc_braking;
739  if (out.fcw_active) {
740  ROS_WARN_THROTTLE(5.0, "Forward collision warning activated!");
741  }
742  if (out.aeb_braking) {
743  ROS_WARN_THROTTLE(5.0, "Automatic emergency braking activated!");
744  }
745  }
746  break;
747 
748  case ID_LICENSE:
749  if (msg->dlc >= sizeof(MsgLicense)) {
750  const MsgLicense *ptr = (const MsgLicense*)msg->data.elems;
751  const Module module = ptr->module ? (Module)ptr->module : M_STEER; // Legacy steering firmware reports zero for module
752  const char * str_m = moduleToString(module);
753  ROS_DEBUG("LICENSE(%x,%02X,%s)", ptr->module, ptr->mux, str_m);
754  if (ptr->ready) {
755  ROS_INFO_ONCE_ID(module, "Licensing: %s ready", str_m);
756  if (ptr->trial) {
757  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);
758  }
759  if (ptr->expired) {
760  ROS_WARN_ONCE_ID(module, "Licensing: %s one or more feature licenses expired due to the firmware build date", str_m);
761  }
762  } else if (module == M_STEER) {
763  ROS_INFO_THROTTLE(10.0, "Licensing: Waiting for VIN...");
764  } else {
765  ROS_INFO_THROTTLE(10.0, "Licensing: Waiting for required info...");
766  }
767  if (ptr->mux == LIC_MUX_LDATE0) {
768  if (ldate_.size() == 0) {
769  ldate_.push_back(ptr->ldate0.ldate0);
770  ldate_.push_back(ptr->ldate0.ldate1);
771  ldate_.push_back(ptr->ldate0.ldate2);
772  ldate_.push_back(ptr->ldate0.ldate3);
773  ldate_.push_back(ptr->ldate0.ldate4);
774  ldate_.push_back(ptr->ldate0.ldate5);
775  }
776  } else if (ptr->mux == LIC_MUX_LDATE1) {
777  if (ldate_.size() == 6) {
778  ldate_.push_back(ptr->ldate1.ldate6);
779  ldate_.push_back(ptr->ldate1.ldate7);
780  ldate_.push_back(ptr->ldate1.ldate8);
781  ldate_.push_back(ptr->ldate1.ldate9);
782  ROS_INFO("Licensing: %s license string date: %s", str_m, ldate_.c_str());
783  }
784  } else if (ptr->mux == LIC_MUX_MAC) {
785  ROS_INFO_ONCE("Licensing: %s MAC: %02X:%02X:%02X:%02X:%02X:%02X", str_m,
786  ptr->mac.addr0, ptr->mac.addr1,
787  ptr->mac.addr2, ptr->mac.addr3,
788  ptr->mac.addr4, ptr->mac.addr5);
789  } else if (ptr->mux == LIC_MUX_BDATE0) {
790  std::string &bdate = bdate_[module];
791  if (bdate.size() == 0) {
792  bdate.push_back(ptr->bdate0.date0);
793  bdate.push_back(ptr->bdate0.date1);
794  bdate.push_back(ptr->bdate0.date2);
795  bdate.push_back(ptr->bdate0.date3);
796  bdate.push_back(ptr->bdate0.date4);
797  bdate.push_back(ptr->bdate0.date5);
798  }
799  } else if (ptr->mux == LIC_MUX_BDATE1) {
800  std::string &bdate = bdate_[module];
801  if (bdate.size() == 6) {
802  bdate.push_back(ptr->bdate1.date6);
803  bdate.push_back(ptr->bdate1.date7);
804  bdate.push_back(ptr->bdate1.date8);
805  bdate.push_back(ptr->bdate1.date9);
806  ROS_INFO("Licensing: %s firmware build date: %s", str_m, bdate.c_str());
807  }
808  } else if (ptr->mux == LIC_MUX_VIN0) {
809  if (vin_.size() == 0) {
810  vin_.push_back(ptr->vin0.vin00);
811  vin_.push_back(ptr->vin0.vin01);
812  vin_.push_back(ptr->vin0.vin02);
813  vin_.push_back(ptr->vin0.vin03);
814  vin_.push_back(ptr->vin0.vin04);
815  vin_.push_back(ptr->vin0.vin05);
816  }
817  } else if (ptr->mux == LIC_MUX_VIN1) {
818  if (vin_.size() == 6) {
819  vin_.push_back(ptr->vin1.vin06);
820  vin_.push_back(ptr->vin1.vin07);
821  vin_.push_back(ptr->vin1.vin08);
822  vin_.push_back(ptr->vin1.vin09);
823  vin_.push_back(ptr->vin1.vin10);
824  vin_.push_back(ptr->vin1.vin11);
825  }
826  } else if (ptr->mux == LIC_MUX_VIN2) {
827  if (vin_.size() == 12) {
828  vin_.push_back(ptr->vin2.vin12);
829  vin_.push_back(ptr->vin2.vin13);
830  vin_.push_back(ptr->vin2.vin14);
831  vin_.push_back(ptr->vin2.vin15);
832  vin_.push_back(ptr->vin2.vin16);
833  std_msgs::String msg; msg.data = vin_;
834  pub_vin_.publish(msg);
835  ROS_INFO("Licensing: VIN: %s", vin_.c_str());
836  }
837  } else if ((LIC_MUX_F0 <= ptr->mux) && (ptr->mux <= LIC_MUX_F7)) {
838  constexpr std::array<const char*, 8> NAME = {"BASE","CONTROL","SENSORS","REMOTE","","","",""};
839  constexpr std::array<bool, 8> WARN = {true, true, true, false, true, true, true, true};
840  const size_t i = ptr->mux - LIC_MUX_F0;
841  const int id = module * NAME.size() + i;
842  const std::string name = strcmp(NAME[i], "") ? NAME[i] : std::string(1, '0' + i);
843  if (ptr->license.enabled) {
844  ROS_INFO_ONCE_ID(id, "Licensing: %s feature '%s' enabled%s", str_m, name.c_str(), ptr->license.trial ? " as a counted trial" : "");
845  } else if (ptr->ready && !WARN[i]) {
846  ROS_INFO_ONCE_ID(id, "Licensing: %s feature '%s' not licensed.", str_m, name.c_str());
847  } else if (ptr->ready) {
848  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());
849  }
850  if (ptr->ready && (module == M_STEER) && (ptr->license.trial || (!ptr->license.enabled && WARN[i]))) {
851  ROS_INFO_ONCE("Licensing: Feature '%s' trials used: %u, remaining: %u", name.c_str(),
852  ptr->license.trials_used, ptr->license.trials_left);
853  }
854  }
855  }
856  break;
857 
858  case ID_VERSION:
859  if (msg->dlc >= sizeof(MsgVersion)) {
860  const MsgVersion *ptr = (const MsgVersion*)msg->data.elems;
861  const PlatformVersion version((Platform)ptr->platform, (Module)ptr->module, ptr->major, ptr->minor, ptr->build);
862  const ModuleVersion latest = FIRMWARE_LATEST.findModule(version);
863  const char * str_p = platformToString(version.p);
864  const char * str_m = moduleToString(version.m);
865  if (firmware_.findModule(version) != version.v) {
866  firmware_.insert(version);
867  if (latest.valid()) {
868  ROS_INFO("Detected %s %s firmware version %u.%u.%u", str_p, str_m, ptr->major, ptr->minor, ptr->build);
869  } else {
870  ROS_WARN("Detected %s %s firmware version %u.%u.%u, which is unsupported. Platform: 0x%02X, Module: %u", str_p, str_m,
871  ptr->major, ptr->minor, ptr->build, ptr->platform, ptr->module);
872  }
873  if (version < latest) {
874  ROS_WARN("Firmware %s %s has old version %u.%u.%u, updating to %u.%u.%u is suggested.", str_p, str_m,
875  version.v.major(), version.v.minor(), version.v.build(),
876  latest.major(), latest.minor(), latest.build());
877  }
878  }
879  }
880  break;
881 
882  case ID_BRAKE_CMD:
883  ROS_WARN_COND(warn_cmds_ && !((const MsgBrakeCmd*)msg->data.elems)->RES1 && !((const MsgBrakeCmd*)msg->data.elems)->RES2,
884  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Brake. Id: 0x%03X", ID_BRAKE_CMD);
885  break;
886  case ID_THROTTLE_CMD:
887  ROS_WARN_COND(warn_cmds_ && !((const MsgThrottleCmd*)msg->data.elems)->RES1 && !((const MsgThrottleCmd*)msg->data.elems)->RES2,
888  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Throttle. Id: 0x%03X", ID_THROTTLE_CMD);
889  break;
890  case ID_STEERING_CMD:
891  ROS_WARN_COND(warn_cmds_ && !((const MsgSteeringCmd*)msg->data.elems)->RES1 && !((const MsgSteeringCmd*)msg->data.elems)->RES2,
892  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Steering. Id: 0x%03X", ID_STEERING_CMD);
893  break;
894  case ID_GEAR_CMD:
895  ROS_WARN_COND(warn_cmds_ && !((const MsgGearCmd*)msg->data.elems)->RES1 && !((const MsgGearCmd*)msg->data.elems)->RES2,
896  "DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Shifting. Id: 0x%03X", ID_GEAR_CMD);
897  break;
898  case ID_MISC_CMD:
899  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);
900  break;
901 
902  case 0x100 ... 0x103: // DBW2 steer/brake/throttle/gear report
903  case 0x6C0 ... 0x6C5: // DBW2 ECU info for each module
904  ROS_WARN_ONCE_ID(msg->id, "Received unsupported CAN ID %03X from next-generation drive-by-wire system (DBW2)"
905  "\nUse the ROS2 ds_dbw_can package instead", msg->id);
906  break;
907  }
908  }
909 #if 0
910  ROS_INFO("ena: %s, clr: %s, brake: %s, throttle: %s, steering: %s, gear: %s",
911  enabled() ? "true " : "false",
912  clear() ? "true " : "false",
913  override_brake_ ? "true " : "false",
914  override_throttle_ ? "true " : "false",
915  override_steering_ ? "true " : "false",
916  override_gear_ ? "true " : "false"
917  );
918 #endif
919 }
920 
921 void DbwNode::recvCanImu(const std::vector<can_msgs::Frame::ConstPtr> &msgs) {
922  ROS_ASSERT(msgs.size() == 2);
923  ROS_ASSERT(msgs[0]->id == ID_REPORT_ACCEL);
924  ROS_ASSERT(msgs[1]->id == ID_REPORT_GYRO);
925  if ((msgs[0]->dlc >= sizeof(MsgReportAccel)) && (msgs[1]->dlc >= sizeof(MsgReportGyro))) {
926  const MsgReportAccel *ptr_accel = (const MsgReportAccel*)msgs[0]->data.elems;
927  const MsgReportGyro *ptr_gyro = (const MsgReportGyro*)msgs[1]->data.elems;
928  sensor_msgs::Imu out;
929  out.header.stamp = msgs[0]->header.stamp;
930  out.header.frame_id = frame_id_;
931  out.orientation_covariance[0] = -1; // Orientation not present
932  if ((uint16_t)ptr_accel->accel_long == 0x8000) {
933  out.linear_acceleration.x = NAN;
934  } else {
935  out.linear_acceleration.x = (double)ptr_accel->accel_long * 0.01;
936  }
937  if ((uint16_t)ptr_accel->accel_lat == 0x8000) {
938  out.linear_acceleration.y = NAN;
939  } else {
940  out.linear_acceleration.y = (double)ptr_accel->accel_lat * -0.01;
941  }
942  if ((uint16_t)ptr_accel->accel_vert == 0x8000) {
943  out.linear_acceleration.z = NAN;
944  } else {
945  out.linear_acceleration.z = (double)ptr_accel->accel_vert * -0.01;
946  }
947  if ((uint16_t)ptr_gyro->gyro_roll == 0x8000) {
948  out.angular_velocity.x = NAN;
949  } else {
950  out.angular_velocity.x = (double)ptr_gyro->gyro_roll * 0.0002;
951  }
952  if ((uint16_t)ptr_gyro->gyro_yaw == 0x8000) {
953  out.angular_velocity.z = NAN;
954  } else {
955  out.angular_velocity.z = (double)ptr_gyro->gyro_yaw * 0.0002;
956  }
957  pub_imu_.publish(out);
958  }
959 #if 0
960  ROS_INFO("Time: %u.%u, %u.%u, delta: %fms",
961  msgs[0]->header.stamp.sec, msgs[0]->header.stamp.nsec,
962  msgs[1]->header.stamp.sec, msgs[1]->header.stamp.nsec,
963  labs((msgs[1]->header.stamp - msgs[0]->header.stamp).toNSec()) / 1000000.0);
964 #endif
965 }
966 
967 void DbwNode::recvCanGps(const std::vector<can_msgs::Frame::ConstPtr> &msgs) {
968  ROS_ASSERT(msgs.size() == 3);
969  ROS_ASSERT(msgs[0]->id == ID_REPORT_GPS1);
970  ROS_ASSERT(msgs[1]->id == ID_REPORT_GPS2);
971  ROS_ASSERT(msgs[2]->id == ID_REPORT_GPS3);
972  if ((msgs[0]->dlc >= sizeof(MsgReportGps1)) && (msgs[1]->dlc >= sizeof(MsgReportGps2)) && (msgs[2]->dlc >= sizeof(MsgReportGps3))) {
973  const MsgReportGps1 *ptr1 = (const MsgReportGps1*)msgs[0]->data.elems;
974  const MsgReportGps2 *ptr2 = (const MsgReportGps2*)msgs[1]->data.elems;
975  const MsgReportGps3 *ptr3 = (const MsgReportGps3*)msgs[2]->data.elems;
976 
977  sensor_msgs::NavSatFix msg_fix;
978  msg_fix.header.stamp = msgs[0]->header.stamp;
979  msg_fix.latitude = (double)ptr1->latitude / 3e6;
980  msg_fix.longitude = (double)ptr1->longitude / 3e6;
981  msg_fix.altitude = (double)ptr3->altitude * 0.25;
982  msg_fix.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
983  msg_fix.status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
984  switch (ptr3->quality) {
985  case 0:
986  default:
987  msg_fix.status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
988  break;
989  case 1:
990  case 2:
991  msg_fix.status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
992  break;
993  }
994  pub_gps_fix_.publish(msg_fix);
995 
996  geometry_msgs::TwistStamped msg_vel;
997  msg_vel.header.stamp = msgs[0]->header.stamp;
998  double heading = (double)ptr3->heading * (0.01 * M_PI / 180);
999  double speed = (double)ptr3->speed * 0.44704;
1000  msg_vel.twist.linear.x = cos(heading) * speed;
1001  msg_vel.twist.linear.y = sin(heading) * speed;
1002  pub_gps_vel_.publish(msg_vel);
1003 
1004  sensor_msgs::TimeReference msg_time;
1005  struct tm unix_time;
1006  unix_time.tm_year = ptr2->utc_year + 100; // [1900] <-- [2000]
1007  unix_time.tm_mon = ptr2->utc_month - 1; // [0-11] <-- [1-12]
1008  unix_time.tm_mday = ptr2->utc_day; // [1-31] <-- [1-31]
1009  unix_time.tm_hour = ptr2->utc_hours; // [0-23] <-- [0-23]
1010  unix_time.tm_min = ptr2->utc_minutes; // [0-59] <-- [0-59]
1011  unix_time.tm_sec = ptr2->utc_seconds; // [0-59] <-- [0-59]
1012  msg_time.header.stamp = msgs[0]->header.stamp;
1013  msg_time.time_ref.sec = timegm(&unix_time);
1014  msg_time.time_ref.nsec = 0;
1015  pub_gps_time_.publish(msg_time);
1016 
1017 #if 0
1018  ROS_INFO("UTC Time: %04d-%02d-%02d %02d:%02d:%02d",
1019  2000 + ptr2->utc_year, ptr2->utc_month, ptr2->utc_day,
1020  ptr2->utc_hours, ptr2->utc_minutes, ptr2->utc_seconds);
1021 #endif
1022  }
1023 #if 0
1024  ROS_INFO("Time: %u.%u, %u.%u, %u.%u, delta: %fms",
1025  msgs[0]->header.stamp.sec, msgs[0]->header.stamp.nsec,
1026  msgs[1]->header.stamp.sec, msgs[1]->header.stamp.nsec,
1027  msgs[2]->header.stamp.sec, msgs[2]->header.stamp.nsec,
1028  std::max(std::max(
1029  labs((msgs[1]->header.stamp - msgs[0]->header.stamp).toNSec()),
1030  labs((msgs[2]->header.stamp - msgs[1]->header.stamp).toNSec())),
1031  labs((msgs[0]->header.stamp - msgs[2]->header.stamp).toNSec())) / 1000000.0);
1032 #endif
1033 }
1034 
1035 void DbwNode::recvBrakeCmd(const dbw_mkz_msgs::BrakeCmd::ConstPtr& msg)
1036 {
1037  can_msgs::Frame out;
1038  out.id = ID_BRAKE_CMD;
1039  out.is_extended = false;
1040  out.dlc = sizeof(MsgBrakeCmd);
1041  MsgBrakeCmd *ptr = (MsgBrakeCmd*)out.data.elems;
1042  memset(ptr, 0x00, sizeof(*ptr));
1043  bool fwd_abs = firmware_.findModule(M_ABS).valid(); // Does the ABS braking module exist?
1044  bool fwd_bpe = firmware_.findPlatform(M_BPEC) >= FIRMWARE_CMDTYPE; // Minimum required BPEC firmware version
1045  bool fwd = !pedal_luts_; // Forward command type, or apply pedal LUTs locally
1046  fwd |= fwd_abs; // The local pedal LUTs are for the BPEC module, the ABS module requires forwarding
1047  fwd &= fwd_bpe; // Only modern BPEC firmware supports forwarding the command type
1048  switch (msg->pedal_cmd_type) {
1049  case dbw_mkz_msgs::BrakeCmd::CMD_NONE:
1050  break;
1051  case dbw_mkz_msgs::BrakeCmd::CMD_PEDAL:
1052  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1053  ptr->PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
1055  ROS_WARN_THROTTLE(1.0, "Module ABS does not support brake command type PEDAL");
1056  }
1057  break;
1058  case dbw_mkz_msgs::BrakeCmd::CMD_PERCENT:
1059  if (fwd) {
1060  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PERCENT;
1061  ptr->PCMD = std::clamp<float>(msg->pedal_cmd * UINT16_MAX, 0, UINT16_MAX);
1062  } else {
1063  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1064  ptr->PCMD = std::clamp<float>(brakePedalFromPercent(msg->pedal_cmd) * UINT16_MAX, 0, UINT16_MAX);
1065  }
1066  break;
1067  case dbw_mkz_msgs::BrakeCmd::CMD_TORQUE:
1068  if (fwd) {
1069  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE;
1070  ptr->PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1071  } else {
1072  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1073  ptr->PCMD = std::clamp<float>(brakePedalFromTorque(msg->pedal_cmd) * UINT16_MAX, 0, UINT16_MAX);
1074  }
1076  ROS_WARN_THROTTLE(1.0, "Module ABS does not support brake command type TORQUE");
1077  }
1078  break;
1079  case dbw_mkz_msgs::BrakeCmd::CMD_TORQUE_RQ:
1080  if (fwd_abs || fwd_bpe) {
1081  // CMD_TORQUE_RQ must be forwarded, there is no local implementation
1082  fwd = true;
1083  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE_RQ;
1084  ptr->PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1085  } else if (fwd) {
1086  // Fallback to forwarded CMD_TORQUE
1087  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_TORQUE;
1088  ptr->PCMD = std::clamp<float>(msg->pedal_cmd, 0, UINT16_MAX);
1089  } else {
1090  // Fallback to local CMD_TORQUE
1091  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_PEDAL;
1092  ptr->PCMD = std::clamp<float>(brakePedalFromTorque(msg->pedal_cmd) * UINT16_MAX, 0, UINT16_MAX);
1093  }
1095  ROS_WARN_THROTTLE(1.0, "Module ABS does not support brake command type TORQUE_RQ");
1096  }
1097  break;
1098  case dbw_mkz_msgs::BrakeCmd::CMD_DECEL:
1099  // CMD_DECEL must be forwarded, there is no local implementation
1100  ptr->CMD_TYPE = dbw_mkz_msgs::BrakeCmd::CMD_DECEL;
1101  ptr->PCMD = std::clamp<float>(msg->pedal_cmd * 1e3f, 0, 10e3);
1103  ROS_WARN_THROTTLE(1.0, "Module BPEC does not support brake command type DECEL");
1104  }
1105  break;
1106  default:
1107  ROS_WARN("Unknown brake command type: %u", msg->pedal_cmd_type);
1108  break;
1109  }
1110 #if 1 // Manually implement auto BOO control (brake lights) for legacy firmware
1111  ptr->ABOO = 1;
1112  const PlatformVersion firmware_bpec = firmware_.findPlatform(M_BPEC);
1113  if (firmware_bpec.v.valid() && (firmware_bpec < FIRMWARE_CMDTYPE)) {
1114  const uint16_t BOO_THRESH_LO = 0.20 * UINT16_MAX;
1115  const uint16_t BOO_THRESH_HI = 0.22 * UINT16_MAX;
1116  static bool boo_status_ = false;
1117  if (boo_status_) {
1118  ptr->BCMD = 1;
1119  }
1120  if (!boo_status_ && (ptr->PCMD > BOO_THRESH_HI)) {
1121  ptr->BCMD = 1;
1122  boo_status_ = true;
1123  } else if (boo_status_ && (ptr->PCMD < BOO_THRESH_LO)) {
1124  ptr->BCMD = 0;
1125  boo_status_ = false;
1126  }
1127  }
1128 #endif
1129  if (enabled() && msg->enable) {
1130  ptr->EN = 1;
1131  }
1132  if (clear() || msg->clear) {
1133  ptr->CLEAR = 1;
1134  }
1135  if (msg->ignore) {
1136  ptr->IGNORE = 1;
1137  }
1138  ptr->COUNT = msg->count;
1139  pub_can_.publish(out);
1140 }
1141 
1142 void DbwNode::recvThrottleCmd(const dbw_mkz_msgs::ThrottleCmd::ConstPtr& msg)
1143 {
1144  can_msgs::Frame out;
1145  out.id = ID_THROTTLE_CMD;
1146  out.is_extended = false;
1147  out.dlc = sizeof(MsgThrottleCmd);
1148  MsgThrottleCmd *ptr = (MsgThrottleCmd*)out.data.elems;
1149  memset(ptr, 0x00, sizeof(*ptr));
1150  bool fwd = !pedal_luts_; // Forward command type, or apply pedal LUTs locally
1151  fwd &= firmware_.findPlatform(M_TPEC) >= FIRMWARE_CMDTYPE; // Minimum required firmware version
1152  float cmd = 0.0;
1153  switch (msg->pedal_cmd_type) {
1154  case dbw_mkz_msgs::ThrottleCmd::CMD_NONE:
1155  break;
1156  case dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL:
1157  ptr->CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL;
1158  cmd = msg->pedal_cmd;
1159  break;
1160  case dbw_mkz_msgs::ThrottleCmd::CMD_PERCENT:
1161  if (fwd) {
1162  ptr->CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PERCENT;
1163  cmd = msg->pedal_cmd;
1164  } else {
1165  ptr->CMD_TYPE = dbw_mkz_msgs::ThrottleCmd::CMD_PEDAL;
1166  cmd = throttlePedalFromPercent(msg->pedal_cmd);
1167  }
1168  break;
1169  default:
1170  ROS_WARN("Unknown throttle command type: %u", msg->pedal_cmd_type);
1171  break;
1172  }
1173  ptr->PCMD = std::clamp<float>(cmd * UINT16_MAX, 0, UINT16_MAX);
1174  if (enabled() && msg->enable) {
1175  ptr->EN = 1;
1176  }
1177  if (clear() || msg->clear) {
1178  ptr->CLEAR = 1;
1179  }
1180  if (msg->ignore) {
1181  ptr->IGNORE = 1;
1182  }
1183  ptr->COUNT = msg->count;
1184  pub_can_.publish(out);
1185 }
1186 
1187 void DbwNode::recvSteeringCmd(const dbw_mkz_msgs::SteeringCmd::ConstPtr& msg)
1188 {
1189  can_msgs::Frame out;
1190  out.id = ID_STEERING_CMD;
1191  out.is_extended = false;
1192  out.dlc = sizeof(MsgSteeringCmd);
1193  MsgSteeringCmd *ptr = (MsgSteeringCmd*)out.data.elems;
1194  memset(ptr, 0x00, sizeof(*ptr));
1195  switch (msg->cmd_type) {
1196  case dbw_mkz_msgs::SteeringCmd::CMD_ANGLE:
1197  ptr->SCMD = std::clamp<float>(msg->steering_wheel_angle_cmd * (float)(180 / M_PI * 10), -INT16_MAX, INT16_MAX);
1198  if (fabsf(msg->steering_wheel_angle_velocity) > 0) {
1200  ptr->SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (float)(180 / M_PI / 4)), 1, 254);
1201  } else {
1202  ptr->SVEL = std::clamp<float>(roundf(fabsf(msg->steering_wheel_angle_velocity) * (float)(180 / M_PI / 2)), 1, 254);
1203  }
1204  }
1205  ptr->CMD_TYPE = dbw_mkz_msgs::SteeringCmd::CMD_ANGLE;
1206  break;
1207  case dbw_mkz_msgs::SteeringCmd::CMD_TORQUE:
1208  ptr->SCMD = std::clamp<float>(msg->steering_wheel_torque_cmd * 128, -INT16_MAX, INT16_MAX);
1209  ptr->CMD_TYPE = dbw_mkz_msgs::SteeringCmd::CMD_TORQUE;
1211  ROS_WARN_THROTTLE(1.0, "Module STEER does not support steering command type TORQUE");
1212  }
1213  break;
1214  default:
1215  ROS_WARN("Unknown steering command type: %u", msg->cmd_type);
1216  break;
1217  }
1218  if (enabled() && msg->enable) {
1219  ptr->EN = 1;
1220  }
1221  if (clear() || msg->clear) {
1222  ptr->CLEAR = 1;
1223  }
1224  if (msg->ignore) {
1225  ptr->IGNORE = 1;
1226  }
1227  if (msg->quiet) {
1228  ptr->QUIET = 1;
1229  }
1230  if (msg->alert) {
1231  ptr->ALERT = 1;
1232  }
1233  ptr->COUNT = msg->count;
1234  pub_can_.publish(out);
1235 }
1236 
1237 void DbwNode::recvGearCmd(const dbw_mkz_msgs::GearCmd::ConstPtr& msg)
1238 {
1239  can_msgs::Frame out;
1240  out.id = ID_GEAR_CMD;
1241  out.is_extended = false;
1242  out.dlc = sizeof(MsgGearCmd);
1243  MsgGearCmd *ptr = (MsgGearCmd*)out.data.elems;
1244  memset(ptr, 0x00, sizeof(*ptr));
1245  if (enabled()) {
1246  ptr->GCMD = msg->cmd.gear;
1247  }
1248  if (clear() || msg->clear) {
1249  ptr->CLEAR = 1;
1250  }
1251  pub_can_.publish(out);
1252 }
1253 
1254 void DbwNode::recvMiscCmd(const dbw_mkz_msgs::MiscCmd::ConstPtr& msg)
1255 {
1256  can_msgs::Frame out;
1257  out.id = ID_MISC_CMD;
1258  out.is_extended = false;
1259  out.dlc = sizeof(MsgMiscCmd);
1260  MsgMiscCmd *ptr = (MsgMiscCmd*)out.data.elems;
1261  memset(ptr, 0x00, sizeof(*ptr));
1262  if (enabled()) {
1263  ptr->TRNCMD = msg->cmd.value;
1264  ptr->PBRKCMD = msg->pbrk.cmd;
1265  }
1266  pub_can_.publish(out);
1267 }
1268 
1270 {
1271  bool en = enabled();
1272  bool change = prev_enable_ != en;
1273  if (change || force) {
1274  std_msgs::Bool msg;
1275  msg.data = en;
1276  pub_sys_enable_.publish(msg);
1277  }
1278  prev_enable_ = en;
1279  return change;
1280 }
1281 
1283 {
1284  // Publish status periodically, in addition to latched and on change
1285  if (publishDbwEnabled(true)) {
1286  ROS_WARN("DBW system enable status changed unexpectedly");
1287  }
1288 
1289  // Clear override statuses if necessary
1290  if (clear()) {
1291  can_msgs::Frame out;
1292  out.is_extended = false;
1293 
1294  if (override_brake_) {
1295  out.id = ID_BRAKE_CMD;
1296  out.dlc = 4; // Sending the full eight bytes will fault the watchdog counter (if enabled)
1297  memset(out.data.elems, 0x00, 8);
1298  ((MsgBrakeCmd*)out.data.elems)->CLEAR = 1;
1299  pub_can_.publish(out);
1300  }
1301 
1302  if (override_throttle_) {
1303  out.id = ID_THROTTLE_CMD;
1304  out.dlc = 4; // Sending the full eight bytes will fault the watchdog counter (if enabled)
1305  memset(out.data.elems, 0x00, 8);
1306  ((MsgThrottleCmd*)out.data.elems)->CLEAR = 1;
1307  pub_can_.publish(out);
1308  }
1309 
1310  if (override_steering_) {
1311  out.id = ID_STEERING_CMD;
1312  out.dlc = 4; // Sending the full eight bytes will fault the watchdog counter (if enabled)
1313  memset(out.data.elems, 0x00, 8);
1314  ((MsgSteeringCmd*)out.data.elems)->CLEAR = 1;
1315  pub_can_.publish(out);
1316  }
1317 
1318  if (override_gear_) {
1319  out.id = ID_GEAR_CMD;
1320  out.dlc = sizeof(MsgGearCmd);
1321  memset(out.data.elems, 0x00, 8);
1322  ((MsgGearCmd*)out.data.elems)->CLEAR = 1;
1323  pub_can_.publish(out);
1324  }
1325  }
1326 }
1327 
1329 {
1330  if (!enable_) {
1331  if (fault()) {
1332  if (fault_steering_cal_) {
1333  ROS_WARN("DBW system not enabled. Steering calibration fault.");
1334  }
1335  if (fault_brakes_) {
1336  ROS_WARN("DBW system not enabled. Braking fault.");
1337  }
1338  if (fault_throttle_) {
1339  ROS_WARN("DBW system not enabled. Throttle fault.");
1340  }
1341  if (fault_steering_) {
1342  ROS_WARN("DBW system not enabled. Steering fault.");
1343  }
1344  if (fault_watchdog_) {
1345  ROS_WARN("DBW system not enabled. Watchdog fault.");
1346  }
1347  } else {
1348  enable_ = true;
1349  if (publishDbwEnabled()) {
1350  ROS_INFO("DBW system enabled.");
1351  } else {
1352  ROS_INFO("DBW system enable requested. Waiting for ready.");
1353  }
1354  }
1355  }
1356 }
1357 
1359 {
1360  if (enable_) {
1361  enable_ = false;
1363  ROS_WARN("DBW system disabled.");
1364  }
1365 }
1366 
1368 {
1369  if (enable_) {
1370  enable_ = false;
1372  ROS_WARN("DBW system disabled. Cancel button pressed.");
1373  }
1374 }
1375 
1376 void DbwNode::overrideBrake(bool override, bool timeout)
1377 {
1378  bool en = enabled();
1379  if (en && timeout) {
1380  override = false;
1381  }
1382  if (en && override) {
1383  enable_ = false;
1384  }
1385  override_brake_ = override;
1386  if (publishDbwEnabled()) {
1387  if (en) {
1388  ROS_WARN("DBW system disabled. Driver override on brake/throttle pedal.");
1389  } else {
1390  ROS_INFO("DBW system enabled.");
1391  }
1392  }
1393 }
1394 
1395 void DbwNode::overrideThrottle(bool override, bool timeout)
1396 {
1397  bool en = enabled();
1398  if (en && timeout) {
1399  override = false;
1400  }
1401  if (en && override) {
1402  enable_ = false;
1403  }
1404  override_throttle_ = override;
1405  if (publishDbwEnabled()) {
1406  if (en) {
1407  ROS_WARN("DBW system disabled. Driver override on brake/throttle pedal.");
1408  } else {
1409  ROS_INFO("DBW system enabled.");
1410  }
1411  }
1412 }
1413 
1414 void DbwNode::overrideSteering(bool override, bool timeout)
1415 {
1416  bool en = enabled();
1417  if (en && timeout) {
1418  override = false;
1419  }
1420  if (en && override) {
1421  enable_ = false;
1422  }
1423  override_steering_ = override;
1424  if (publishDbwEnabled()) {
1425  if (en) {
1426  ROS_WARN("DBW system disabled. Driver override on steering wheel.");
1427  } else {
1428  ROS_INFO("DBW system enabled.");
1429  }
1430  }
1431 }
1432 
1433 void DbwNode::overrideGear(bool override)
1434 {
1435  bool en = enabled();
1436  if (en && override) {
1437  enable_ = false;
1438  }
1439  override_gear_ = override;
1440  if (publishDbwEnabled()) {
1441  if (en) {
1442  ROS_WARN("DBW system disabled. Driver override on shifter.");
1443  } else {
1444  ROS_INFO("DBW system enabled.");
1445  }
1446  }
1447 }
1448 
1449 void DbwNode::timeoutBrake(bool timeout, bool enabled)
1450 {
1451  if (!timeout_brakes_ && enabled_brakes_ && timeout && !enabled) {
1452  ROS_WARN("Brake subsystem disabled after 100ms command timeout");
1453  }
1454  timeout_brakes_ = timeout;
1456 }
1457 
1458 void DbwNode::timeoutThrottle(bool timeout, bool enabled)
1459 {
1460  if (!timeout_throttle_ && enabled_throttle_ && timeout && !enabled) {
1461  ROS_WARN("Throttle subsystem disabled after 100ms command timeout");
1462  }
1463  timeout_throttle_ = timeout;
1465 }
1466 
1467 void DbwNode::timeoutSteering(bool timeout, bool enabled)
1468 {
1469  if (!timeout_steering_ && enabled_steering_ && timeout && !enabled) {
1470  ROS_WARN("Steering subsystem disabled after 100ms command timeout");
1471  }
1472  timeout_steering_ = timeout;
1474 }
1475 
1476 void DbwNode::faultBrakes(bool fault)
1477 {
1478  bool en = enabled();
1479  if (fault && en) {
1480  enable_ = false;
1481  }
1482  fault_brakes_ = fault;
1483  if (publishDbwEnabled()) {
1484  if (en) {
1485  ROS_ERROR("DBW system disabled. Braking fault.");
1486  } else {
1487  ROS_INFO("DBW system enabled.");
1488  }
1489  }
1490 }
1491 
1492 void DbwNode::faultThrottle(bool fault)
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. Throttle fault.");
1502  } else {
1503  ROS_INFO("DBW system enabled.");
1504  }
1505  }
1506 }
1507 
1508 void DbwNode::faultSteering(bool fault)
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. Steering fault.");
1518  } else {
1519  ROS_INFO("DBW system enabled.");
1520  }
1521  }
1522 }
1523 
1525 {
1526  bool en = enabled();
1527  if (fault && en) {
1528  enable_ = false;
1529  }
1531  if (publishDbwEnabled()) {
1532  if (en) {
1533  ROS_ERROR("DBW system disabled. Steering calibration fault.");
1534  } else {
1535  ROS_INFO("DBW system enabled.");
1536  }
1537  }
1538 }
1539 
1540 void DbwNode::faultWatchdog(bool fault, uint8_t src, bool braking)
1541 {
1542  bool en = enabled();
1543  if (fault && en) {
1544  enable_ = false;
1545  }
1547  if (publishDbwEnabled()) {
1548  if (en) {
1549  ROS_ERROR("DBW system disabled. Watchdog fault.");
1550  } else {
1551  ROS_INFO("DBW system enabled.");
1552  }
1553  }
1554  if (braking && !fault_watchdog_using_brakes_) {
1555  ROS_WARN("Watchdog event: Alerting driver and applying brakes.");
1556  } else if (!braking && fault_watchdog_using_brakes_) {
1557  ROS_INFO("Watchdog event: Driver has successfully taken control.");
1558  }
1559  if (fault && src && !fault_watchdog_warned_) {
1560  switch (src) {
1561  case dbw_mkz_msgs::WatchdogCounter::OTHER_BRAKE:
1562  ROS_WARN("Watchdog event: Fault determined by brake controller");
1563  break;
1564  case dbw_mkz_msgs::WatchdogCounter::OTHER_THROTTLE:
1565  ROS_WARN("Watchdog event: Fault determined by throttle controller");
1566  break;
1567  case dbw_mkz_msgs::WatchdogCounter::OTHER_STEERING:
1568  ROS_WARN("Watchdog event: Fault determined by steering controller");
1569  break;
1570  case dbw_mkz_msgs::WatchdogCounter::BRAKE_COUNTER:
1571  ROS_WARN("Watchdog event: Brake command counter failed to increment");
1572  break;
1573  case dbw_mkz_msgs::WatchdogCounter::BRAKE_DISABLED:
1574  ROS_WARN("Watchdog event: Brake transition to disabled while in gear or moving");
1575  break;
1576  case dbw_mkz_msgs::WatchdogCounter::BRAKE_COMMAND:
1577  ROS_WARN("Watchdog event: Brake command timeout after 100ms");
1578  break;
1579  case dbw_mkz_msgs::WatchdogCounter::BRAKE_REPORT:
1580  ROS_WARN("Watchdog event: Brake report timeout after 100ms");
1581  break;
1582  case dbw_mkz_msgs::WatchdogCounter::THROTTLE_COUNTER:
1583  ROS_WARN("Watchdog event: Throttle command counter failed to increment");
1584  break;
1585  case dbw_mkz_msgs::WatchdogCounter::THROTTLE_DISABLED:
1586  ROS_WARN("Watchdog event: Throttle transition to disabled while in gear or moving");
1587  break;
1588  case dbw_mkz_msgs::WatchdogCounter::THROTTLE_COMMAND:
1589  ROS_WARN("Watchdog event: Throttle command timeout after 100ms");
1590  break;
1591  case dbw_mkz_msgs::WatchdogCounter::THROTTLE_REPORT:
1592  ROS_WARN("Watchdog event: Throttle report timeout after 100ms");
1593  break;
1594  case dbw_mkz_msgs::WatchdogCounter::STEERING_COUNTER:
1595  ROS_WARN("Watchdog event: Steering command counter failed to increment");
1596  break;
1597  case dbw_mkz_msgs::WatchdogCounter::STEERING_DISABLED:
1598  ROS_WARN("Watchdog event: Steering transition to disabled while in gear or moving");
1599  break;
1600  case dbw_mkz_msgs::WatchdogCounter::STEERING_COMMAND:
1601  ROS_WARN("Watchdog event: Steering command timeout after 100ms");
1602  break;
1603  case dbw_mkz_msgs::WatchdogCounter::STEERING_REPORT:
1604  ROS_WARN("Watchdog event: Steering report timeout after 100ms");
1605  break;
1606  }
1607  fault_watchdog_warned_ = true;
1608  } else if (!fault) {
1609  fault_watchdog_warned_ = false;
1610  }
1611  fault_watchdog_using_brakes_ = braking;
1613  ROS_WARN_THROTTLE(2.0, "Watchdog event: Press left OK button on the steering wheel or cycle power to clear event.");
1614  }
1615 }
1616 
1617 void DbwNode::faultWatchdog(bool fault, uint8_t src) {
1618  faultWatchdog(fault, src, fault_watchdog_using_brakes_); // No change to 'using brakes' status
1619 }
1620 
1621 void DbwNode::publishJointStates(const ros::Time &stamp, const dbw_mkz_msgs::WheelSpeedReport *wheels, const dbw_mkz_msgs::SteeringReport *steering)
1622 {
1623  double dt = (stamp - joint_state_.header.stamp).toSec();
1624  if (wheels) {
1625  if (std::isfinite(wheels->front_left)) {
1626  joint_state_.velocity[JOINT_FL] = wheels->front_left;
1627  }
1628  if (std::isfinite(wheels->front_right)) {
1629  joint_state_.velocity[JOINT_FR] = wheels->front_right;
1630  }
1631  if (std::isfinite(wheels->rear_left)) {
1632  joint_state_.velocity[JOINT_RL] = wheels->rear_left;
1633  }
1634  if (std::isfinite(wheels->rear_right)) {
1635  joint_state_.velocity[JOINT_RR] = wheels->rear_right;
1636  }
1637  }
1638  if (steering) {
1639  if (std::isfinite(steering->steering_wheel_angle)) {
1640  const double L = acker_wheelbase_;
1641  const double W = acker_track_;
1642  const double r = L / tan(steering->steering_wheel_angle / steering_ratio_);
1643  joint_state_.position[JOINT_SL] = atan(L / (r - W/2));
1644  joint_state_.position[JOINT_SR] = atan(L / (r + W/2));
1645  }
1646  }
1647  if (dt < 0.5) {
1648  for (size_t i = JOINT_FL; i <= JOINT_RR; i++) {
1649  joint_state_.position[i] = fmod(joint_state_.position[i] + dt * joint_state_.velocity[i], 2*M_PI);
1650  }
1651  }
1652  joint_state_.header.stamp = stamp;
1654 }
1655 
1656 } // namespace dbw_mkz_can
1657 
dbw_mkz_can::MsgReportSurround::l_blis_alert
uint8_t l_blis_alert
Definition: dispatch.h:338
dbw_mkz_can::MsgMiscReport::btn_rd_ok
uint8_t btn_rd_ok
Definition: dispatch.h:239
dbw_mkz_can::MsgMiscCmd
Definition: dispatch.h:196
dbw_mkz_can::MsgReportWheelPosition::rear_left
int16_t rear_left
Definition: dispatch.h:315
dbw_mkz_can::DbwNode::ldate_
std::string ldate_
Definition: DbwNode.h:222
dbw_mkz_can::MsgMiscReport::btn_ld_down
uint8_t btn_ld_down
Definition: dispatch.h:233
dbw_mkz_can::MsgSteeringCmd
Definition: dispatch.h:144
dbw_mkz_can::MsgReportThrottleInfo::batt_curr
int16_t batt_curr
Definition: dispatch.h:389
dbw_mkz_can::DbwNode::enable_
bool enable_
Definition: DbwNode.h:162
dbw_mkz_can::MsgReportAccel::accel_long
int16_t accel_long
Definition: dispatch.h:265
NAME
string NAME
dbw_mkz_can::LIC_MUX_F0
@ LIC_MUX_F0
Definition: dispatch.h:408
dbw_mkz_can::MsgBrakeReport::ENABLED
uint8_t ENABLED
Definition: dispatch.h:102
dbw_mkz_can::MsgThrottleCmd::CLEAR
uint8_t CLEAR
Definition: dispatch.h:117
dbw_mkz_can::MsgLicense::expired
uint8_t expired
Definition: dispatch.h:429
dbw_mkz_can::MsgSteeringReport::FLTCAL
uint8_t FLTCAL
Definition: dispatch.h:174
dbw_mkz_can::DbwNode::pub_vin_
ros::Publisher pub_vin_
Definition: DbwNode.h:281
dbw_mkz_can::DbwNode::sub_gear_
ros::Subscriber sub_gear_
Definition: DbwNode.h:255
dbw_mkz_can::MsgSteeringReport::FLTBUS2
uint8_t FLTBUS2
Definition: dispatch.h:173
dbw_mkz_can::MsgReportDriverAssist::decel
uint8_t decel
Definition: dispatch.h:393
dbw_mkz_can::DbwNode::fault_throttle_
bool fault_throttle_
Definition: DbwNode.h:168
dbw_mkz_can::MsgMiscReport::btn_cc_on_off
uint8_t btn_cc_on_off
Definition: dispatch.h:213
dbw_mkz_can::DbwNode::fault_steering_
bool fault_steering_
Definition: DbwNode.h:169
dbw_mkz_can::ID_THROTTLE_REPORT
@ ID_THROTTLE_REPORT
Definition: dispatch.h:550
dbw_mkz_can::MsgReportBrakeInfo::trac_active
uint8_t trac_active
Definition: dispatch.h:375
dbw_mkz_can::ID_MISC_CMD
@ ID_MISC_CMD
Definition: dispatch.h:555
dbw_mkz_can::MsgBrakeReport::FLTPWR
uint8_t FLTPWR
Definition: dispatch.h:108
dbw_mkz_can::MsgMiscReport::btn_mute
uint8_t btn_mute
Definition: dispatch.h:247
dbw_mkz_can::brakeTorqueFromPedal
static float brakeTorqueFromPedal(float pedal)
Definition: pedal_lut.h:96
dbw_mkz_can::MsgReportBrakeInfo::accel_over_ground_est
int16_t accel_over_ground_est
Definition: dispatch.h:370
dbw_mkz_can::MsgReportSurround::sonar_10
uint8_t sonar_10
Definition: dispatch.h:354
dbw_mkz_can::DbwNode::prev_enable_
bool prev_enable_
Definition: DbwNode.h:161
dbw_mkz_can::DbwNode::acker_track_
double acker_track_
Definition: DbwNode.h:242
dbw_mkz_can::MsgReportBrakeInfo
Definition: dispatch.h:361
dbw_mkz_can::ID_REPORT_DRIVER_ASSIST
@ ID_REPORT_DRIVER_ASSIST
Definition: dispatch.h:569
dbw_mkz_can::MsgLicense::mux
uint8_t mux
Definition: dispatch.h:426
dbw_mkz_can::MsgSteeringReport::TORQUE
int8_t TORQUE
Definition: dispatch.h:167
sonar_lut.h
dbw_mkz_can::MsgSteeringReport::OVERRIDE
uint8_t OVERRIDE
Definition: dispatch.h:169
dbw_mkz_can::MsgReportSurround::sonar_01
uint8_t sonar_01
Definition: dispatch.h:345
dbw_mkz_can::MsgMiscReport::btn_media
uint8_t btn_media
Definition: dispatch.h:244
dbw_mkz_can::DbwNode::faultSteeringCal
void faultSteeringCal(bool fault)
Definition: DbwNode.cpp:1524
dbw_mkz_can::ID_BRAKE_REPORT
@ ID_BRAKE_REPORT
Definition: dispatch.h:548
ROS_INFO_ONCE_ID
#define ROS_INFO_ONCE_ID(id,...)
Definition: DbwNode.cpp:54
dbw_mkz_can::MsgMiscReport::btn_cc_res_dec
uint8_t btn_cc_res_dec
Definition: dispatch.h:236
dbw_mkz_can::MsgReportSurround::sonar_00
uint8_t sonar_00
Definition: dispatch.h:344
dbw_mkz_can::MsgThrottleReport
Definition: dispatch.h:128
dbw_mkz_can::MsgMiscReport::btn_cc_cncl
uint8_t btn_cc_cncl
Definition: dispatch.h:211
dbw_mkz_can::ID_REPORT_GPS2
@ ID_REPORT_GPS2
Definition: dispatch.h:561
dbw_mkz_can::MsgBrakeCmd::IGNORE
uint8_t IGNORE
Definition: dispatch.h:116
dbw_mkz_can::DbwNode::timerCallback
void timerCallback(const ros::TimerEvent &event)
Definition: DbwNode.cpp:1282
dbw_mkz_can::MsgReportSurround::r_cta_alert
uint8_t r_cta_alert
Definition: dispatch.h:340
dbw_mkz_can::MsgLicense::mac
struct dbw_mkz_can::MsgLicense::@1::@6 mac
dbw_mkz_can::MsgReportSurround::sonar_enabled
uint8_t sonar_enabled
Definition: dispatch.h:357
dbw_mkz_can::ID_VERSION
@ ID_VERSION
Definition: dispatch.h:571
dbw_mkz_can::ID_GEAR_REPORT
@ ID_GEAR_REPORT
Definition: dispatch.h:554
dbw_mkz_can::DbwNode::recvSteeringCmd
void recvSteeringCmd(const dbw_mkz_msgs::SteeringCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1187
dbw_mkz_can::DbwNode::pub_gps_vel_
ros::Publisher pub_gps_vel_
Definition: DbwNode.h:277
dbw_mkz_can::MsgBrakeReport::FLT1
uint8_t FLT1
Definition: dispatch.h:106
dbw_mkz_can::M_EPS
@ M_EPS
Definition: PlatformVersion.h:100
dbw_mkz_can::MsgThrottleReport::FLT2
uint8_t FLT2
Definition: dispatch.h:139
dbw_mkz_can::DbwNode::sub_brake_
ros::Subscriber sub_brake_
Definition: DbwNode.h:252
dbw_mkz_can::MsgSteeringReport::FLTWDC
uint8_t FLTWDC
Definition: dispatch.h:171
dbw_mkz_can::DbwNode::sync_gps_
dataspeed_can_msg_filters::ApproximateTime sync_gps_
Definition: DbwNode.h:286
dbw_mkz_can::MsgMiscReport::btn_prev
uint8_t btn_prev
Definition: dispatch.h:249
dbw_mkz_can::MsgReportSurround::r_blis_enabled
uint8_t r_blis_enabled
Definition: dispatch.h:343
dbw_mkz_can::DbwNode::sub_can_
ros::Subscriber sub_can_
Definition: DbwNode.h:251
dbw_mkz_can::ID_REPORT_WHEEL_SPEED
@ ID_REPORT_WHEEL_SPEED
Definition: dispatch.h:557
dbw_mkz_can::DbwNode::pub_gps_fix_
ros::Publisher pub_gps_fix_
Definition: DbwNode.h:276
ROS_WARN_ONCE_ID
#define ROS_WARN_ONCE_ID(id,...)
Definition: DbwNode.cpp:55
dbw_mkz_can::MsgLicense::ldate1
uint8_t ldate1
Definition: dispatch.h:443
dbw_mkz_can::ID_THROTTLE_CMD
@ ID_THROTTLE_CMD
Definition: dispatch.h:549
dbw_mkz_can::MsgMiscReport::btn_cc_gap_inc
uint8_t btn_cc_gap_inc
Definition: dispatch.h:217
dbw_mkz_can::MsgMiscReport::pasngr_detect
uint8_t pasngr_detect
Definition: dispatch.h:227
dbw_mkz_can::MsgSteeringReport::VEH_VEL
int16_t VEH_VEL
Definition: dispatch.h:166
dbw_mkz_can::MsgReportBrakeInfo::hsa_mode
uint8_t hsa_mode
Definition: dispatch.h:366
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
dbw_mkz_can::MsgReportDriverAssist::aeb_enabled
uint8_t aeb_enabled
Definition: dispatch.h:398
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
dbw_mkz_can::MsgSteeringCmd::CMD_TYPE
uint8_t CMD_TYPE
Definition: dispatch.h:153
dbw_mkz_can::MsgThrottleReport::ENABLED
uint8_t ENABLED
Definition: dispatch.h:134
dbw_mkz_can::FIRMWARE_HIGH_RATE_LIMIT
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))}, })
dbw_mkz_can::MsgLicense::vin2
struct dbw_mkz_can::MsgLicense::@1::@11 vin2
dbw_mkz_can::DbwNode::timeoutThrottle
void timeoutThrottle(bool timeout, bool enabled)
Definition: DbwNode.cpp:1458
dbw_mkz_can::MsgReportBrakeInfo::abs_active
uint8_t abs_active
Definition: dispatch.h:371
dbw_mkz_can::MsgMiscCmd::TRNCMD
uint8_t TRNCMD
Definition: dispatch.h:197
dbw_mkz_can::MsgReportSurround::l_cta_alert
uint8_t l_cta_alert
Definition: dispatch.h:336
dbw_mkz_can::DbwNode::pub_can_
ros::Publisher pub_can_
Definition: DbwNode.h:260
dbw_mkz_can::MsgBrakeReport::WDCBRK
uint8_t WDCBRK
Definition: dispatch.h:100
dbw_mkz_can::Platform
Platform
Definition: PlatformVersion.h:77
dbw_mkz_can::DbwNode::fault_watchdog_warned_
bool fault_watchdog_warned_
Definition: DbwNode.h:173
dbw_mkz_can::DbwNode::publishDbwEnabled
bool publishDbwEnabled(bool force=false)
Definition: DbwNode.cpp:1269
dbw_mkz_can::MsgThrottleReport::PO
uint16_t PO
Definition: dispatch.h:131
dbw_mkz_can::MsgMiscReport::btn_cc_res_inc
uint8_t btn_cc_res_inc
Definition: dispatch.h:212
dbw_mkz_can::P_FORD_P5
@ P_FORD_P5
Definition: PlatformVersion.h:111
dbw_mkz_can::MsgReportDriverAssist
Definition: dispatch.h:392
dbw_mkz_can::DbwNode::JOINT_FR
@ JOINT_FR
Definition: DbwNode.h:205
dbw_mkz_can::ID_STEERING_CMD
@ ID_STEERING_CMD
Definition: dispatch.h:551
dbw_mkz_can::MsgMiscReport::btn_call_end
uint8_t btn_call_end
Definition: dispatch.h:252
dbw_mkz_can::DbwNode::JOINT_SR
@ JOINT_SR
Definition: DbwNode.h:209
ROS_DEBUG
#define ROS_DEBUG(...)
dbw_mkz_can::DbwNode::timeout_brakes_
bool timeout_brakes_
Definition: DbwNode.h:174
ros::TransportHints
dbw_mkz_can::MsgThrottleReport::TMOUT
uint8_t TMOUT
Definition: dispatch.h:141
dbw_mkz_can::MsgBrakeReport::OVERRIDE
uint8_t OVERRIDE
Definition: dispatch.h:103
dbw_mkz_can::DbwNode
Definition: DbwNode.h:109
dbw_mkz_can::Module
Module
Definition: PlatformVersion.h:93
dbw_mkz_can::MsgReportBrakeInfo::stab_active
uint8_t stab_active
Definition: dispatch.h:373
dbw_mkz_can::moduleToString
static const char * moduleToString(Module x)
Definition: PlatformVersion.h:121
dbw_mkz_can::MsgBrakeReport::BC
uint8_t BC
Definition: dispatch.h:99
dbw_mkz_can::MsgGearReport::READY
uint8_t READY
Definition: dispatch.h:193
dbw_mkz_can::M_BPEC
@ M_BPEC
Definition: PlatformVersion.h:94
dbw_mkz_can::LIC_MUX_VIN0
@ LIC_MUX_VIN0
Definition: dispatch.h:421
dbw_mkz_can::brakePedalFromPercent
static float brakePedalFromPercent(float percent)
Definition: pedal_lut.h:142
dbw_mkz_can::MsgMiscReport::btn_ld_right
uint8_t btn_ld_right
Definition: dispatch.h:235
dbw_mkz_can::DbwNode::pub_throttle_
ros::Publisher pub_throttle_
Definition: DbwNode.h:262
dbw_mkz_can::DbwNode::recvDisable
void recvDisable(const std_msgs::Empty::ConstPtr &msg)
Definition: DbwNode.cpp:239
dbw_mkz_can::DbwNode::DbwNode
DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
Definition: DbwNode.cpp:117
dbw_mkz_can::MsgReportGps1::longitude
int32_t longitude
Definition: dispatch.h:277
dbw_mkz_can::MsgReportSurround::sonar_11
uint8_t sonar_11
Definition: dispatch.h:355
boost
dbw_mkz_can::DbwNode::timeoutBrake
void timeoutBrake(bool timeout, bool enabled)
Definition: DbwNode.cpp:1449
dbw_mkz_can::DbwNode::pub_brake_
ros::Publisher pub_brake_
Definition: DbwNode.h:261
dbw_mkz_can::MsgThrottleCmd::PCMD
uint16_t PCMD
Definition: dispatch.h:113
dbw_mkz_can::MsgBrakeCmd::PCMD
uint16_t PCMD
Definition: dispatch.h:109
dbw_mkz_can::MsgReportBrakeInfo::hsa_stat
uint8_t hsa_stat
Definition: dispatch.h:363
dbw_mkz_can::ID_LICENSE
@ ID_LICENSE
Definition: dispatch.h:570
dbw_mkz_can::P_FORD_GE1
@ P_FORD_GE1
Definition: PlatformVersion.h:116
dbw_mkz_can::MsgReportFuelLevel::odometer
uint32_t odometer
Definition: dispatch.h:331
dbw_mkz_can::MsgMiscReport::btn_next
uint8_t btn_next
Definition: dispatch.h:250
dbw_mkz_can::DbwNode::bdate_
std::map< uint8_t, std::string > bdate_
Definition: DbwNode.h:223
dbw_mkz_can::MsgReportGps3::altitude
int16_t altitude
Definition: dispatch.h:303
dbw_mkz_can::MsgThrottleCmd
Definition: dispatch.h:112
dbw_mkz_can::MsgReportDriverAssist::acc_enabled
uint8_t acc_enabled
Definition: dispatch.h:402
dbw_mkz_can::MsgSteeringCmd::ALERT
uint8_t ALERT
Definition: dispatch.h:152
dbw_mkz_can::MsgReportWheelPosition::rear_right
int16_t rear_right
Definition: dispatch.h:316
dbw_mkz_can::P_FORD_T6
@ P_FORD_T6
Definition: PlatformVersion.h:113
dbw_mkz_can::DbwNode::faultThrottle
void faultThrottle(bool fault)
Definition: DbwNode.cpp:1492
dbw_mkz_can::MsgMiscReport::buckle_driver
uint8_t buckle_driver
Definition: dispatch.h:229
dbw_mkz_can::MsgLicense::vin1
struct dbw_mkz_can::MsgLicense::@1::@10 vin1
dbw_mkz_can::DbwNode::disableSystem
void disableSystem()
Definition: DbwNode.cpp:1358
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
dbw_mkz_can::MsgReportSurround::sonar_06
uint8_t sonar_06
Definition: dispatch.h:350
dbw_mkz_can::DbwNode::pub_driver_assist_
ros::Publisher pub_driver_assist_
Definition: DbwNode.h:274
dbw_mkz_can::MsgLicense::vin0
struct dbw_mkz_can::MsgLicense::@1::@9 vin0
dbw_mkz_can::MsgMiscReport::btn_vol_dec
uint8_t btn_vol_dec
Definition: dispatch.h:246
dbw_mkz_can::MsgReportGps3::quality
uint8_t quality
Definition: dispatch.h:308
dbw_mkz_can::DbwNode::recvEnable
void recvEnable(const std_msgs::Empty::ConstPtr &msg)
Definition: DbwNode.cpp:234
dbw_mkz_can::DbwNode::sub_disable_
ros::Subscriber sub_disable_
Definition: DbwNode.h:250
dbw_mkz_can::MsgBrakeReport::DRIVER
uint8_t DRIVER
Definition: dispatch.h:104
dbw_mkz_can::MsgReportAccel::accel_lat
int16_t accel_lat
Definition: dispatch.h:264
ros::TransportHints::tcpNoDelay
TransportHints & tcpNoDelay(bool nodelay=true)
dbw_mkz_can::DbwNode::override_throttle_
bool override_throttle_
Definition: DbwNode.h:164
dbw_mkz_can::MsgReportDriverAssist::fcw_active
uint8_t fcw_active
Definition: dispatch.h:397
f
f
dbw_mkz_can::MsgLicense::trial
uint8_t trial
Definition: dispatch.h:428
dbw_mkz_can::MsgReportFuelLevel::battery_12v
uint8_t battery_12v
Definition: dispatch.h:330
dbw_mkz_can::DbwNode::acker_wheelbase_
double acker_wheelbase_
Definition: DbwNode.h:241
dbw_mkz_can::MsgGearReport::STATE
uint8_t STATE
Definition: dispatch.h:187
ROS_WARN_COND
#define ROS_WARN_COND(cond,...)
dbw_mkz_can::MsgBrakeReport::FLT2
uint8_t FLT2
Definition: dispatch.h:107
dbw_mkz_can::MsgReportSurround::sonar_04
uint8_t sonar_04
Definition: dispatch.h:348
dbw_mkz_can::MsgThrottleCmd::CMD_TYPE
uint8_t CMD_TYPE
Definition: dispatch.h:115
dbw_mkz_can::MsgMiscReport::wiper_front
uint8_t wiper_front
Definition: dispatch.h:206
dbw_mkz_can::MsgMiscReport::door_trunk
uint8_t door_trunk
Definition: dispatch.h:226
dbw_mkz_can::DbwNode::recvCanGps
void recvCanGps(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
Definition: DbwNode.cpp:967
dbw_mkz_can::FIRMWARE_TIMEOUT
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))}, })
dbw_mkz_can::sonarMetersFromBits
static float sonarMetersFromBits(uint8_t bits)
Definition: sonar_lut.h:90
dbw_mkz_can::MsgMiscReport::btn_rd_down
uint8_t btn_rd_down
Definition: dispatch.h:241
dbw_mkz_can::DbwNode::publishJointStates
void publishJointStates(const ros::Time &stamp, const dbw_mkz_msgs::WheelSpeedReport *wheels, const dbw_mkz_msgs::SteeringReport *steering)
Definition: DbwNode.cpp:1621
dbw_mkz_can::DbwNode::buttonCancel
void buttonCancel()
Definition: DbwNode.cpp:1367
dbw_mkz_can::DbwNode::pub_surround_
ros::Publisher pub_surround_
Definition: DbwNode.h:270
dbw_mkz_can::DbwNode::recvGearCmd
void recvGearCmd(const dbw_mkz_msgs::GearCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1237
dbw_mkz_can::ModuleVersion::minor
uint16_t minor() const
Definition: ModuleVersion.h:127
dispatch.h
dbw_mkz_can::MsgSteeringReport
Definition: dispatch.h:162
dbw_mkz_can::MsgLicense::bdate1
struct dbw_mkz_can::MsgLicense::@1::@8 bdate1
dbw_mkz_can::PlatformMap::findPlatform
PlatformVersion findPlatform(Module m) const
Definition: PlatformMap.h:153
dbw_mkz_can::MsgBrakeReport::PI
uint16_t PI
Definition: dispatch.h:95
dbw_mkz_can::MsgReportSurround
Definition: dispatch.h:335
dbw_mkz_can::DbwNode::recvCanImu
void recvCanImu(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
Definition: DbwNode.cpp:921
dbw_mkz_can::DbwNode::pub_steering_
ros::Publisher pub_steering_
Definition: DbwNode.h:263
dbw_mkz_can::LIC_MUX_BDATE1
@ LIC_MUX_BDATE1
Definition: dispatch.h:420
dbw_mkz_can::PlatformMap::findModule
ModuleVersion findModule(Module m) const
Definition: PlatformMap.h:129
dbw_mkz_can::DbwNode::enabled
bool enabled()
Definition: DbwNode.h:184
dbw_mkz_can::MsgMiscReport::btn_cc_off
uint8_t btn_cc_off
Definition: dispatch.h:209
dbw_mkz_can::MsgMiscReport::btn_ld_up
uint8_t btn_ld_up
Definition: dispatch.h:232
dbw_mkz_can::MsgSteeringCmd::EN
uint8_t EN
Definition: dispatch.h:146
dbw_mkz_can::FIRMWARE_LATEST
PlatformMap FIRMWARE_LATEST({ {PlatformVersion(P_FORD_C1, M_TPEC, ModuleVersion(1, 3, 4))}, {PlatformVersion(P_FORD_C1, M_STEER, ModuleVersion(1, 3, 4))}, {PlatformVersion(P_FORD_C1, M_SHIFT, ModuleVersion(1, 3, 4))}, {PlatformVersion(P_FORD_C1, M_ABS, ModuleVersion(1, 3, 4))}, {PlatformVersion(P_FORD_C1, M_BOO, ModuleVersion(1, 3, 4))}, {PlatformVersion(P_FORD_C1, M_EPS, ModuleVersion(1, 3, 4))}, {PlatformVersion(P_FORD_CD4, M_BPEC, ModuleVersion(2, 6, 4))}, {PlatformVersion(P_FORD_CD4, M_TPEC, ModuleVersion(2, 6, 4))}, {PlatformVersion(P_FORD_CD4, M_STEER, ModuleVersion(2, 6, 4))}, {PlatformVersion(P_FORD_CD4, M_SHIFT, ModuleVersion(2, 6, 4))}, {PlatformVersion(P_FORD_CD5, M_BOO, ModuleVersion(1, 2, 4))}, {PlatformVersion(P_FORD_CD5, M_TPEC, ModuleVersion(1, 2, 4))}, {PlatformVersion(P_FORD_CD5, M_STEER, ModuleVersion(1, 2, 4))}, {PlatformVersion(P_FORD_GE1, M_TPEC, ModuleVersion(1, 0, 4))}, {PlatformVersion(P_FORD_GE1, M_STEER, ModuleVersion(1, 0, 4))}, {PlatformVersion(P_FORD_GE1, M_SHIFT, ModuleVersion(1, 0, 4))}, {PlatformVersion(P_FORD_P5, M_TPEC, ModuleVersion(1, 5, 4))}, {PlatformVersion(P_FORD_P5, M_STEER, ModuleVersion(1, 5, 4))}, {PlatformVersion(P_FORD_P5, M_SHIFT, ModuleVersion(1, 5, 4))}, {PlatformVersion(P_FORD_P5, M_ABS, ModuleVersion(1, 5, 4))}, {PlatformVersion(P_FORD_P5, M_BOO, ModuleVersion(1, 5, 4))}, {PlatformVersion(P_FORD_P702, M_TPEC, ModuleVersion(0, 1, 4))}, {PlatformVersion(P_FORD_P702, M_STEER, ModuleVersion(0, 1, 4))}, {PlatformVersion(P_FORD_P702, M_SHIFT, ModuleVersion(0, 1, 4))}, {PlatformVersion(P_FORD_T6, M_TPEC, ModuleVersion(0, 3, 4))}, {PlatformVersion(P_FORD_T6, M_STEER, ModuleVersion(0, 3, 4))}, {PlatformVersion(P_FORD_T6, M_SHIFT, ModuleVersion(0, 3, 4))}, {PlatformVersion(P_FORD_U6, M_TPEC, ModuleVersion(1, 1, 4))}, {PlatformVersion(P_FORD_U6, M_STEER, ModuleVersion(1, 1, 4))}, {PlatformVersion(P_FORD_U6, M_SHIFT, ModuleVersion(1, 1, 4))}, {PlatformVersion(P_FORD_U6, M_ABS, ModuleVersion(1, 1, 4))}, {PlatformVersion(P_FORD_U6, M_BOO, ModuleVersion(1, 1, 4))}, })
dbw_mkz_can::DbwNode::sub_enable_
ros::Subscriber sub_enable_
Definition: DbwNode.h:249
dbw_mkz_can::MsgLicense::license
struct dbw_mkz_can::MsgLicense::@1::@3 license
dbw_mkz_can::MsgVersion::major
uint16_t major
Definition: dispatch.h:511
dbw_mkz_can::MsgReportSurround::sonar_09
uint8_t sonar_09
Definition: dispatch.h:353
dbw_mkz_can::DbwNode::JOINT_COUNT
@ JOINT_COUNT
Definition: DbwNode.h:210
dbw_mkz_can::MsgReportWheelSpeed::rear_right
int16_t rear_right
Definition: dispatch.h:260
dbw_mkz_can::DbwNode::overrideGear
void overrideGear(bool override)
Definition: DbwNode.cpp:1433
dbw_mkz_can::DbwNode::override_steering_
bool override_steering_
Definition: DbwNode.h:165
dbw_mkz_can::DbwNode::pedal_luts_
bool pedal_luts_
Definition: DbwNode.h:238
dbw_mkz_can::DbwNode::pub_gear_
ros::Publisher pub_gear_
Definition: DbwNode.h:264
dbw_mkz_can::MsgSteeringReport::CMD
int16_t CMD
Definition: dispatch.h:164
dbw_mkz_can::MsgBrakeCmd::BCMD
uint8_t BCMD
Definition: dispatch.h:110
dbw_mkz_can::DbwNode::pub_fuel_level_
ros::Publisher pub_fuel_level_
Definition: DbwNode.h:269
dbw_mkz_can::MsgThrottleReport::FLTWDC
uint8_t FLTWDC
Definition: dispatch.h:137
dbw_mkz_can::MsgSteeringCmd::IGNORE
uint8_t IGNORE
Definition: dispatch.h:148
dbw_mkz_can::MsgMiscReport::turn_signal
uint8_t turn_signal
Definition: dispatch.h:204
dbw_mkz_can::MsgReportGps1::latitude
int32_t latitude
Definition: dispatch.h:275
dbw_mkz_can::ID_REPORT_THROTTLE_INFO
@ ID_REPORT_THROTTLE_INFO
Definition: dispatch.h:568
dbw_mkz_can::MsgThrottleCmd::IGNORE
uint8_t IGNORE
Definition: dispatch.h:118
dbw_mkz_can::DbwNode::sub_misc_
ros::Subscriber sub_misc_
Definition: DbwNode.h:257
dbw_mkz_can::MsgSteeringCmd::SCMD
int16_t SCMD
Definition: dispatch.h:145
dbw_mkz_can::MsgReportGps2
Definition: dispatch.h:281
dbw_mkz_can::MsgReportBrakeInfo::stationary
uint8_t stationary
Definition: dispatch.h:364
dbw_mkz_can::MsgReportSurround::sonar_05
uint8_t sonar_05
Definition: dispatch.h:349
dbw_mkz_can::DbwNode::fault_brakes_
bool fault_brakes_
Definition: DbwNode.h:167
dbw_mkz_can::MsgThrottleCmd::EN
uint8_t EN
Definition: dispatch.h:116
dbw_mkz_can::MsgReportWheelPosition::front_right
int16_t front_right
Definition: dispatch.h:314
dbw_mkz_can::MsgReportBrakeInfo::parking_brake
uint8_t parking_brake
Definition: dispatch.h:367
dbw_mkz_can::DbwNode::enabled_steering_
bool enabled_steering_
Definition: DbwNode.h:179
dbw_mkz_can::MsgMiscCmd::PBRKCMD
uint8_t PBRKCMD
Definition: dispatch.h:198
dbw_mkz_can::DbwNode::overrideThrottle
void overrideThrottle(bool override, bool timeout)
Definition: DbwNode.cpp:1395
dbw_mkz_can::throttlePedalFromPercent
static float throttlePedalFromPercent(float percent)
Definition: pedal_lut.h:145
dbw_mkz_can::DbwNode::recvBrakeCmd
void recvBrakeCmd(const dbw_mkz_msgs::BrakeCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1035
dbw_mkz_can::DbwNode::firmware_
PlatformMap firmware_
Definition: DbwNode.h:226
dbw_mkz_can::MsgMiscReport::door_rear_right
uint8_t door_rear_right
Definition: dispatch.h:224
dataspeed_can_msg_filters::ApproximateTime::setInterMessageLowerBound
void setInterMessageLowerBound(ros::Duration lower_bound)
dbw_mkz_can::MsgLicense::ready
uint8_t ready
Definition: dispatch.h:427
dbw_mkz_can::ID_REPORT_BRAKE_INFO
@ ID_REPORT_BRAKE_INFO
Definition: dispatch.h:567
dbw_mkz_can::DbwNode::timer_
ros::Timer timer_
Definition: DbwNode.h:160
dbw_mkz_can::MsgReportThrottleInfo::engine_rpm
uint16_t engine_rpm
Definition: dispatch.h:380
dbw_mkz_can::MsgReportBrakeInfo::stab_enabled
uint8_t stab_enabled
Definition: dispatch.h:374
dbw_mkz_can::MsgVersion::minor
uint16_t minor
Definition: dispatch.h:512
dbw_mkz_can::MsgBrakeReport::WDCSRC
uint8_t WDCSRC
Definition: dispatch.h:101
dbw_mkz_can::MsgReportFuelLevel::battery_hev
uint16_t battery_hev
Definition: dispatch.h:329
dbw_mkz_can::MsgMiscReport::buckle_pasngr
uint8_t buckle_pasngr
Definition: dispatch.h:230
dbw_mkz_can::MsgThrottleReport::WDCSRC
uint8_t WDCSRC
Definition: dispatch.h:133
dbw_mkz_can::DbwNode::recvMiscCmd
void recvMiscCmd(const dbw_mkz_msgs::MiscCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1254
dbw_mkz_can::M_ABS
@ M_ABS
Definition: PlatformVersion.h:98
dbw_mkz_can::LIC_MUX_VIN2
@ LIC_MUX_VIN2
Definition: dispatch.h:423
dbw_mkz_can::MsgSteeringCmd::COUNT
uint8_t COUNT
Definition: dispatch.h:159
ROS_INFO_ONCE
#define ROS_INFO_ONCE(...)
dbw_mkz_can::DbwNode::fault_watchdog_
bool fault_watchdog_
Definition: DbwNode.h:171
dbw_mkz_can::MsgSteeringCmd::CLEAR
uint8_t CLEAR
Definition: dispatch.h:147
dbw_mkz_can::DbwNode::pub_wheel_speeds_
ros::Publisher pub_wheel_speeds_
Definition: DbwNode.h:266
dbw_mkz_can::DbwNode::gear_warned_
bool gear_warned_
Definition: DbwNode.h:180
dbw_mkz_can::MsgReportThrottleInfo::one_pedal_drive
uint8_t one_pedal_drive
Definition: dispatch.h:383
dbw_mkz_can::MsgReportWheelSpeed::front_left
int16_t front_left
Definition: dispatch.h:257
dbw_mkz_can::MsgReportThrottleInfo::ign_stat
uint8_t ign_stat
Definition: dispatch.h:388
dbw_mkz_can::MsgReportFuelLevel
Definition: dispatch.h:326
dbw_mkz_can::MsgReportGps3
Definition: dispatch.h:302
ROS_ERROR
#define ROS_ERROR(...)
dbw_mkz_can::MsgGearReport
Definition: dispatch.h:186
dbw_mkz_can::DbwNode::pub_sonar_cloud_
ros::Publisher pub_sonar_cloud_
Definition: DbwNode.h:271
dbw_mkz_can::DbwNode::recvCAN
void recvCAN(const can_msgs::Frame::ConstPtr &msg)
Definition: DbwNode.cpp:244
dbw_mkz_can::M_STEER
@ M_STEER
Definition: PlatformVersion.h:96
dbw_mkz_can::DbwNode::faultBrakes
void faultBrakes(bool fault)
Definition: DbwNode.cpp:1476
dbw_mkz_can::DbwNode::enabled_brakes_
bool enabled_brakes_
Definition: DbwNode.h:177
dbw_mkz_can::MsgReportSurround::sonar_08
uint8_t sonar_08
Definition: dispatch.h:352
dbw_mkz_can::MsgGearCmd::GCMD
uint8_t GCMD
Definition: dispatch.h:179
dbw_mkz_can::MsgLicense
Definition: dispatch.h:425
pedal_lut.h
dbw_mkz_can::DbwNode::vin_
std::string vin_
Definition: DbwNode.h:221
ROS_WARN
#define ROS_WARN(...)
dbw_mkz_can::MsgVersion::build
uint16_t build
Definition: dispatch.h:513
dbw_mkz_can::MsgMiscReport::btn_ld_left
uint8_t btn_ld_left
Definition: dispatch.h:234
dbw_mkz_can::DbwNode::clear
bool clear()
Definition: DbwNode.h:183
dbw_mkz_can::MsgReportBrakeInfo::trac_enabled
uint8_t trac_enabled
Definition: dispatch.h:376
dbw_mkz_can::MsgThrottleReport::DRIVER
uint8_t DRIVER
Definition: dispatch.h:136
dbw_mkz_can::DbwNode::joint_state_
sensor_msgs::JointState joint_state_
Definition: DbwNode.h:212
dbw_mkz_can::DbwNode::pub_brake_info_
ros::Publisher pub_brake_info_
Definition: DbwNode.h:272
dbw_mkz_can::MsgBrakeReport::TMOUT
uint8_t TMOUT
Definition: dispatch.h:109
dbw_mkz_can::MsgLicense::bdate0
struct dbw_mkz_can::MsgLicense::@1::@7 bdate0
dbw_mkz_can::ModuleVersion
Definition: ModuleVersion.h:83
dbw_mkz_can::MsgReportTirePressure
Definition: dispatch.h:319
dbw_mkz_can::MsgMiscReport::door_hood
uint8_t door_hood
Definition: dispatch.h:225
dbw_mkz_can::MsgReportSurround::l_cta_enabled
uint8_t l_cta_enabled
Definition: dispatch.h:337
dbw_mkz_can::DbwNode::JOINT_SL
@ JOINT_SL
Definition: DbwNode.h:208
dbw_mkz_can::DbwNode::pub_imu_
ros::Publisher pub_imu_
Definition: DbwNode.h:275
dbw_mkz_can::ID_MISC_REPORT
@ ID_MISC_REPORT
Definition: dispatch.h:556
dbw_mkz_can::MsgBrakeReport::FLTWDC
uint8_t FLTWDC
Definition: dispatch.h:105
dbw_mkz_can::MsgBrakeCmd::EN
uint8_t EN
Definition: dispatch.h:114
dbw_mkz_can::ID_REPORT_FUEL_LEVEL
@ ID_REPORT_FUEL_LEVEL
Definition: dispatch.h:565
dataspeed_can_msg_filters::ApproximateTime::processMsg
void processMsg(const Type &msg)
ros::TimerEvent
dbw_mkz_can::MsgMiscReport::FLTBUS
uint8_t FLTBUS
Definition: dispatch.h:220
dbw_mkz_can::MsgMiscReport::outside_air_temp
uint8_t outside_air_temp
Definition: dispatch.h:253
dbw_mkz_can::MsgSteeringReport::TMOUT
uint8_t TMOUT
Definition: dispatch.h:175
dbw_mkz_can::MsgReportThrottleInfo
Definition: dispatch.h:379
dbw_mkz_can::P_FORD_U6
@ P_FORD_U6
Definition: PlatformVersion.h:114
dbw_mkz_can::platformToString
static const char * platformToString(Platform x)
Definition: PlatformVersion.h:103
dbw_mkz_can::PlatformVersion::v
ModuleVersion v
Definition: PlatformVersion.h:145
dbw_mkz_can::MsgReportThrottleInfo::throttle_pc
uint16_t throttle_pc
Definition: dispatch.h:381
dbw_mkz_can::DbwNode::steering_ratio_
double steering_ratio_
Definition: DbwNode.h:243
dbw_mkz_can::ID_REPORT_ACCEL
@ ID_REPORT_ACCEL
Definition: dispatch.h:558
dbw_mkz_can::MsgMiscReport::btn_cc_on
uint8_t btn_cc_on
Definition: dispatch.h:208
dbw_mkz_can::DbwNode::enableSystem
void enableSystem()
Definition: DbwNode.cpp:1328
dbw_mkz_can::MsgReportWheelPosition::front_left
int16_t front_left
Definition: dispatch.h:313
dbw_mkz_can::ModuleVersion::major
uint16_t major() const
Definition: ModuleVersion.h:126
dbw_mkz_can::MsgGearReport::OVERRIDE
uint8_t OVERRIDE
Definition: dispatch.h:188
dbw_mkz_can::MsgMiscReport::btn_call_start
uint8_t btn_call_start
Definition: dispatch.h:251
dbw_mkz_can
Definition: dispatch.h:39
dbw_mkz_can::MsgReportThrottleInfo::aped_qf
uint8_t aped_qf
Definition: dispatch.h:384
dbw_mkz_can::ID_BRAKE_CMD
@ ID_BRAKE_CMD
Definition: dispatch.h:547
dbw_mkz_can::DbwNode::fault
bool fault()
Definition: DbwNode.h:181
dbw_mkz_can::MsgMiscReport::btn_speak
uint8_t btn_speak
Definition: dispatch.h:248
dbw_mkz_can::MsgGearCmd::CLEAR
uint8_t CLEAR
Definition: dispatch.h:183
dbw_mkz_can::MsgMiscReport::door_passenger
uint8_t door_passenger
Definition: dispatch.h:222
dbw_mkz_can::MsgSteeringReport::ENABLED
uint8_t ENABLED
Definition: dispatch.h:168
dbw_mkz_can::MsgBrakeCmd::CMD_TYPE
uint8_t CMD_TYPE
Definition: dispatch.h:113
dbw_mkz_can::MsgVersion
Definition: dispatch.h:508
dbw_mkz_can::MsgReportBrakeInfo::wheel_torque
int16_t wheel_torque
Definition: dispatch.h:368
dbw_mkz_can::LIC_MUX_LDATE1
@ LIC_MUX_LDATE1
Definition: dispatch.h:417
dbw_mkz_can::MsgReportWheelSpeed::rear_left
int16_t rear_left
Definition: dispatch.h:259
dbw_mkz_can::ID_REPORT_GPS3
@ ID_REPORT_GPS3
Definition: dispatch.h:562
dbw_mkz_can::MsgReportDriverAssist::aeb_precharge
uint8_t aeb_precharge
Definition: dispatch.h:399
dbw_mkz_can::MsgReportWheelSpeed::front_right
int16_t front_right
Definition: dispatch.h:258
dbw_mkz_can::MsgReportDriverAssist::fcw_enabled
uint8_t fcw_enabled
Definition: dispatch.h:396
dbw_mkz_can::brakePedalFromTorque
static float brakePedalFromTorque(float torque)
Definition: pedal_lut.h:119
dbw_mkz_can::MsgReportSurround::sonar_07
uint8_t sonar_07
Definition: dispatch.h:351
dbw_mkz_can::ID_STEERING_REPORT
@ ID_STEERING_REPORT
Definition: dispatch.h:552
dbw_mkz_can::sonarBuildPointCloud2
static void sonarBuildPointCloud2(sensor_msgs::PointCloud2 &cloud, const dbw_mkz_msgs::SurroundReport &surround)
Definition: sonar_lut.h:102
dbw_mkz_can::DbwNode::faultWatchdog
void faultWatchdog(bool fault, uint8_t src, bool braking)
Definition: DbwNode.cpp:1540
dbw_mkz_can::P_FORD_P702
@ P_FORD_P702
Definition: PlatformVersion.h:117
dbw_mkz_can::ID_GEAR_CMD
@ ID_GEAR_CMD
Definition: dispatch.h:553
dbw_mkz_can::MsgReportBrakeInfo::abs_enabled
uint8_t abs_enabled
Definition: dispatch.h:372
dbw_mkz_can::PlatformVersion
Definition: PlatformVersion.h:134
dbw_mkz_can::MsgSteeringCmd::QUIET
uint8_t QUIET
Definition: dispatch.h:150
dbw_mkz_can::MsgReportGps1
Definition: dispatch.h:274
dbw_mkz_can::MsgThrottleReport::PI
uint16_t PI
Definition: dispatch.h:129
dbw_mkz_can::MsgMiscReport::btn_vol_inc
uint8_t btn_vol_inc
Definition: dispatch.h:245
dbw_mkz_can::DbwNode::frame_id_
std::string frame_id_
Definition: DbwNode.h:229
dbw_mkz_can::MsgReportBrakeInfo::bped_qf
uint8_t bped_qf
Definition: dispatch.h:369
dbw_mkz_can::MsgReportSurround::l_blis_enabled
uint8_t l_blis_enabled
Definition: dispatch.h:339
dbw_mkz_can::DbwNode::JOINT_RR
@ JOINT_RR
Definition: DbwNode.h:207
dbw_mkz_can::DbwNode::buttons_
bool buttons_
Definition: DbwNode.h:235
dbw_mkz_can::PlatformMap::insert
void insert(Platform p, Module m, ModuleVersion v)
Definition: PlatformMap.h:123
dbw_mkz_can::DbwNode::enable_joint_states_
bool enable_joint_states_
Definition: DbwNode.h:246
dbw_mkz_can::MsgReportThrottleInfo::throttle_rate
int8_t throttle_rate
Definition: dispatch.h:385
dbw_mkz_can::MsgReportSurround::sonar_03
uint8_t sonar_03
Definition: dispatch.h:347
dbw_mkz_can::MsgReportSurround::sonar_fault
uint8_t sonar_fault
Definition: dispatch.h:358
dbw_mkz_can::MsgMiscReport::door_rear_left
uint8_t door_rear_left
Definition: dispatch.h:223
dbw_mkz_can::DbwNode::overrideSteering
void overrideSteering(bool override, bool timeout)
Definition: DbwNode.cpp:1414
dbw_mkz_can::MsgReportTirePressure::rear_left
uint16_t rear_left
Definition: dispatch.h:322
dbw_mkz_can::DbwNode::warn_cmds_
bool warn_cmds_
Definition: DbwNode.h:232
ros::Time
dbw_mkz_can::DbwNode::pub_misc_1_
ros::Publisher pub_misc_1_
Definition: DbwNode.h:265
dbw_mkz_can::MsgMiscReport::head_light_hi
uint8_t head_light_hi
Definition: dispatch.h:205
dbw_mkz_can::DbwNode::timeout_throttle_
bool timeout_throttle_
Definition: DbwNode.h:175
dbw_mkz_can::MsgReportFuelLevel::fuel_level
int16_t fuel_level
Definition: dispatch.h:327
dbw_mkz_can::DbwNode::sub_steering_
ros::Subscriber sub_steering_
Definition: DbwNode.h:254
dbw_mkz_can::MsgBrakeReport
Definition: dispatch.h:94
dbw_mkz_can::MsgSteeringReport::FLTPWR
uint8_t FLTPWR
Definition: dispatch.h:170
dbw_mkz_can::MsgSteeringReport::FLTBUS1
uint8_t FLTBUS1
Definition: dispatch.h:172
dbw_mkz_can::MsgReportAccel
Definition: dispatch.h:263
dbw_mkz_can::MsgLicense::module
uint8_t module
Definition: dispatch.h:431
dbw_mkz_can::MsgReportDriverAssist::decel_src
uint8_t decel_src
Definition: dispatch.h:394
dbw_mkz_can::M_SHIFT
@ M_SHIFT
Definition: PlatformVersion.h:97
dbw_mkz_can::DbwNode::override_gear_
bool override_gear_
Definition: DbwNode.h:166
dbw_mkz_can::MsgGearReport::REJECT
uint8_t REJECT
Definition: dispatch.h:191
DbwNode.h
dbw_mkz_can::MsgThrottleReport::FLT1
uint8_t FLT1
Definition: dispatch.h:138
dbw_mkz_can::MsgReportDriverAssist::acc_braking
uint8_t acc_braking
Definition: dispatch.h:403
dbw_mkz_can::P_FORD_C1
@ P_FORD_C1
Definition: PlatformVersion.h:112
dbw_mkz_can::ID_REPORT_GPS1
@ ID_REPORT_GPS1
Definition: dispatch.h:560
dbw_mkz_can::MsgMiscReport::btn_cc_res
uint8_t btn_cc_res
Definition: dispatch.h:210
dbw_mkz_can::MsgBrakeCmd
Definition: dispatch.h:76
dbw_mkz_can::MsgMiscReport::light_ambient
uint8_t light_ambient
Definition: dispatch.h:207
dbw_mkz_can::ID_REPORT_SURROUND
@ ID_REPORT_SURROUND
Definition: dispatch.h:566
dbw_mkz_can::MsgSteeringReport::TMODE
uint8_t TMODE
Definition: dispatch.h:165
dbw_mkz_can::M_TPEC
@ M_TPEC
Definition: PlatformVersion.h:95
dbw_mkz_can::MsgReportDriverAssist::aeb_braking
uint8_t aeb_braking
Definition: dispatch.h:400
dbw_mkz_can::MsgMiscReport::btn_la_on_off
uint8_t btn_la_on_off
Definition: dispatch.h:219
dbw_mkz_can::MsgSteeringCmd::SVEL
uint8_t SVEL
Definition: dispatch.h:154
dbw_mkz_can::MsgGearCmd
Definition: dispatch.h:178
dbw_mkz_can::MsgReportSurround::sonar_02
uint8_t sonar_02
Definition: dispatch.h:346
dbw_mkz_can::DbwNode::timeout_steering_
bool timeout_steering_
Definition: DbwNode.h:176
dbw_mkz_can::MsgThrottleReport::OVERRIDE
uint8_t OVERRIDE
Definition: dispatch.h:135
dbw_mkz_can::DbwNode::enabled_throttle_
bool enabled_throttle_
Definition: DbwNode.h:178
dbw_mkz_can::MsgReportGps3::speed
uint8_t speed
Definition: dispatch.h:305
dbw_mkz_can::MsgReportTirePressure::rear_right
uint16_t rear_right
Definition: dispatch.h:323
dbw_mkz_can::MsgMiscReport::btn_ld_ok
uint8_t btn_ld_ok
Definition: dispatch.h:231
dbw_mkz_can::DbwNode::pub_throttle_info_
ros::Publisher pub_throttle_info_
Definition: DbwNode.h:273
dbw_mkz_can::MsgReportTirePressure::front_right
uint16_t front_right
Definition: dispatch.h:321
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
dbw_mkz_can::ID_REPORT_TIRE_PRESSURE
@ ID_REPORT_TIRE_PRESSURE
Definition: dispatch.h:564
dbw_mkz_can::DbwNode::sub_turn_signal_
ros::Subscriber sub_turn_signal_
Definition: DbwNode.h:256
dbw_mkz_can::DbwNode::sync_imu_
dataspeed_can_msg_filters::ApproximateTime sync_imu_
Definition: DbwNode.h:285
dbw_mkz_can::DbwNode::JOINT_RL
@ JOINT_RL
Definition: DbwNode.h:206
dbw_mkz_can::MsgReportTirePressure::front_left
uint16_t front_left
Definition: dispatch.h:320
dbw_mkz_can::MsgBrakeReport::BTYPE
uint8_t BTYPE
Definition: dispatch.h:98
dbw_mkz_can::MsgReportBrakeInfo::brake_torque_actual
uint16_t brake_torque_actual
Definition: dispatch.h:365
dbw_mkz_can::DbwNode::pub_sys_enable_
ros::Publisher pub_sys_enable_
Definition: DbwNode.h:282
dbw_mkz_can::MsgThrottleReport::PC
uint16_t PC
Definition: dispatch.h:130
dbw_mkz_can::MsgReportAccel::accel_vert
int16_t accel_vert
Definition: dispatch.h:266
dbw_mkz_can::MsgVersion::module
uint8_t module
Definition: dispatch.h:509
dbw_mkz_can::LIC_MUX_VIN1
@ LIC_MUX_VIN1
Definition: dispatch.h:422
dbw_mkz_can::MsgMiscReport::btn_cc_gap_dec
uint8_t btn_cc_gap_dec
Definition: dispatch.h:218
dbw_mkz_can::DbwNode::timeoutSteering
void timeoutSteering(bool timeout, bool enabled)
Definition: DbwNode.cpp:1467
dbw_mkz_can::MsgMiscReport
Definition: dispatch.h:203
dbw_mkz_can::MsgLicense::ldate0
uint8_t ldate0
Definition: dispatch.h:442
dbw_mkz_can::MsgGearReport::CMD
uint8_t CMD
Definition: dispatch.h:189
dbw_mkz_can::DbwNode::override_brake_
bool override_brake_
Definition: DbwNode.h:163
dbw_mkz_can::MsgReportGyro
Definition: dispatch.h:269
dbw_mkz_can::DbwNode::pub_gps_time_
ros::Publisher pub_gps_time_
Definition: DbwNode.h:278
dbw_mkz_can::P_FORD_CD5
@ P_FORD_CD5
Definition: PlatformVersion.h:115
dbw_mkz_can::MsgThrottleReport::FLTPWR
uint8_t FLTPWR
Definition: dispatch.h:140
dbw_mkz_can::MsgReportSurround::r_cta_enabled
uint8_t r_cta_enabled
Definition: dispatch.h:341
cmd
string cmd
dbw_mkz_can::MsgBrakeReport::PC
uint16_t PC
Definition: dispatch.h:96
dbw_mkz_can::MsgMiscReport::btn_cc_set_inc
uint8_t btn_cc_set_inc
Definition: dispatch.h:215
header
const std::string header
dbw_mkz_can::M_BOO
@ M_BOO
Definition: PlatformVersion.h:99
ROS_INFO
#define ROS_INFO(...)
dbw_mkz_can::MsgBrakeCmd::COUNT
uint8_t COUNT
Definition: dispatch.h:123
dbw_mkz_can::MsgReportWheelSpeed
Definition: dispatch.h:256
ROS_ASSERT
#define ROS_ASSERT(cond)
dbw_mkz_can::ID_REPORT_GYRO
@ ID_REPORT_GYRO
Definition: dispatch.h:559
dbw_mkz_can::DbwNode::pub_wheel_positions_
ros::Publisher pub_wheel_positions_
Definition: DbwNode.h:267
dbw_mkz_can::DbwNode::overrideBrake
void overrideBrake(bool override, bool timeout)
Definition: DbwNode.cpp:1376
dbw_mkz_can::LIC_MUX_BDATE0
@ LIC_MUX_BDATE0
Definition: dispatch.h:419
dbw_mkz_can::MsgMiscReport::btn_cc_res_cncl
uint8_t btn_cc_res_cncl
Definition: dispatch.h:214
dbw_mkz_can::MsgGearReport::FLTBUS
uint8_t FLTBUS
Definition: dispatch.h:190
dbw_mkz_can::MsgReportWheelPosition
Definition: dispatch.h:312
dbw_mkz_can::DbwNode::JOINT_FL
@ JOINT_FL
Definition: DbwNode.h:204
dbw_mkz_can::MsgMiscReport::btn_rd_up
uint8_t btn_rd_up
Definition: dispatch.h:240
dbw_mkz_can::DbwNode::pub_joint_states_
ros::Publisher pub_joint_states_
Definition: DbwNode.h:279
dbw_mkz_can::P_FORD_CD4
@ P_FORD_CD4
Definition: PlatformVersion.h:110
dbw_mkz_can::DbwNode::pub_twist_
ros::Publisher pub_twist_
Definition: DbwNode.h:280
ros::Duration
dbw_mkz_can::MsgMiscReport::btn_rd_right
uint8_t btn_rd_right
Definition: dispatch.h:243
dbw_mkz_can::MsgMiscReport::btn_cc_set_dec
uint8_t btn_cc_set_dec
Definition: dispatch.h:216
dbw_mkz_can::DbwNode::recvThrottleCmd
void recvThrottleCmd(const dbw_mkz_msgs::ThrottleCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1142
dbw_mkz_can::MsgBrakeReport::PO
uint16_t PO
Definition: dispatch.h:97
dbw_mkz_can::ModuleVersion::valid
bool valid() const
Definition: ModuleVersion.h:125
dbw_mkz_can::LIC_MUX_F7
@ LIC_MUX_F7
Definition: dispatch.h:415
dbw_mkz_can::ModuleVersion::build
uint16_t build() const
Definition: ModuleVersion.h:128
dbw_mkz_can::DbwNode::pub_tire_pressure_
ros::Publisher pub_tire_pressure_
Definition: DbwNode.h:268
dbw_mkz_can::MsgSteeringReport::ANGLE
int16_t ANGLE
Definition: dispatch.h:163
dbw_mkz_can::MsgReportThrottleInfo::gear_num
uint8_t gear_num
Definition: dispatch.h:386
dbw_mkz_can::MsgReportGps3::heading
uint16_t heading
Definition: dispatch.h:304
dbw_mkz_can::DbwNode::sub_throttle_
ros::Subscriber sub_throttle_
Definition: DbwNode.h:253
brake_sweep.node
node
Definition: brake_sweep.py:159
dbw_mkz_can::FIRMWARE_CMDTYPE
PlatformMap FIRMWARE_CMDTYPE({ {PlatformVersion(P_FORD_CD4, M_BPEC, ModuleVersion(2, 0, 7))}, {PlatformVersion(P_FORD_CD4, M_TPEC, ModuleVersion(2, 0, 7))}, })
dbw_mkz_can::LIC_MUX_MAC
@ LIC_MUX_MAC
Definition: dispatch.h:418
dbw_mkz_can::MsgBrakeCmd::ABOO
uint8_t ABOO
Definition: dispatch.h:111
dbw_mkz_can::MsgMiscReport::pasngr_airbag
uint8_t pasngr_airbag
Definition: dispatch.h:228
ros::NodeHandle
dbw_mkz_can::LIC_MUX_LDATE0
@ LIC_MUX_LDATE0
Definition: dispatch.h:416
dbw_mkz_can::DbwNode::~DbwNode
~DbwNode()
Definition: DbwNode.cpp:230
dbw_mkz_can::DbwNode::fault_steering_cal_
bool fault_steering_cal_
Definition: DbwNode.h:170
dbw_mkz_can::MsgVersion::platform
uint8_t platform
Definition: dispatch.h:510
dbw_mkz_can::DbwNode::fault_watchdog_using_brakes_
bool fault_watchdog_using_brakes_
Definition: DbwNode.h:172
dbw_mkz_can::MsgReportBrakeInfo::brake_torque_request
uint16_t brake_torque_request
Definition: dispatch.h:362
dbw_mkz_can::MsgMiscReport::door_driver
uint8_t door_driver
Definition: dispatch.h:221
dbw_mkz_can::MsgBrakeCmd::CLEAR
uint8_t CLEAR
Definition: dispatch.h:115
dbw_mkz_can::DbwNode::faultSteering
void faultSteering(bool fault)
Definition: DbwNode.cpp:1508
ROS_INFO_THROTTLE
#define ROS_INFO_THROTTLE(period,...)
dbw_mkz_can::MsgThrottleCmd::COUNT
uint8_t COUNT
Definition: dispatch.h:125
dbw_mkz_can::MsgMiscReport::btn_rd_left
uint8_t btn_rd_left
Definition: dispatch.h:242
dbw_mkz_can::ID_REPORT_WHEEL_POSITION
@ ID_REPORT_WHEEL_POSITION
Definition: dispatch.h:563
dbw_mkz_can::MsgReportSurround::r_blis_alert
uint8_t r_blis_alert
Definition: dispatch.h:342


dbw_mkz_can
Author(s): Kevin Hallenbeck
autogenerated on Thu Jan 4 2024 03:46:24