DbwNode.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018-2019 New Eagle
5  * Copyright (c) 2015-2018, Dataspeed Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Dataspeed Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #include "DbwNode.h"
38 
39 namespace dbw_pacifica_can
40 {
41 
43 {
44  priv_nh.getParam("dbw_dbc_file", dbcFile_);
45 
46  // Initialize enable state machine
47  prev_enable_ = true;
48  enable_ = false;
49  override_brake_ = false;
51  override_steering_ = false;
52  override_gear_ = false;
53  fault_brakes_ = false;
55  fault_steering_ = false;
56  fault_steering_cal_ = false;
57  fault_watchdog_ = false;
59  fault_watchdog_warned_ = false;
60  timeout_brakes_ = false;
62  timeout_steering_ = false;
63  enabled_brakes_ = false;
65  enabled_steering_ = false;
66  gear_warned_ = false;
67 
68  // Frame ID
69  frame_id_ = "base_footprint";
70  priv_nh.getParam("frame_id", frame_id_);
71 
72  // Buttons (enable/disable)
73  buttons_ = true;
74  priv_nh.getParam("buttons", buttons_);
75 
76 
77  // Ackermann steering parameters
78  acker_wheelbase_ = 2.8498; // 112.2 inches
79  acker_track_ = 1.5824; // 62.3 inches
80  steering_ratio_ = 14.8;
81  priv_nh.getParam("ackermann_wheelbase", acker_wheelbase_);
82  priv_nh.getParam("ackermann_track", acker_track_);
83  priv_nh.getParam("steering_ratio", steering_ratio_);
84 
85  // Initialize joint states
86  joint_state_.position.resize(JOINT_COUNT);
87  joint_state_.velocity.resize(JOINT_COUNT);
88  joint_state_.effort.resize(JOINT_COUNT);
89  joint_state_.name.resize(JOINT_COUNT);
90  joint_state_.name[JOINT_FL] = "wheel_fl"; // Front Left
91  joint_state_.name[JOINT_FR] = "wheel_fr"; // Front Right
92  joint_state_.name[JOINT_RL] = "wheel_rl"; // Rear Left
93  joint_state_.name[JOINT_RR] = "wheel_rr"; // Rear Right
94  joint_state_.name[JOINT_SL] = "steer_fl";
95  joint_state_.name[JOINT_SR] = "steer_fr";
96 
97  // Set up Publishers
98  pub_can_ = node.advertise<can_msgs::Frame>("can_tx", 10);
99  pub_brake_ = node.advertise<dbw_pacifica_msgs::BrakeReport>("brake_report", 2);
100  pub_accel_pedal_ = node.advertise<dbw_pacifica_msgs::AcceleratorPedalReport>("accelerator_pedal_report", 2);
101  pub_steering_ = node.advertise<dbw_pacifica_msgs::SteeringReport>("steering_report", 2);
102  pub_gear_ = node.advertise<dbw_pacifica_msgs::GearReport>("gear_report", 2);
103  pub_wheel_speeds_ = node.advertise<dbw_pacifica_msgs::WheelSpeedReport>("wheel_speed_report", 2);
104  pub_wheel_positions_ = node.advertise<dbw_pacifica_msgs::WheelPositionReport>("wheel_position_report", 2);
105  pub_tire_pressure_ = node.advertise<dbw_pacifica_msgs::TirePressureReport>("tire_pressure_report", 2);
106  pub_surround_ = node.advertise<dbw_pacifica_msgs::SurroundReport>("surround_report", 2);
107 
108  pub_low_voltage_system_ = node.advertise<dbw_pacifica_msgs::LowVoltageSystemReport>("low_voltage_system_report", 2);
109 
110  pub_brake_2_report_ = node.advertise<dbw_pacifica_msgs::Brake2Report>("brake_2_report", 2);
111  pub_steering_2_report_ = node.advertise<dbw_pacifica_msgs::Steering2Report>("steering_2_report", 2);
112  pub_fault_actions_report_ = node.advertise<dbw_pacifica_msgs::FaultActionsReport>("fault_actions_report", 2);
113  pub_hmi_global_enable_report_ = node.advertise<dbw_pacifica_msgs::HmiGlobalEnableReport>("hmi_global_enable_report", 2);
114 
115  pub_imu_ = node.advertise<sensor_msgs::Imu>("imu/data_raw", 10);
116  pub_joint_states_ = node.advertise<sensor_msgs::JointState>("joint_states", 10);
117  pub_twist_ = node.advertise<geometry_msgs::TwistStamped>("twist", 10);
118  pub_vin_ = node.advertise<std_msgs::String>("vin", 1, true);
119  pub_driver_input_ = node.advertise<dbw_pacifica_msgs::DriverInputReport>("driver_input_report", 2);
120  pub_misc_ = node.advertise<dbw_pacifica_msgs::MiscReport>("misc_report", 2);
121  pub_sys_enable_ = node.advertise<std_msgs::Bool>("dbw_enabled", 1, true);
123 
124  // Set up Subscribers
125  sub_enable_ = node.subscribe("enable", 10, &DbwNode::recvEnable, this, ros::TransportHints().tcpNoDelay(true));
126  sub_disable_ = node.subscribe("disable", 10, &DbwNode::recvDisable, this, ros::TransportHints().tcpNoDelay(true));
127  sub_can_ = node.subscribe("can_rx", 100, &DbwNode::recvCAN, this, ros::TransportHints().tcpNoDelay(true));
128  sub_brake_ = node.subscribe("brake_cmd", 1, &DbwNode::recvBrakeCmd, this, ros::TransportHints().tcpNoDelay(true));
129  sub_accelerator_pedal_ = node.subscribe("accelerator_pedal_cmd", 1, &DbwNode::recvAcceleratorPedalCmd, this, ros::TransportHints().tcpNoDelay(true));
130  sub_steering_ = node.subscribe("steering_cmd", 1, &DbwNode::recvSteeringCmd, this, ros::TransportHints().tcpNoDelay(true));
131  sub_gear_ = node.subscribe("gear_cmd", 1, &DbwNode::recvGearCmd, this, ros::TransportHints().tcpNoDelay(true));
132  sub_misc_ = node.subscribe("misc_cmd", 1, &DbwNode::recvMiscCmd, this, ros::TransportHints().tcpNoDelay(true));
133  sub_global_enable_ = node.subscribe("global_enable_cmd", 1, &DbwNode::recvGlobalEnableCmd, this, ros::TransportHints().tcpNoDelay(true));
134 
135  pdu1_relay_pub_ = node.advertise<pdu_msgs::RelayCommand>("/pduB/relay_cmd", 1000);
136  count_ = 0;
137 
139 
140  // Set up Timer
141  timer_ = node.createTimer(ros::Duration(1 / 20.0), &DbwNode::timerCallback, this);
142 }
143 
145 {
146 }
147 
148 void DbwNode::recvEnable(const std_msgs::Empty::ConstPtr& msg)
149 {
150  enableSystem();
151 }
152 
153 void DbwNode::recvDisable(const std_msgs::Empty::ConstPtr& msg)
154 {
155  disableSystem();
156 }
157 
158 void DbwNode::recvCAN(const can_msgs::Frame::ConstPtr& msg)
159 {
160 
161  if (!msg->is_rtr && !msg->is_error) {
162  switch (msg->id) {
163  case ID_BRAKE_REPORT:
164  {
166 
167  if (msg->dlc >= message->GetDlc()) {
168  message->SetFrame(msg);
169 
170  bool faultCh1 = message->GetSignal("DBW_BrakeFault_Ch1")->GetResult() ? true : false;
171  bool faultCh2 = message->GetSignal("DBW_BrakeFault_Ch2")->GetResult() ? true : false;
172  bool brakeSystemFault = message->GetSignal("DBW_BrakeFault")->GetResult() ? true : false;
173  bool dbwSystemFault = brakeSystemFault;
174 
175  faultBrakes(faultCh1 && faultCh2);
176  faultWatchdog(dbwSystemFault, brakeSystemFault);
177 
178  overrideBrake(message->GetSignal("DBW_BrakeDriverActivity")->GetResult());
179  dbw_pacifica_msgs::BrakeReport brakeReport;
180  brakeReport.header.stamp = msg->header.stamp;
181  brakeReport.pedal_position = message->GetSignal("DBW_BrakePdlDriverInput")->GetResult();
182  brakeReport.pedal_output = message->GetSignal("DBW_BrakePdlPosnFdbck")->GetResult();
183 
184  brakeReport.enabled = message->GetSignal("DBW_BrakeEnabled")->GetResult() ? true : false;
185  brakeReport.driver_activity = message->GetSignal("DBW_BrakeDriverActivity")->GetResult() ? true : false;
186 
187  brakeReport.fault_brake_system = brakeSystemFault;
188 
189  brakeReport.fault_ch2 = faultCh2;
190 
191  brakeReport.rolling_counter = message->GetSignal("DBW_BrakeRollingCntr")->GetResult();
192 
193  brakeReport.brake_torque_actual = message->GetSignal("DBW_BrakePcntTorqueActual")->GetResult();
194 
195  brakeReport.intervention_active = message->GetSignal("DBW_BrakeInterventionActv")->GetResult() ? true : false;
196  brakeReport.intervention_ready = message->GetSignal("DBW_BrakeInterventionReady")->GetResult() ? true : false;
197 
198  brakeReport.parking_brake.status = message->GetSignal("DBW_BrakeParkingBrkStatus")->GetResult();
199 
200  brakeReport.control_type.value = message->GetSignal("DBW_BrakeCtrlType")->GetResult();
201 
202  pub_brake_.publish(brakeReport);
203  if (faultCh1 || faultCh2) {
204  ROS_WARN_THROTTLE(5.0, "Brake fault. FLT1: %s FLT2: %s",
205  faultCh1 ? "true, " : "false,",
206  faultCh2 ? "true, " : "false,");
207  }
208  }
209  }
210  break;
211 
213  {
215  if (msg->dlc >= message->GetDlc()) {
216 
217  message->SetFrame(msg);
218 
219  bool faultCh1 = message->GetSignal("DBW_AccelPdlFault_Ch1")->GetResult() ? true : false;
220  bool faultCh2 = message->GetSignal("DBW_AccelPdlFault_Ch2")->GetResult() ? true : false;
221  bool accelPdlSystemFault = message->GetSignal("DBW_AccelPdlFault")->GetResult() ? true : false;
222  bool dbwSystemFault = accelPdlSystemFault;
223 
224  uint16_t positionFeedback = message->GetSignal("DBW_AccelPdlPosnFdbck")->GetResult();
225 
226  faultAcceleratorPedal(faultCh1 && faultCh2);
227  faultWatchdog(dbwSystemFault, accelPdlSystemFault);
228 
229  overrideAcceleratorPedal(message->GetSignal("DBW_AccelPdlDriverActivity")->GetResult());
230 
231  dbw_pacifica_msgs::AcceleratorPedalReport accelPedalReprt;
232  accelPedalReprt.header.stamp = msg->header.stamp;
233  accelPedalReprt.pedal_input = message->GetSignal("DBW_AccelPdlDriverInput")->GetResult();
234  accelPedalReprt.pedal_output = message->GetSignal("DBW_AccelPdlPosnFdbck")->GetResult();
235  accelPedalReprt.enabled = message->GetSignal("DBW_AccelPdlEnabled")->GetResult() ? true : false;
236  accelPedalReprt.ignore_driver = message->GetSignal("DBW_AccelPdlIgnoreDriver")->GetResult() ? true : false;
237  accelPedalReprt.driver_activity = message->GetSignal("DBW_AccelPdlDriverActivity")->GetResult() ? true : false;
238  accelPedalReprt.torque_actual = message->GetSignal("DBW_AccelPcntTorqueActual")->GetResult();
239 
240  accelPedalReprt.control_type.value = message->GetSignal("DBW_AccelCtrlType")->GetResult();
241 
242  accelPedalReprt.rolling_counter = message->GetSignal("DBW_AccelPdlRollingCntr")->GetResult();
243 
244  accelPedalReprt.fault_accel_pedal_system = accelPdlSystemFault;
245 
246  accelPedalReprt.fault_ch1 = faultCh1;
247  accelPedalReprt.fault_ch2 = faultCh2;
248 
249  pub_accel_pedal_.publish(accelPedalReprt);
250 
251  if (faultCh1 || faultCh2) {
252  ROS_WARN_THROTTLE(5.0, "Accelerator Pedal fault. FLT1: %s FLT2: %s",
253  faultCh1 ? "true, " : "false,",
254  faultCh2 ? "true, " : "false,");
255  }
256  }
257  }
258  break;
259 
260  case ID_STEERING_REPORT:
261  {
263  if (msg->dlc >= message->GetDlc()) {
264 
265  message->SetFrame(msg);
266 
267  bool steeringSystemFault = message->GetSignal("DBW_SteeringFault")->GetResult() ? true : false;
268  bool dbwSystemFault = steeringSystemFault;
269 
270  faultSteering(steeringSystemFault);
271 
272  faultWatchdog(dbwSystemFault);
273  overrideSteering(message->GetSignal("DBW_SteeringDriverActivity")->GetResult() ? true : false);
274 
275  dbw_pacifica_msgs::SteeringReport steeringReport;
276  steeringReport.header.stamp = msg->header.stamp;
277  steeringReport.steering_wheel_angle = message->GetSignal("DBW_SteeringWhlAngleAct")->GetResult() * (M_PI / 180);
278  steeringReport.steering_wheel_angle_cmd = message->GetSignal("DBW_SteeringWhlAngleDes")->GetResult() * (M_PI / 180);
279  steeringReport.steering_wheel_torque = message->GetSignal("DBW_SteeringWhlPcntTrqCmd")->GetResult() * 0.0625;
280 
281  steeringReport.enabled = message->GetSignal("DBW_SteeringEnabled")->GetResult() ? true : false;
282  steeringReport.driver_activity = message->GetSignal("DBW_SteeringDriverActivity")->GetResult() ? true : false;
283 
284  steeringReport.rolling_counter = message->GetSignal("DBW_SteeringRollingCntr")->GetResult();
285 
286  steeringReport.control_type.value = message->GetSignal("DBW_SteeringCtrlType")->GetResult();
287 
288  steeringReport.overheat_prevention_mode = message->GetSignal("DBW_OverheatPreventMode")->GetResult() ? true : false;
289 
290  steeringReport.steering_overheat_warning = message->GetSignal("DBW_SteeringOverheatWarning")->GetResult() ? true : false;
291 
292  steeringReport.fault_steering_system = steeringSystemFault;
293 
294  pub_steering_.publish(steeringReport);
295 
296  publishJointStates(msg->header.stamp, NULL, &steeringReport);
297 
298  if (steeringSystemFault) {
299  ROS_WARN_THROTTLE(5.0, "Steering fault: %s",
300  steeringSystemFault ? "true, " : "false,");
301  }
302  }
303  }
304  break;
305 
306  case ID_GEAR_REPORT:
307  {
309 
310  if (msg->dlc >= 1) {
311 
312  message->SetFrame(msg);
313 
314  bool driverActivity = message->GetSignal("DBW_PrndDriverActivity")->GetResult() ? true : false;
315 
316  overrideGear(driverActivity);
317  dbw_pacifica_msgs::GearReport out;
318  out.header.stamp = msg->header.stamp;
319 
320  out.enabled = message->GetSignal("DBW_PrndCtrlEnabled")->GetResult() ? true : false;
321  out.state.gear = message->GetSignal("DBW_PrndStateActual")->GetResult();
322  out.driver_activity = driverActivity;
323  out.gear_select_system_fault = message->GetSignal("DBW_PrndFault")->GetResult() ? true : false;
324 
325  out.reject = message->GetSignal("DBW_PrndStateReject")->GetResult() ? true : false;
326 
327  pub_gear_.publish(out);
328  }
329  }
330  break;
331 
333  {
335 
336  if (msg->dlc >= message->GetDlc()) {
337  message->SetFrame(msg);
338 
339  dbw_pacifica_msgs::WheelSpeedReport out;
340  out.header.stamp = msg->header.stamp;
341 
342  out.front_left = message->GetSignal("DBW_WhlSpd_FL")->GetResult();
343  out.front_right = message->GetSignal("DBW_WhlSpd_FR")->GetResult();
344  out.rear_left = message->GetSignal("DBW_WhlSpd_RL")->GetResult();
345  out.rear_right = message->GetSignal("DBW_WhlSpd_RR")->GetResult();
346 
348  publishJointStates(msg->header.stamp, &out, NULL);
349  }
350  }
351  break;
352 
354  {
356  if (msg->dlc >= message->GetDlc()) {
357 
358  message->SetFrame(msg);
359 
360  dbw_pacifica_msgs::WheelPositionReport out;
361  out.header.stamp = msg->header.stamp;
362  out.front_left = message->GetSignal("DBW_WhlPulseCnt_FL")->GetResult();
363  out.front_right = message->GetSignal("DBW_WhlPulseCnt_FR")->GetResult();
364  out.rear_left = message->GetSignal("DBW_WhlPulseCnt_RL")->GetResult();
365  out.rear_right = message->GetSignal("DBW_WhlPulseCnt_RR")->GetResult();
366  out.wheel_pulses_per_rev = message->GetSignal("DBW_WhlPulsesPerRev")->GetResult();
367 
369  }
370  }
371  break;
372 
374  {
376 
377  if (msg->dlc >= message->GetDlc()) {
378 
379  message->SetFrame(msg);
380 
381  dbw_pacifica_msgs::TirePressureReport out;
382  out.header.stamp = msg->header.stamp;
383  out.front_left = message->GetSignal("DBW_TirePressFL")->GetResult();
384  out.front_right = message->GetSignal("DBW_TirePressFR")->GetResult();
385  out.rear_left = message->GetSignal("DBW_TirePressRL")->GetResult();
386  out.rear_right = message->GetSignal("DBW_TirePressRR")->GetResult();
388  }
389  }
390  break;
391 
392  case ID_REPORT_SURROUND:
393  {
395 
396  if (msg->dlc >= message->GetDlc()) {
397 
398  message->SetFrame(msg);
399 
400  dbw_pacifica_msgs::SurroundReport out;
401  out.header.stamp = msg->header.stamp;
402 
403  out.front_radar_object_distance = message->GetSignal("DBW_Reserved2")->GetResult();
404  out.rear_radar_object_distance = message->GetSignal("DBW_SonarRearDist")->GetResult();
405 
406  out.front_radar_distance_valid = message->GetSignal("DBW_Reserved3")->GetResult() ? true : false;
407  out.parking_sonar_data_valid = message->GetSignal("DBW_SonarVld")->GetResult() ? true : false;
408 
409  out.rear_right.status = message->GetSignal("DBW_SonarArcNumRR")->GetResult();
410  out.rear_left.status = message->GetSignal("DBW_SonarArcNumRL")->GetResult();
411  out.rear_center.status = message->GetSignal("DBW_SonarArcNumRC")->GetResult();
412 
413  out.front_right.status = message->GetSignal("DBW_SonarArcNumFR")->GetResult();
414  out.front_left.status = message->GetSignal("DBW_SonarArcNumFL")->GetResult();
415  out.front_center.status = message->GetSignal("DBW_SonarArcNumFC")->GetResult();
416 
417  pub_surround_.publish(out);
418  }
419  }
420  break;
421 
422  case ID_VIN:
423  {
425 
426  if (msg->dlc >= message->GetDlc()) {
427 
428  message->SetFrame(msg);
429 
430  if (message->GetSignal("DBW_VinMultiplexor")->GetResult() == VIN_MUX_VIN0) {
431  vin_.push_back(message->GetSignal("DBW_VinDigit_01")->GetResult());
432  vin_.push_back(message->GetSignal("DBW_VinDigit_02")->GetResult());
433  vin_.push_back(message->GetSignal("DBW_VinDigit_03")->GetResult());
434  vin_.push_back(message->GetSignal("DBW_VinDigit_04")->GetResult());
435  vin_.push_back(message->GetSignal("DBW_VinDigit_05")->GetResult());
436  vin_.push_back(message->GetSignal("DBW_VinDigit_06")->GetResult());
437  vin_.push_back(message->GetSignal("DBW_VinDigit_07")->GetResult());
438  } else if (message->GetSignal("DBW_VinMultiplexor")->GetResult() == VIN_MUX_VIN1) {
439  vin_.push_back(message->GetSignal("DBW_VinDigit_08")->GetResult());
440  vin_.push_back(message->GetSignal("DBW_VinDigit_09")->GetResult());
441  vin_.push_back(message->GetSignal("DBW_VinDigit_10")->GetResult());
442  vin_.push_back(message->GetSignal("DBW_VinDigit_11")->GetResult());
443  vin_.push_back(message->GetSignal("DBW_VinDigit_12")->GetResult());
444  vin_.push_back(message->GetSignal("DBW_VinDigit_13")->GetResult());
445  vin_.push_back(message->GetSignal("DBW_VinDigit_14")->GetResult());
446  } else if (message->GetSignal("DBW_VinMultiplexor")->GetResult() == VIN_MUX_VIN2) {
447  vin_.push_back(message->GetSignal("DBW_VinDigit_15")->GetResult());
448  vin_.push_back(message->GetSignal("DBW_VinDigit_16")->GetResult());
449  vin_.push_back(message->GetSignal("DBW_VinDigit_17")->GetResult());
450  std_msgs::String msg; msg.data = vin_;
451  pub_vin_.publish(msg);
452  //ROS_INFO("Detected VIN: %s", vin_.c_str());
453  }
454  }
455  }
456  break;
457 
458  case ID_REPORT_IMU:
459  {
461 
462  if (msg->dlc >= message->GetDlc()) {
463 
464  message->SetFrame(msg);
465 
466  sensor_msgs::Imu out;
467  out.header.stamp = msg->header.stamp;
468  out.header.frame_id = frame_id_;
469 
470  out.angular_velocity.z = (double)message->GetSignal("DBW_ImuYawRate")->GetResult() * (M_PI / 180.0);
471 
472  out.linear_acceleration.x = (double)message->GetSignal("DBW_ImuAccelX")->GetResult();
473  out.linear_acceleration.y = (double)message->GetSignal("DBW_ImuAccelY")->GetResult();
474 
475  pub_imu_.publish(out);
476  }
477  }
478  break;
479 
481  {
483 
484  if (msg->dlc >= message->GetDlc()) {
485 
486  message->SetFrame(msg);
487 
488  dbw_pacifica_msgs::DriverInputReport out;
489  out.header.stamp = msg->header.stamp;
490 
491  out.turn_signal.value = message->GetSignal("DBW_DrvInptTurnSignal")->GetResult();
492  out.high_beam_headlights.status = message->GetSignal("DBW_DrvInptHiBeam")->GetResult();
493  out.wiper.status = message->GetSignal("DBW_DrvInptWiper")->GetResult();
494 
495  out.cruise_resume_button = message->GetSignal("DBW_DrvInptCruiseResumeBtn")->GetResult() ? true : false;
496  out.cruise_cancel_button = message->GetSignal("DBW_DrvInptCruiseCancelBtn")->GetResult() ? true : false;
497  out.cruise_accel_button = message->GetSignal("DBW_DrvInptCruiseAccelBtn")->GetResult() ? true : false;
498  out.cruise_decel_button = message->GetSignal("DBW_DrvInptCruiseDecelBtn")->GetResult() ? true : false;
499  out.cruise_on_off_button = message->GetSignal("DBW_DrvInptCruiseOnOffBtn")->GetResult() ? true : false;
500 
501  out.adaptive_cruise_on_off_button = message->GetSignal("DBW_DrvInptAccOnOffBtn")->GetResult() ? true : false;
502  out.adaptive_cruise_increase_distance_button = message->GetSignal("DBW_DrvInptAccIncDistBtn")->GetResult() ? true : false;
503  out.adaptive_cruise_decrease_distance_button = message->GetSignal("DBW_DrvInptAccDecDistBtn")->GetResult() ? true : false;
504 
505  out.door_or_hood_ajar = message->GetSignal("DBW_OccupAnyDoorOrHoodAjar")->GetResult() ? true : false;
506 
507  out.airbag_deployed = message->GetSignal("DBW_OccupAnyAirbagDeployed")->GetResult() ? true : false;
508  out.any_seatbelt_unbuckled = message->GetSignal("DBW_OccupAnySeatbeltUnbuckled")->GetResult() ? true : false;
509 
511  }
512  }
513  break;
514 
515  case ID_MISC_REPORT:
516  {
518 
519  if (msg->dlc >= message->GetDlc()) {
520 
521  message->SetFrame(msg);
522 
523  dbw_pacifica_msgs::MiscReport out;
524  out.header.stamp = msg->header.stamp;
525 
526  out.fuel_level = (double)message->GetSignal("DBW_MiscFuelLvl")->GetResult();
527 
528  out.drive_by_wire_enabled = (bool)message->GetSignal("DBW_MiscByWireEnabled")->GetResult();
529  out.vehicle_speed = (double)message->GetSignal("DBW_MiscVehicleSpeed")->GetResult();
530 
531  out.software_build_number = message->GetSignal("DBW_SoftwareBuildNumber")->GetResult();
532  out.general_actuator_fault = message->GetSignal("DBW_MiscFault")->GetResult() ? true : false;
533  out.by_wire_ready = message->GetSignal("DBW_MiscByWireReady")->GetResult() ? true : false;
534  out.general_driver_activity = message->GetSignal("DBW_MiscDriverActivity")->GetResult() ? true : false;
535  out.comms_fault = message->GetSignal("DBW_MiscAKitCommFault")->GetResult() ? true : false;
536 
537  out.ambient_temp = (double)message->GetSignal("DBW_AmbientTemp")->GetResult();
538 
539  pub_misc_.publish(out);
540  }
541  }
542  break;
543 
545  {
547 
548  if (msg->dlc >= message->GetDlc()) {
549 
550  message->SetFrame(msg);
551 
552  dbw_pacifica_msgs::LowVoltageSystemReport lvSystemReport;
553  lvSystemReport.header.stamp = msg->header.stamp;
554 
555  lvSystemReport.vehicle_battery_volts = (double)message->GetSignal("DBW_LvVehBattVlt")->GetResult();
556  lvSystemReport.vehicle_battery_current = (double)message->GetSignal("DBW_LvBattCurr")->GetResult();
557  lvSystemReport.vehicle_alternator_current = (double)message->GetSignal("DBW_LvAlternatorCurr")->GetResult();
558 
559  lvSystemReport.dbw_battery_volts = (double)message->GetSignal("DBW_LvDbwBattVlt")->GetResult();
560  lvSystemReport.dcdc_current = (double)message->GetSignal("DBW_LvDcdcCurr")->GetResult();
561 
562  lvSystemReport.aux_inverter_contactor = message->GetSignal("DBW_LvInvtrContactorCmd")->GetResult() ? true : false;
563 
564  pub_low_voltage_system_.publish(lvSystemReport);
565  }
566  }
567  break;
568 
569  case ID_BRAKE_2_REPORT:
570  {
572 
573  if (msg->dlc >= message->GetDlc()) {
574  message->SetFrame(msg);
575 
576  dbw_pacifica_msgs::Brake2Report brake2Report;
577  brake2Report.header.stamp = msg->header.stamp;
578 
579  brake2Report.brake_pressure = message->GetSignal("DBW_BrakePress_bar")->GetResult();
580 
581  brake2Report.estimated_road_slope = message->GetSignal("DBW_RoadSlopeEstimate")->GetResult();
582 
583  brake2Report.speed_set_point = message->GetSignal("DBW_SpeedSetpt")->GetResult();
584 
585  pub_brake_2_report_.publish(brake2Report);
586  }
587  }
588  break;
589 
591  {
593 
594  if (msg->dlc >= message->GetDlc()) {
595  message->SetFrame(msg);
596 
597  dbw_pacifica_msgs::Steering2Report steering2Report;
598  steering2Report.header.stamp = msg->header.stamp;
599 
600  steering2Report.vehicle_curvature_actual = message->GetSignal("DBW_SteeringVehCurvatureAct")->GetResult();
601 
602  steering2Report.max_torque_driver = message->GetSignal("DBW_SteerTrq_Driver")->GetResult();
603 
604  steering2Report.max_torque_motor = message->GetSignal("DBW_SteerTrq_Motor")->GetResult();
605 
606  pub_steering_2_report_.publish(steering2Report);
607  }
608  }
609  break;
610 
612  {
614 
615  if (msg->dlc >= message->GetDlc()) {
616  message->SetFrame(msg);
617 
618  dbw_pacifica_msgs::FaultActionsReport faultActionsReport;
619  faultActionsReport.header.stamp = msg->header.stamp;
620 
621  faultActionsReport.autonomous_disabled_no_brakes = message->GetSignal("DBW_FltAct_AutonDsblNoBrakes")->GetResult();
622 
623  faultActionsReport.autonomous_disabled_apply_brakes = message->GetSignal("DBW_FltAct_AutonDsblApplyBrakes")->GetResult();
624  faultActionsReport.can_gateway_disabled = message->GetSignal("DBW_FltAct_CANGatewayDsbl")->GetResult();
625  faultActionsReport.inverter_contactor_disabled = message->GetSignal("DBW_FltAct_InvtrCntctrDsbl")->GetResult();
626  faultActionsReport.prevent_enter_autonomous_mode = message->GetSignal("DBW_FltAct_PreventEnterAutonMode")->GetResult();
627  faultActionsReport.warn_driver_only = message->GetSignal("DBW_FltAct_WarnDriverOnly")->GetResult();
628 
629  pub_fault_actions_report_.publish(faultActionsReport);
630  }
631  }
632  break;
633 
635  {
637 
638  if (msg->dlc >= message->GetDlc()) {
639  message->SetFrame(msg);
640 
641  dbw_pacifica_msgs::HmiGlobalEnableReport hmiGlobalEnableReport;
642  hmiGlobalEnableReport.header.stamp = msg->header.stamp;
643 
644  hmiGlobalEnableReport.enable_request = message->GetSignal("HMI_GlobalByWireEnblReq")->GetResult();
645 
646  hmiGlobalEnableReport.disable_request = message->GetSignal("HMI_GlobalByWireDisblReq")->GetResult();
647  hmiGlobalEnableReport.checksum = message->GetSignal("HMI_GlobalEnblChecksum")->GetResult();
648  hmiGlobalEnableReport.ecu_build_number = message->GetSignal("HMI_SoftwareBuildNumber")->GetResult();
649  hmiGlobalEnableReport.rolling_counter = message->GetSignal("HMI_GlobalEnblRollingCntr")->GetResult();
650 
651  pub_hmi_global_enable_report_.publish(hmiGlobalEnableReport);
652  }
653  }
654  break;
655 
656  case ID_BRAKE_CMD:
657  //ROS_WARN("DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Brake. Id: 0x%03X", ID_BRAKE_CMD);
658  break;
660  //ROS_WARN("DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Accelerator Pedal. Id: 0x%03X", ID_ACCELERATOR_PEDAL_CMD);
661  break;
662  case ID_STEERING_CMD:
663  //ROS_WARN("DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Steering. Id: 0x%03X", ID_STEERING_CMD);
664  break;
665  case ID_GEAR_CMD:
666  //ROS_WARN("DBW system: Another node on the CAN bus is commanding the vehicle!!! Subsystem: Shifting. Id: 0x%03X", ID_GEAR_CMD);
667  break;
668  }
669  }
670 #if 0
671  ROS_INFO("ena: %s, clr: %s, brake: %s, Accelerator Pedal: %s, steering: %s, gear: %s",
672  enabled() ? "true " : "false",
673  clear() ? "true " : "false",
674  override_brake_ ? "true " : "false",
675  override_accelerator_pedal_ ? "true " : "false",
676  override_steering_ ? "true " : "false",
677  override_gear_ ? "true " : "false"
678  );
679 #endif
680 }
681 
682 void DbwNode::recvBrakeCmd(const dbw_pacifica_msgs::BrakeCmd::ConstPtr& msg)
683 {
684  NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_BrakeRequest");
685 
686  message->GetSignal("AKit_BrakePedalReq")->SetResult(0);
687  message->GetSignal("AKit_BrakeCtrlEnblReq")->SetResult(0);
688  message->GetSignal("AKit_BrakeCtrlReqType")->SetResult(0);
689  message->GetSignal("AKit_BrakePcntTorqueReq")->SetResult(0);
690  message->GetSignal("AKit_SpeedModeDecelLim")->SetResult(0);
691  message->GetSignal("AKit_SpeedModeNegJerkLim")->SetResult(0);
692 
693  if (enabled()) {
694  if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::open_loop) {
695  message->GetSignal("AKit_BrakeCtrlReqType")->SetResult(0);
696  message->GetSignal("AKit_BrakePedalReq")->SetResult(msg->pedal_cmd);
697  } else if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::closed_loop_actuator) {
698  message->GetSignal("AKit_BrakeCtrlReqType")->SetResult(1);
699  message->GetSignal("AKit_BrakePcntTorqueReq")->SetResult(msg->torque_cmd);
700  } else if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::closed_loop_vehicle) {
701  message->GetSignal("AKit_BrakeCtrlReqType")->SetResult(2);
702  message->GetSignal("AKit_SpeedModeDecelLim")->SetResult(msg->decel_limit);
703  message->GetSignal("AKit_SpeedModeNegJerkLim")->SetResult(msg->decel_negative_jerk_limit);
704  } else {
705  message->GetSignal("AKit_BrakeCtrlReqType")->SetResult(0);
706  }
707 
708  if(msg->enable) {
709  message->GetSignal("AKit_BrakeCtrlEnblReq")->SetResult(1);
710  }
711 
712  }
713 
714  NewEagle::DbcSignal* cnt = message->GetSignal("AKit_BrakeRollingCntr");
715  cnt->SetResult(msg->rolling_counter);
716 
717  can_msgs::Frame frame = message->GetFrame();
718 
719  pub_can_.publish(frame);
720 }
721 
722 void DbwNode::recvAcceleratorPedalCmd(const dbw_pacifica_msgs::AcceleratorPedalCmd::ConstPtr& msg)
723 {
724  NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_AccelPdlRequest");
725 
726  message->GetSignal("AKit_AccelPdlReq")->SetResult(0);
727  message->GetSignal("AKit_AccelPdlEnblReq")->SetResult(0);
728  message->GetSignal("Akit_AccelPdlIgnoreDriverOvrd")->SetResult(0);
729  message->GetSignal("AKit_AccelPdlRollingCntr")->SetResult(0);
730  message->GetSignal("AKit_AccelReqType")->SetResult(0);
731  message->GetSignal("AKit_AccelPcntTorqueReq")->SetResult(0);
732  message->GetSignal("AKit_AccelPdlChecksum")->SetResult(0);
733  message->GetSignal("AKit_SpeedReq")->SetResult(0);
734  message->GetSignal("AKit_SpeedModeRoadSlope")->SetResult(0);
735  message->GetSignal("AKit_SpeedModeAccelLim")->SetResult(0);
736  message->GetSignal("AKit_SpeedModePosJerkLim")->SetResult(0);
737 
738  if (enabled()) {
739 
740  if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::open_loop) {
741  message->GetSignal("AKit_AccelReqType")->SetResult(0);
742  message->GetSignal("AKit_AccelPdlReq")->SetResult(msg->pedal_cmd);
743  } else if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::closed_loop_actuator) {
744  message->GetSignal("AKit_AccelReqType")->SetResult(1);
745  message->GetSignal("AKit_AccelPcntTorqueReq")->SetResult(msg->torque_cmd);
746  } else if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::closed_loop_vehicle) {
747  message->GetSignal("AKit_AccelReqType")->SetResult(2);
748 
749  message->GetSignal("AKit_SpeedReq")->SetResult(msg->speed_cmd);
750  message->GetSignal("AKit_SpeedModeRoadSlope")->SetResult(msg->road_slope);
751  message->GetSignal("AKit_SpeedModeAccelLim")->SetResult(msg->accel_limit);
752  message->GetSignal("AKit_SpeedModePosJerkLim")->SetResult(msg->accel_positive_jerk_limit);
753  } else {
754  message->GetSignal("AKit_AccelReqType")->SetResult(0);
755  }
756 
757  if(msg->enable) {
758  message->GetSignal("AKit_AccelPdlEnblReq")->SetResult(1);
759  }
760  }
761 
762  NewEagle::DbcSignal* cnt = message->GetSignal("AKit_AccelPdlRollingCntr");
763  cnt->SetResult(msg->rolling_counter);
764 
765  if (msg->ignore) {
766  message->GetSignal("Akit_AccelPdlIgnoreDriverOvrd")->SetResult(1);
767  }
768 
769  can_msgs::Frame frame = message->GetFrame();
770 
771  pub_can_.publish(frame);
772 }
773 
774 void DbwNode::recvSteeringCmd(const dbw_pacifica_msgs::SteeringCmd::ConstPtr& msg)
775 {
776  NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_SteeringRequest");
777 
778  message->GetSignal("AKit_SteeringWhlAngleReq")->SetResult(0);
779  message->GetSignal("AKit_SteeringWhlAngleVelocityLim")->SetResult(0);
780  message->GetSignal("AKit_SteerCtrlEnblReq")->SetResult(0);
781  message->GetSignal("AKit_SteeringWhlIgnoreDriverOvrd")->SetResult(0);
782  message->GetSignal("AKit_SteeringWhlPcntTrqReq")->SetResult(0);
783  message->GetSignal("AKit_SteeringReqType")->SetResult(0);
784  message->GetSignal("AKit_SteeringVehCurvatureReq")->SetResult(0);
785  message->GetSignal("AKit_SteeringChecksum")->SetResult(0);
786 
787  if (enabled()) {
788  if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::open_loop) {
789  message->GetSignal("AKit_SteeringReqType")->SetResult(0);
790  message->GetSignal("AKit_SteeringWhlPcntTrqReq")->SetResult(msg->torque_cmd);
791  } else if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::closed_loop_actuator) {
792  message->GetSignal("AKit_SteeringReqType")->SetResult(1);
793  double scmd = std::max((float)-470.0, std::min((float)470.0, (float)(msg->angle_cmd * (180 / M_PI * 1.0))));
794  message->GetSignal("AKit_SteeringWhlAngleReq")->SetResult(scmd);
795  } else if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::closed_loop_vehicle) {
796  message->GetSignal("AKit_SteeringReqType")->SetResult(2);
797  message->GetSignal("AKit_SteeringVehCurvatureReq")->SetResult(msg->vehicle_curvature_cmd);
798  } else {
799  message->GetSignal("AKit_SteeringReqType")->SetResult(0);
800  }
801 
802  if (fabsf(msg->angle_velocity) > 0)
803  {
804  uint16_t vcmd = std::max((float)1, std::min((float)254, (float)roundf(fabsf(msg->angle_velocity) * 180 / M_PI / 2)));
805 
806  message->GetSignal("AKit_SteeringWhlAngleVelocityLim")->SetResult(vcmd);
807  }
808  if(msg->enable) {
809  message->GetSignal("AKit_SteerCtrlEnblReq")->SetResult(1);
810  }
811  }
812 
813  if (msg->ignore) {
814  message->GetSignal("AKit_SteeringWhlIgnoreDriverOvrd")->SetResult(1);
815  }
816 
817  message->GetSignal("AKit_SteerRollingCntr")->SetResult(msg->rolling_counter);
818 
819  can_msgs::Frame frame = message->GetFrame();
820 
821  pub_can_.publish(frame);
822 }
823 
824 void DbwNode::recvGearCmd(const dbw_pacifica_msgs::GearCmd::ConstPtr& msg)
825 {
826  NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_PrndRequest");
827 
828  message->GetSignal("AKit_PrndCtrlEnblReq")->SetResult(0);
829  message->GetSignal("AKit_PrndStateReq")->SetResult(0);
830  message->GetSignal("AKit_PrndChecksum")->SetResult(0);
831 
832  if (enabled()) {
833  if(msg->enable)
834  {
835  message->GetSignal("AKit_PrndCtrlEnblReq")->SetResult(1);
836  }
837 
838  message->GetSignal("AKit_PrndStateReq")->SetResult(msg->cmd.gear);
839  }
840 
841  message->GetSignal("AKit_PrndRollingCntr")->SetResult(msg->rolling_counter);
842 
843  can_msgs::Frame frame = message->GetFrame();
844 
845  pub_can_.publish(frame);
846 }
847 
848 void DbwNode::recvGlobalEnableCmd(const dbw_pacifica_msgs::GlobalEnableCmd::ConstPtr& msg)
849 {
850  NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_GlobalEnbl");
851 
852  message->GetSignal("AKit_GlobalEnblRollingCntr")->SetResult(0);
853  message->GetSignal("AKit_GlobalByWireEnblReq")->SetResult(0);
854  message->GetSignal("AKit_EnblJoystickLimits")->SetResult(0);
855  message->GetSignal("AKit_SoftwareBuildNumber")->SetResult(0);
856  message->GetSignal("Akit_GlobalEnblChecksum")->SetResult(0);
857 
858  if (enabled()) {
859  if(msg->global_enable) {
860  message->GetSignal("AKit_GlobalByWireEnblReq")->SetResult(1);
861  }
862 
863  if(msg->enable_joystick_limits) {
864  message->GetSignal("AKit_EnblJoystickLimits")->SetResult(1);
865  }
866 
867  message->GetSignal("AKit_SoftwareBuildNumber")->SetResult(msg->ecu_build_number);
868  }
869 
870  message->GetSignal("AKit_GlobalEnblRollingCntr")->SetResult(msg->rolling_counter);
871 
872  can_msgs::Frame frame = message->GetFrame();
873 
874  pub_can_.publish(frame);
875 }
876 
877 void DbwNode::recvMiscCmd(const dbw_pacifica_msgs::MiscCmd::ConstPtr& msg)
878 {
879  NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_OtherActuators");
880 
881  message->GetSignal("AKit_TurnSignalReq")->SetResult(0);
882  message->GetSignal("AKit_RightRearDoorReq")->SetResult(0);
883  message->GetSignal("AKit_HighBeamReq")->SetResult(0);
884  message->GetSignal("AKit_FrontWiperReq")->SetResult(0);
885  message->GetSignal("AKit_RearWiperReq")->SetResult(0);
886  message->GetSignal("AKit_IgnitionReq")->SetResult(0);
887  message->GetSignal("AKit_LeftRearDoorReq")->SetResult(0);
888  message->GetSignal("AKit_LiftgateDoorReq")->SetResult(0);
889  message->GetSignal("AKit_BlockBasicCruiseCtrlBtns")->SetResult(0);
890  message->GetSignal("AKit_BlockAdapCruiseCtrlBtns")->SetResult(0);
891  message->GetSignal("AKit_BlockTurnSigStalkInpts")->SetResult(0);
892  message->GetSignal("AKit_OtherChecksum")->SetResult(0);
893  message->GetSignal("AKit_HornReq")->SetResult(0);
894  message->GetSignal("AKit_LowBeamReq")->SetResult(0);
895 
896  if (enabled()) {
897 
898  message->GetSignal("AKit_TurnSignalReq")->SetResult(msg->cmd.value);
899 
900  message->GetSignal("AKit_RightRearDoorReq")->SetResult(msg->door_request_right_rear.value);
901  message->GetSignal("AKit_HighBeamReq")->SetResult(msg->high_beam_cmd.status);
902 
903  message->GetSignal("AKit_FrontWiperReq")->SetResult(msg->front_wiper_cmd.status);
904  message->GetSignal("AKit_RearWiperReq")->SetResult(msg->rear_wiper_cmd.status);
905 
906  message->GetSignal("AKit_IgnitionReq")->SetResult(msg->ignition_cmd.status);
907 
908  message->GetSignal("AKit_LeftRearDoorReq")->SetResult(msg->door_request_left_rear.value);
909  message->GetSignal("AKit_LiftgateDoorReq")->SetResult(msg->door_request_lift_gate.value);
910 
911  message->GetSignal("AKit_BlockBasicCruiseCtrlBtns")->SetResult(msg->block_standard_cruise_buttons);
912  message->GetSignal("AKit_BlockAdapCruiseCtrlBtns")->SetResult(msg->block_adaptive_cruise_buttons);
913  message->GetSignal("AKit_BlockTurnSigStalkInpts")->SetResult(msg->block_turn_signal_stalk);
914 
915  message->GetSignal("AKit_HornReq")->SetResult(msg->horn_cmd);
916  message->GetSignal("AKit_LowBeamReq")->SetResult(msg->low_beam_cmd.status);
917  }
918 
919  message->GetSignal("AKit_OtherRollingCntr")->SetResult(msg->rolling_counter);
920 
921  can_msgs::Frame frame = message->GetFrame();
922 
923  pub_can_.publish(frame);
924 }
925 
927 {
928  bool change = false;
929  bool en = enabled();
930  if (prev_enable_ != en) {
931  std_msgs::Bool msg;
932  msg.data = en;
934  change = true;
935  }
936  prev_enable_ = en;
937  return change;
938 }
939 
941 {
942  if (clear()) {
943  can_msgs::Frame out;
944  out.is_extended = false;
945 
946  if (override_brake_) {
947  // Might have an issue with WatchdogCntr when these are set.
948  NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_BrakeRequest");
949  message->GetSignal("AKit_BrakePedalReq")->SetResult(0);
950  message->GetSignal("AKit_BrakeCtrlEnblReq")->SetResult(0);
951  //message->GetSignal("AKit_BrakePedalCtrlMode")->SetResult(0);
952  pub_can_.publish(message->GetFrame());
953  }
954 
956  {
957  // Might have an issue with WatchdogCntr when these are set.
958  NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_AccelPdlRequest");
959  message->GetSignal("AKit_AccelPdlReq")->SetResult(0);
960  message->GetSignal("AKit_AccelPdlEnblReq")->SetResult(0);
961  message->GetSignal("Akit_AccelPdlIgnoreDriverOvrd")->SetResult(0);
962  //message->GetSignal("AKit_AccelPdlCtrlMode")->SetResult(0);
963  pub_can_.publish(message->GetFrame());
964  }
965 
966  if (override_steering_) {
967  // Might have an issue with WatchdogCntr when these are set.
968  NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_SteeringRequest");
969  message->GetSignal("AKit_SteeringWhlAngleReq")->SetResult(0);
970  message->GetSignal("AKit_SteeringWhlAngleVelocityLim")->SetResult(0);
971  message->GetSignal("AKit_SteeringWhlIgnoreDriverOvrd")->SetResult(0);
972  message->GetSignal("AKit_SteeringWhlPcntTrqReq")->SetResult(0);
973  //message->GetSignal("AKit_SteeringWhlCtrlMode")->SetResult(0);
974  //message->GetSignal("AKit_SteeringWhlCmdType")->SetResult(0);
975 
976  pub_can_.publish(message->GetFrame());
977  }
978 
979  if (override_gear_) {
980  NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_GearRequest");
981  message->GetSignal("AKit_PrndStateCmd")->SetResult(0);
982  message->GetSignal("AKit_PrndChecksum")->SetResult(0);
983  pub_can_.publish(message->GetFrame());
984  }
985  }
986 }
987 
989 {
990  if (!enable_) {
991  if (fault()) {
992  if (fault_steering_cal_) {
993  ROS_WARN("DBW system not enabled. Steering calibration fault.");
994  }
995  if (fault_brakes_) {
996  ROS_WARN("DBW system not enabled. Braking fault.");
997  }
999  ROS_WARN("DBW system not enabled. Accelerator Pedal fault.");
1000  }
1001  if (fault_steering_) {
1002  ROS_WARN("DBW system not enabled. Steering fault.");
1003  }
1004  if (fault_watchdog_) {
1005  ROS_WARN("DBW system not enabled. Watchdog fault.");
1006  }
1007  } else {
1008  enable_ = true;
1009  if (publishDbwEnabled()) {
1010  ROS_INFO("DBW system enabled.");
1011  } else {
1012  ROS_INFO("DBW system enable requested. Waiting for ready.");
1013  }
1014  }
1015  }
1016 }
1017 
1019 {
1020  if (enable_) {
1021  enable_ = false;
1023  ROS_WARN("DBW system disabled.");
1024  }
1025 }
1026 
1028 {
1029  if (enable_) {
1030  enable_ = false;
1032  ROS_WARN("DBW system disabled. Cancel button pressed.");
1033  }
1034 }
1035 
1036 void DbwNode::overrideBrake(bool override)
1037 {
1038  bool en = enabled();
1039  if (override && en) {
1040  enable_ = false;
1041  }
1042  override_brake_ = override;
1043  if (publishDbwEnabled()) {
1044  if (en) {
1045  ROS_WARN("DBW system disabled. Driver override on brake/Accelerator Pedal pedal.");
1046  } else {
1047  ROS_INFO("DBW system enabled.");
1048  }
1049  }
1050 }
1051 
1053 {
1054  bool en = enabled();
1055  if (override && en) {
1056  enable_ = false;
1057  }
1058  override_accelerator_pedal_ = override;
1059  if (publishDbwEnabled()) {
1060  if (en) {
1061  ROS_WARN("DBW system disabled. Driver override on brake/Accelerator Pedal pedal.");
1062  } else {
1063  ROS_INFO("DBW system enabled.");
1064  }
1065  }
1066 }
1067 
1068 void DbwNode::overrideSteering(bool override)
1069 {
1070  bool en = enabled();
1071  if (override && en) {
1072  enable_ = false;
1073  }
1074  override_steering_ = override;
1075  if (publishDbwEnabled()) {
1076  if (en) {
1077  ROS_WARN("DBW system disabled. Driver override on steering wheel.");
1078  } else {
1079  ROS_INFO("DBW system enabled.");
1080  }
1081  }
1082 }
1083 
1084 void DbwNode::overrideGear(bool override)
1085 {
1086  bool en = enabled();
1087  if (override && en) {
1088  enable_ = false;
1089  }
1090  override_gear_ = override;
1091  if (publishDbwEnabled()) {
1092  if (en) {
1093  ROS_WARN("DBW system disabled. Driver override on shifter.");
1094  } else {
1095  ROS_INFO("DBW system enabled.");
1096  }
1097  }
1098 }
1099 
1100 void DbwNode::timeoutBrake(bool timeout, bool enabled)
1101 {
1102  if (!timeout_brakes_ && enabled_brakes_ && timeout && !enabled) {
1103  ROS_WARN("Brake subsystem disabled after 100ms command timeout");
1104  }
1105  timeout_brakes_ = timeout;
1107 }
1108 
1110 {
1111  if (!timeout_accelerator_pedal_ && enabled_accelerator_pedal_ && timeout && !enabled) {
1112  ROS_WARN("Accelerator Pedal subsystem disabled after 100ms command timeout");
1113  }
1114  timeout_accelerator_pedal_ = timeout;
1116 }
1117 
1118 void DbwNode::timeoutSteering(bool timeout, bool enabled)
1119 {
1120  if (!timeout_steering_ && enabled_steering_ && timeout && !enabled) {
1121  ROS_WARN("Steering subsystem disabled after 100ms command timeout");
1122  }
1123  timeout_steering_ = timeout;
1125 }
1126 
1128 {
1129  bool en = enabled();
1130  if (fault && en) {
1131  enable_ = false;
1132  }
1133  fault_brakes_ = fault;
1134  if (publishDbwEnabled()) {
1135  if (en) {
1136  ROS_ERROR("DBW system disabled. Braking fault.");
1137  } else {
1138  ROS_INFO("DBW system enabled.");
1139  }
1140  }
1141 }
1142 
1144 {
1145  bool en = enabled();
1146  if (fault && en) {
1147  enable_ = false;
1148  }
1150  if (publishDbwEnabled()) {
1151  if (en) {
1152  ROS_ERROR("DBW system disabled. Accelerator Pedal fault.");
1153  } else {
1154  ROS_INFO("DBW system enabled.");
1155  }
1156  }
1157 }
1158 
1160 {
1161  bool en = enabled();
1162  if (fault && en) {
1163  enable_ = false;
1164  }
1166  if (publishDbwEnabled()) {
1167  if (en) {
1168  ROS_ERROR("DBW system disabled. Steering fault.");
1169  } else {
1170  ROS_INFO("DBW system enabled.");
1171  }
1172  }
1173 }
1174 
1176 {
1177  bool en = enabled();
1178  if (fault && en) {
1179  enable_ = false;
1180  }
1182  if (publishDbwEnabled()) {
1183  if (en) {
1184  ROS_ERROR("DBW system disabled. Steering calibration fault.");
1185  } else {
1186  ROS_INFO("DBW system enabled.");
1187  }
1188  }
1189 }
1190 
1191 void DbwNode::faultWatchdog(bool fault, uint8_t src, bool braking)
1192 {
1193  bool en = enabled();
1194  if (fault && en) {
1195  enable_ = false;
1196  }
1198  if (publishDbwEnabled()) {
1199  if (en) {
1200  ROS_ERROR("DBW system disabled. Watchdog fault.");
1201  } else {
1202  ROS_INFO("DBW system enabled.");
1203  }
1204  }
1205  if (braking && !fault_watchdog_using_brakes_) {
1206  ROS_WARN("Watchdog event: Alerting driver and applying brakes.");
1207  } else if (!braking && fault_watchdog_using_brakes_) {
1208  ROS_INFO("Watchdog event: Driver has successfully taken control.");
1209  }
1210  if (fault && src && !fault_watchdog_warned_) {
1211  ROS_WARN("Watchdog event: Unknown Fault!");
1212  // switch (src) {
1213  // case dbw_pacifica_msgs::WatchdogStatus::OTHER_BRAKE:
1214  // ROS_WARN("Watchdog event: Fault determined by brake controller");
1215  // break;
1216  // case dbw_pacifica_msgs::WatchdogStatus::OTHER_ACCELERATOR_PEDAL:
1217  // ROS_WARN("Watchdog event: Fault determined by Accelerator Pedal controller");
1218  // break;
1219  // case dbw_pacifica_msgs::WatchdogStatus::OTHER_STEERING:
1220  // ROS_WARN("Watchdog event: Fault determined by steering controller");
1221  // break;
1222  // case dbw_pacifica_msgs::WatchdogStatus::BRAKE_COUNTER:
1223  // ROS_WARN("Watchdog event: Brake command counter failed to increment");
1224  // break;
1225  // case dbw_pacifica_msgs::WatchdogStatus::BRAKE_DISABLED:
1226  // ROS_WARN("Watchdog event: Brake transition to disabled while in gear or moving");
1227  // break;
1228  // case dbw_pacifica_msgs::WatchdogStatus::BRAKE_COMMAND:
1229  // ROS_WARN("Watchdog event: Brake command timeout after 100ms");
1230  // break;
1231  // case dbw_pacifica_msgs::WatchdogStatus::BRAKE_REPORT:
1232  // ROS_WARN("Watchdog event: Brake report timeout after 100ms");
1233  // break;
1234  // case dbw_pacifica_msgs::WatchdogStatus::ACCELERATOR_PEDAL_COUNTER:
1235  // ROS_WARN("Watchdog event: Accelerator Pedal command counter failed to increment");
1236  // break;
1237  // case dbw_pacifica_msgs::WatchdogStatus::ACCELERATOR_PEDAL_DISABLED:
1238  // ROS_WARN("Watchdog event: Accelerator Pedal transition to disabled while in gear or moving");
1239  // break;
1240  // case dbw_pacifica_msgs::WatchdogStatus::ACCELERATOR_PEDAL_COMMAND:
1241  // ROS_WARN("Watchdog event: Accelerator Pedal command timeout after 100ms");
1242  // break;
1243  // case dbw_pacifica_msgs::WatchdogStatus::ACCELERATOR_PEDAL_REPORT:
1244  // ROS_WARN("Watchdog event: Accelerator Pedal report timeout after 100ms");
1245  // break;
1246  // case dbw_pacifica_msgs::WatchdogStatus::STEERING_COUNTER:
1247  // ROS_WARN("Watchdog event: Steering command counter failed to increment");
1248  // break;
1249  // case dbw_pacifica_msgs::WatchdogStatus::STEERING_DISABLED:
1250  // ROS_WARN("Watchdog event: Steering transition to disabled while in gear or moving");
1251  // break;
1252  // case dbw_pacifica_msgs::WatchdogStatus::STEERING_COMMAND:
1253  // ROS_WARN("Watchdog event: Steering command timeout after 100ms");
1254  // break;
1255  // case dbw_pacifica_msgs::WatchdogStatus::STEERING_REPORT:
1256  // ROS_WARN("Watchdog event: Steering report timeout after 100ms");
1257  // break;
1258  // }
1259  fault_watchdog_warned_ = true;
1260  } else if (!fault) {
1261  fault_watchdog_warned_ = false;
1262  }
1263  fault_watchdog_using_brakes_ = braking;
1265  ROS_WARN_THROTTLE(2.0, "Watchdog event: Press left OK button on the steering wheel or cycle power to clear event.");
1266  }
1267 }
1268 
1269 void DbwNode::faultWatchdog(bool fault, uint8_t src) {
1270  faultWatchdog(fault, src, fault_watchdog_using_brakes_); // No change to 'using brakes' status
1271 }
1272 
1273 void DbwNode::publishJointStates(const ros::Time &stamp, const dbw_pacifica_msgs::WheelSpeedReport *wheels, const dbw_pacifica_msgs::SteeringReport *steering)
1274 {
1275  double dt = (stamp - joint_state_.header.stamp).toSec();
1276  if (wheels) {
1277  joint_state_.velocity[JOINT_FL] = wheels->front_left;
1278  joint_state_.velocity[JOINT_FR] = wheels->front_right;
1279  joint_state_.velocity[JOINT_RL] = wheels->rear_left;
1280  joint_state_.velocity[JOINT_RR] = wheels->rear_right;
1281  }
1282  if (steering) {
1283  const double L = acker_wheelbase_;
1284  const double W = acker_track_;
1285  const double r = L / tan(steering->steering_wheel_angle / steering_ratio_);
1286  joint_state_.position[JOINT_SL] = atan(L / (r - W/2));
1287  joint_state_.position[JOINT_SR] = atan(L / (r + W/2));
1288  }
1289  if (dt < 0.5) {
1290  for (unsigned int i = JOINT_FL; i <= JOINT_RR; i++) {
1291  joint_state_.position[i] = fmod(joint_state_.position[i] + dt * joint_state_.velocity[i], 2*M_PI);
1292  }
1293  }
1294  joint_state_.header.stamp = stamp;
1296 }
1297 
1298 } // dbw_pacifica_can
void recvGearCmd(const dbw_pacifica_msgs::GearCmd::ConstPtr &msg)
Definition: DbwNode.cpp:824
ros::Subscriber sub_can_
Definition: DbwNode.h:176
NewEagle::DbcSignal * GetSignal(std::string signalName)
void publishJointStates(const ros::Time &stamp, const dbw_pacifica_msgs::WheelSpeedReport *wheels, const dbw_pacifica_msgs::SteeringReport *steering)
Definition: DbwNode.cpp:1273
void recvMiscCmd(const dbw_pacifica_msgs::MiscCmd::ConstPtr &msg)
Definition: DbwNode.cpp:877
ros::Publisher pub_brake_2_report_
Definition: DbwNode.h:203
void faultWatchdog(bool fault, uint8_t src, bool braking)
Definition: DbwNode.cpp:1191
NewEagle::Dbc dbwDbc_
Definition: DbwNode.h:208
#define ROS_WARN_THROTTLE(rate,...)
ros::Publisher pub_sys_enable_
Definition: DbwNode.h:199
void publish(const boost::shared_ptr< M > &message) const
ros::Subscriber sub_global_enable_
Definition: DbwNode.h:182
void SetFrame(const can_msgs::Frame::ConstPtr &msg)
void recvCAN(const can_msgs::Frame::ConstPtr &msg)
Definition: DbwNode.cpp:158
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Publisher pub_driver_input_
Definition: DbwNode.h:200
sensor_msgs::JointState joint_state_
Definition: DbwNode.h:157
ros::Publisher pub_fault_actions_report_
Definition: DbwNode.h:205
void recvAcceleratorPedalCmd(const dbw_pacifica_msgs::AcceleratorPedalCmd::ConstPtr &msg)
Definition: DbwNode.cpp:722
NewEagle::Dbc NewDbc(const std::string &dbcFile)
ros::Publisher pub_misc_
Definition: DbwNode.h:190
void recvDisable(const std_msgs::Empty::ConstPtr &msg)
Definition: DbwNode.cpp:153
ros::Publisher pub_wheel_speeds_
Definition: DbwNode.h:191
ros::Subscriber sub_gear_
Definition: DbwNode.h:180
void timeoutAcceleratorPedal(bool timeout, bool enabled)
Definition: DbwNode.cpp:1109
ros::Publisher pub_steering_2_report_
Definition: DbwNode.h:204
#define ROS_WARN(...)
void faultSteeringCal(bool fault)
Definition: DbwNode.cpp:1175
double GetResult() const
ros::Publisher pub_brake_
Definition: DbwNode.h:186
void overrideSteering(bool override)
Definition: DbwNode.cpp:1068
ros::Publisher pub_imu_
Definition: DbwNode.h:195
can_msgs::Frame GetFrame()
ros::Publisher pdu1_relay_pub_
Definition: DbwNode.h:212
ros::Publisher pub_low_voltage_system_
Definition: DbwNode.h:201
NewEagle::DbcMessage * GetMessage(std::string messageName)
ros::Subscriber sub_accelerator_pedal_
Definition: DbwNode.h:178
void timeoutSteering(bool timeout, bool enabled)
Definition: DbwNode.cpp:1118
void timerCallback(const ros::TimerEvent &event)
Definition: DbwNode.cpp:940
ros::Subscriber sub_brake_
Definition: DbwNode.h:177
#define ROS_INFO(...)
void timeoutBrake(bool timeout, bool enabled)
Definition: DbwNode.cpp:1100
ros::Subscriber sub_misc_
Definition: DbwNode.h:181
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void recvGlobalEnableCmd(const dbw_pacifica_msgs::GlobalEnableCmd::ConstPtr &msg)
Definition: DbwNode.cpp:848
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string dbcFile_
Definition: DbwNode.h:209
void recvEnable(const std_msgs::Empty::ConstPtr &msg)
Definition: DbwNode.cpp:148
ros::Subscriber sub_disable_
Definition: DbwNode.h:175
void SetResult(double result)
void overrideAcceleratorPedal(bool override)
Definition: DbwNode.cpp:1052
ros::Subscriber sub_steering_
Definition: DbwNode.h:179
ros::Publisher pub_wheel_positions_
Definition: DbwNode.h:192
ros::Publisher pub_joint_states_
Definition: DbwNode.h:196
void faultBrakes(bool fault)
Definition: DbwNode.cpp:1127
std::string frame_id_
Definition: DbwNode.h:163
DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
Definition: DbwNode.cpp:42
ros::Publisher pub_vin_
Definition: DbwNode.h:198
void overrideGear(bool override)
Definition: DbwNode.cpp:1084
ros::Publisher pub_hmi_global_enable_report_
Definition: DbwNode.h:206
NewEagle::DbcMessage * GetMessageById(uint32_t id)
bool getParam(const std::string &key, std::string &s) const
ros::Publisher pub_tire_pressure_
Definition: DbwNode.h:193
ros::Subscriber sub_enable_
Definition: DbwNode.h:174
void recvSteeringCmd(const dbw_pacifica_msgs::SteeringCmd::ConstPtr &msg)
Definition: DbwNode.cpp:774
void faultAcceleratorPedal(bool fault)
Definition: DbwNode.cpp:1143
ros::Publisher pub_surround_
Definition: DbwNode.h:194
ros::Publisher pub_can_
Definition: DbwNode.h:185
void faultSteering(bool fault)
Definition: DbwNode.cpp:1159
void overrideBrake(bool override)
Definition: DbwNode.cpp:1036
ros::Publisher pub_gear_
Definition: DbwNode.h:189
ros::Publisher pub_steering_
Definition: DbwNode.h:188
#define ROS_ERROR(...)
void recvBrakeCmd(const dbw_pacifica_msgs::BrakeCmd::ConstPtr &msg)
Definition: DbwNode.cpp:682
ros::Publisher pub_twist_
Definition: DbwNode.h:197
ros::Publisher pub_accel_pedal_
Definition: DbwNode.h:187


dbw_pacifica_can
Author(s): Ryan Borchert
autogenerated on Fri Mar 20 2020 03:31:38