00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "DbwNode.h"
00037 #include <dbw_pacifica_can/dispatch.h>
00038
00039 namespace dbw_pacifica_can
00040 {
00041
00042 DbwNode::DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
00043 {
00044 priv_nh.getParam("dbw_dbc_file", dbcFile_);
00045
00046
00047 prev_enable_ = true;
00048 enable_ = false;
00049 override_brake_ = false;
00050 override_accelerator_pedal_ = false;
00051 override_steering_ = false;
00052 override_gear_ = false;
00053 fault_brakes_ = false;
00054 fault_accelerator_pedal_ = false;
00055 fault_steering_ = false;
00056 fault_steering_cal_ = false;
00057 fault_watchdog_ = false;
00058 fault_watchdog_using_brakes_ = false;
00059 fault_watchdog_warned_ = false;
00060 timeout_brakes_ = false;
00061 timeout_accelerator_pedal_ = false;
00062 timeout_steering_ = false;
00063 enabled_brakes_ = false;
00064 enabled_accelerator_pedal_ = false;
00065 enabled_steering_ = false;
00066 gear_warned_ = false;
00067
00068
00069 frame_id_ = "base_footprint";
00070 priv_nh.getParam("frame_id", frame_id_);
00071
00072
00073 buttons_ = true;
00074 priv_nh.getParam("buttons", buttons_);
00075
00076
00077
00078 acker_wheelbase_ = 2.8498;
00079 acker_track_ = 1.5824;
00080 steering_ratio_ = 14.8;
00081 priv_nh.getParam("ackermann_wheelbase", acker_wheelbase_);
00082 priv_nh.getParam("ackermann_track", acker_track_);
00083 priv_nh.getParam("steering_ratio", steering_ratio_);
00084
00085
00086 joint_state_.position.resize(JOINT_COUNT);
00087 joint_state_.velocity.resize(JOINT_COUNT);
00088 joint_state_.effort.resize(JOINT_COUNT);
00089 joint_state_.name.resize(JOINT_COUNT);
00090 joint_state_.name[JOINT_FL] = "wheel_fl";
00091 joint_state_.name[JOINT_FR] = "wheel_fr";
00092 joint_state_.name[JOINT_RL] = "wheel_rl";
00093 joint_state_.name[JOINT_RR] = "wheel_rr";
00094 joint_state_.name[JOINT_SL] = "steer_fl";
00095 joint_state_.name[JOINT_SR] = "steer_fr";
00096
00097
00098 pub_can_ = node.advertise<can_msgs::Frame>("can_tx", 10);
00099 pub_brake_ = node.advertise<dbw_pacifica_msgs::BrakeReport>("brake_report", 2);
00100 pub_accel_pedal_ = node.advertise<dbw_pacifica_msgs::AcceleratorPedalReport>("accelerator_pedal_report", 2);
00101 pub_steering_ = node.advertise<dbw_pacifica_msgs::SteeringReport>("steering_report", 2);
00102 pub_gear_ = node.advertise<dbw_pacifica_msgs::GearReport>("gear_report", 2);
00103 pub_wheel_speeds_ = node.advertise<dbw_pacifica_msgs::WheelSpeedReport>("wheel_speed_report", 2);
00104 pub_wheel_positions_ = node.advertise<dbw_pacifica_msgs::WheelPositionReport>("wheel_position_report", 2);
00105 pub_tire_pressure_ = node.advertise<dbw_pacifica_msgs::TirePressureReport>("tire_pressure_report", 2);
00106 pub_surround_ = node.advertise<dbw_pacifica_msgs::SurroundReport>("surround_report", 2);
00107
00108 pub_low_voltage_system_ = node.advertise<dbw_pacifica_msgs::LowVoltageSystemReport>("low_voltage_system_report", 2);
00109
00110 pub_brake_2_report_ = node.advertise<dbw_pacifica_msgs::Brake2Report>("brake_2_report", 2);
00111 pub_steering_2_report_ = node.advertise<dbw_pacifica_msgs::Steering2Report>("steering_2_report", 2);
00112 pub_fault_actions_report_ = node.advertise<dbw_pacifica_msgs::FaultActionsReport>("fault_actions_report", 2);
00113 pub_hmi_global_enable_report_ = node.advertise<dbw_pacifica_msgs::HmiGlobalEnableReport>("hmi_global_enable_report", 2);
00114
00115 pub_imu_ = node.advertise<sensor_msgs::Imu>("imu/data_raw", 10);
00116 pub_joint_states_ = node.advertise<sensor_msgs::JointState>("joint_states", 10);
00117 pub_twist_ = node.advertise<geometry_msgs::TwistStamped>("twist", 10);
00118 pub_vin_ = node.advertise<std_msgs::String>("vin", 1, true);
00119 pub_driver_input_ = node.advertise<dbw_pacifica_msgs::DriverInputReport>("driver_input_report", 2);
00120 pub_misc_ = node.advertise<dbw_pacifica_msgs::MiscReport>("misc_report", 2);
00121 pub_sys_enable_ = node.advertise<std_msgs::Bool>("dbw_enabled", 1, true);
00122 publishDbwEnabled();
00123
00124
00125 sub_enable_ = node.subscribe("enable", 10, &DbwNode::recvEnable, this, ros::TransportHints().tcpNoDelay(true));
00126 sub_disable_ = node.subscribe("disable", 10, &DbwNode::recvDisable, this, ros::TransportHints().tcpNoDelay(true));
00127 sub_can_ = node.subscribe("can_rx", 100, &DbwNode::recvCAN, this, ros::TransportHints().tcpNoDelay(true));
00128 sub_brake_ = node.subscribe("brake_cmd", 1, &DbwNode::recvBrakeCmd, this, ros::TransportHints().tcpNoDelay(true));
00129 sub_accelerator_pedal_ = node.subscribe("accelerator_pedal_cmd", 1, &DbwNode::recvAcceleratorPedalCmd, this, ros::TransportHints().tcpNoDelay(true));
00130 sub_steering_ = node.subscribe("steering_cmd", 1, &DbwNode::recvSteeringCmd, this, ros::TransportHints().tcpNoDelay(true));
00131 sub_gear_ = node.subscribe("gear_cmd", 1, &DbwNode::recvGearCmd, this, ros::TransportHints().tcpNoDelay(true));
00132 sub_misc_ = node.subscribe("misc_cmd", 1, &DbwNode::recvMiscCmd, this, ros::TransportHints().tcpNoDelay(true));
00133 sub_global_enable_ = node.subscribe("global_enable_cmd", 1, &DbwNode::recvGlobalEnableCmd, this, ros::TransportHints().tcpNoDelay(true));
00134
00135 pdu1_relay_pub_ = node.advertise<pdu_msgs::RelayCommand>("/pduB/relay_cmd", 1000);
00136 count_ = 0;
00137
00138 dbwDbc_ = NewEagle::DbcBuilder().NewDbc(dbcFile_);
00139
00140
00141 timer_ = node.createTimer(ros::Duration(1 / 20.0), &DbwNode::timerCallback, this);
00142 }
00143
00144 DbwNode::~DbwNode()
00145 {
00146 }
00147
00148 void DbwNode::recvEnable(const std_msgs::Empty::ConstPtr& msg)
00149 {
00150 enableSystem();
00151 }
00152
00153 void DbwNode::recvDisable(const std_msgs::Empty::ConstPtr& msg)
00154 {
00155 disableSystem();
00156 }
00157
00158 void DbwNode::recvCAN(const can_msgs::Frame::ConstPtr& msg)
00159 {
00160
00161 if (!msg->is_rtr && !msg->is_error) {
00162 switch (msg->id) {
00163 case ID_BRAKE_REPORT:
00164 {
00165 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_BRAKE_REPORT);
00166
00167 if (msg->dlc >= message->GetDlc()) {
00168 message->SetFrame(msg);
00169
00170 bool faultCh1 = message->GetSignal("DBW_BrakeFault_Ch1")->GetResult() ? true : false;
00171 bool faultCh2 = message->GetSignal("DBW_BrakeFault_Ch2")->GetResult() ? true : false;
00172 bool brakeSystemFault = message->GetSignal("DBW_BrakeFault")->GetResult() ? true : false;
00173 bool dbwSystemFault = brakeSystemFault;
00174
00175 faultBrakes(faultCh1 && faultCh2);
00176 faultWatchdog(dbwSystemFault, brakeSystemFault);
00177
00178 overrideBrake(message->GetSignal("DBW_BrakeDriverActivity")->GetResult());
00179 dbw_pacifica_msgs::BrakeReport brakeReport;
00180 brakeReport.header.stamp = msg->header.stamp;
00181 brakeReport.pedal_position = message->GetSignal("DBW_BrakePdlDriverInput")->GetResult();
00182 brakeReport.pedal_output = message->GetSignal("DBW_BrakePdlPosnFdbck")->GetResult();
00183
00184 brakeReport.enabled = message->GetSignal("DBW_BrakeEnabled")->GetResult() ? true : false;
00185 brakeReport.driver_activity = message->GetSignal("DBW_BrakeDriverActivity")->GetResult() ? true : false;
00186
00187 brakeReport.fault_brake_system = brakeSystemFault;
00188
00189 brakeReport.fault_ch2 = faultCh2;
00190
00191 brakeReport.rolling_counter = message->GetSignal("DBW_BrakeRollingCntr")->GetResult();
00192
00193 brakeReport.brake_torque_actual = message->GetSignal("DBW_BrakePcntTorqueActual")->GetResult();
00194
00195 brakeReport.intervention_active = message->GetSignal("DBW_BrakeInterventionActv")->GetResult() ? true : false;
00196 brakeReport.intervention_ready = message->GetSignal("DBW_BrakeInterventionReady")->GetResult() ? true : false;
00197
00198 brakeReport.parking_brake.status = message->GetSignal("DBW_BrakeParkingBrkStatus")->GetResult();
00199
00200 brakeReport.control_type.value = message->GetSignal("DBW_BrakeCtrlType")->GetResult();
00201
00202 pub_brake_.publish(brakeReport);
00203 if (faultCh1 || faultCh2) {
00204 ROS_WARN_THROTTLE(5.0, "Brake fault. FLT1: %s FLT2: %s",
00205 faultCh1 ? "true, " : "false,",
00206 faultCh2 ? "true, " : "false,");
00207 }
00208 }
00209 }
00210 break;
00211
00212 case ID_ACCEL_PEDAL_REPORT:
00213 {
00214 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_ACCEL_PEDAL_REPORT);
00215 if (msg->dlc >= message->GetDlc()) {
00216
00217 message->SetFrame(msg);
00218
00219 bool faultCh1 = message->GetSignal("DBW_AccelPdlFault_Ch1")->GetResult() ? true : false;
00220 bool faultCh2 = message->GetSignal("DBW_AccelPdlFault_Ch2")->GetResult() ? true : false;
00221 bool accelPdlSystemFault = message->GetSignal("DBW_AccelPdlFault")->GetResult() ? true : false;
00222 bool dbwSystemFault = accelPdlSystemFault;
00223
00224 uint16_t positionFeedback = message->GetSignal("DBW_AccelPdlPosnFdbck")->GetResult();
00225
00226 faultAcceleratorPedal(faultCh1 && faultCh2);
00227 faultWatchdog(dbwSystemFault, accelPdlSystemFault);
00228
00229 overrideAcceleratorPedal(message->GetSignal("DBW_AccelPdlDriverActivity")->GetResult());
00230
00231 dbw_pacifica_msgs::AcceleratorPedalReport accelPedalReprt;
00232 accelPedalReprt.header.stamp = msg->header.stamp;
00233 accelPedalReprt.pedal_input = message->GetSignal("DBW_AccelPdlDriverInput")->GetResult();
00234 accelPedalReprt.pedal_output = message->GetSignal("DBW_AccelPdlPosnFdbck")->GetResult();
00235 accelPedalReprt.enabled = message->GetSignal("DBW_AccelPdlEnabled")->GetResult() ? true : false;
00236 accelPedalReprt.ignore_driver = message->GetSignal("DBW_AccelPdlIgnoreDriver")->GetResult() ? true : false;
00237 accelPedalReprt.driver_activity = message->GetSignal("DBW_AccelPdlDriverActivity")->GetResult() ? true : false;
00238 accelPedalReprt.torque_actual = message->GetSignal("DBW_AccelPcntTorqueActual")->GetResult();
00239
00240 accelPedalReprt.control_type.value = message->GetSignal("DBW_AccelCtrlType")->GetResult();
00241
00242 accelPedalReprt.rolling_counter = message->GetSignal("DBW_AccelPdlRollingCntr")->GetResult();
00243
00244 accelPedalReprt.fault_accel_pedal_system = accelPdlSystemFault;
00245
00246 accelPedalReprt.fault_ch1 = faultCh1;
00247 accelPedalReprt.fault_ch2 = faultCh2;
00248
00249 pub_accel_pedal_.publish(accelPedalReprt);
00250
00251 if (faultCh1 || faultCh2) {
00252 ROS_WARN_THROTTLE(5.0, "Accelerator Pedal fault. FLT1: %s FLT2: %s",
00253 faultCh1 ? "true, " : "false,",
00254 faultCh2 ? "true, " : "false,");
00255 }
00256 }
00257 }
00258 break;
00259
00260 case ID_STEERING_REPORT:
00261 {
00262 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_STEERING_REPORT);
00263 if (msg->dlc >= message->GetDlc()) {
00264
00265 message->SetFrame(msg);
00266
00267 bool steeringSystemFault = message->GetSignal("DBW_SteeringFault")->GetResult() ? true : false;
00268 bool dbwSystemFault = steeringSystemFault;
00269
00270 faultSteering(steeringSystemFault);
00271
00272 faultWatchdog(dbwSystemFault);
00273 overrideSteering(message->GetSignal("DBW_SteeringDriverActivity")->GetResult() ? true : false);
00274
00275 dbw_pacifica_msgs::SteeringReport steeringReport;
00276 steeringReport.header.stamp = msg->header.stamp;
00277 steeringReport.steering_wheel_angle = message->GetSignal("DBW_SteeringWhlAngleAct")->GetResult() * (M_PI / 180);
00278 steeringReport.steering_wheel_angle_cmd = message->GetSignal("DBW_SteeringWhlAngleDes")->GetResult() * (M_PI / 180);
00279 steeringReport.steering_wheel_torque = message->GetSignal("DBW_SteeringWhlPcntTrqCmd")->GetResult() * 0.0625;
00280
00281 steeringReport.enabled = message->GetSignal("DBW_SteeringEnabled")->GetResult() ? true : false;
00282 steeringReport.driver_activity = message->GetSignal("DBW_SteeringDriverActivity")->GetResult() ? true : false;
00283
00284 steeringReport.rolling_counter = message->GetSignal("DBW_SteeringRollingCntr")->GetResult();
00285
00286 steeringReport.control_type.value = message->GetSignal("DBW_SteeringCtrlType")->GetResult();
00287
00288 steeringReport.overheat_prevention_mode = message->GetSignal("DBW_OverheatPreventMode")->GetResult() ? true : false;
00289
00290 steeringReport.steering_overheat_warning = message->GetSignal("DBW_SteeringOverheatWarning")->GetResult() ? true : false;
00291
00292 steeringReport.fault_steering_system = steeringSystemFault;
00293
00294 pub_steering_.publish(steeringReport);
00295
00296 publishJointStates(msg->header.stamp, NULL, &steeringReport);
00297
00298 if (steeringSystemFault) {
00299 ROS_WARN_THROTTLE(5.0, "Steering fault: %s",
00300 steeringSystemFault ? "true, " : "false,");
00301 }
00302 }
00303 }
00304 break;
00305
00306 case ID_GEAR_REPORT:
00307 {
00308 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_GEAR_REPORT);
00309
00310 if (msg->dlc >= 1) {
00311
00312 message->SetFrame(msg);
00313
00314 bool driverActivity = message->GetSignal("DBW_PrndDriverActivity")->GetResult() ? true : false;
00315
00316 overrideGear(driverActivity);
00317 dbw_pacifica_msgs::GearReport out;
00318 out.header.stamp = msg->header.stamp;
00319
00320 out.enabled = message->GetSignal("DBW_PrndCtrlEnabled")->GetResult() ? true : false;
00321 out.state.gear = message->GetSignal("DBW_PrndStateActual")->GetResult();
00322 out.driver_activity = driverActivity;
00323 out.gear_select_system_fault = message->GetSignal("DBW_PrndFault")->GetResult() ? true : false;
00324
00325 out.reject = message->GetSignal("DBW_PrndStateReject")->GetResult() ? true : false;
00326
00327 pub_gear_.publish(out);
00328 }
00329 }
00330 break;
00331
00332 case ID_REPORT_WHEEL_SPEED:
00333 {
00334 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_REPORT_WHEEL_SPEED);
00335
00336 if (msg->dlc >= message->GetDlc()) {
00337 message->SetFrame(msg);
00338
00339 dbw_pacifica_msgs::WheelSpeedReport out;
00340 out.header.stamp = msg->header.stamp;
00341
00342 out.front_left = message->GetSignal("DBW_WhlSpd_FL")->GetResult();
00343 out.front_right = message->GetSignal("DBW_WhlSpd_FR")->GetResult();
00344 out.rear_left = message->GetSignal("DBW_WhlSpd_RL")->GetResult();
00345 out.rear_right = message->GetSignal("DBW_WhlSpd_RR")->GetResult();
00346
00347 pub_wheel_speeds_.publish(out);
00348 publishJointStates(msg->header.stamp, &out, NULL);
00349 }
00350 }
00351 break;
00352
00353 case ID_REPORT_WHEEL_POSITION:
00354 {
00355 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_REPORT_WHEEL_POSITION);
00356 if (msg->dlc >= message->GetDlc()) {
00357
00358 message->SetFrame(msg);
00359
00360 dbw_pacifica_msgs::WheelPositionReport out;
00361 out.header.stamp = msg->header.stamp;
00362 out.front_left = message->GetSignal("DBW_WhlPulseCnt_FL")->GetResult();
00363 out.front_right = message->GetSignal("DBW_WhlPulseCnt_FR")->GetResult();
00364 out.rear_left = message->GetSignal("DBW_WhlPulseCnt_RL")->GetResult();
00365 out.rear_right = message->GetSignal("DBW_WhlPulseCnt_RR")->GetResult();
00366 out.wheel_pulses_per_rev = message->GetSignal("DBW_WhlPulsesPerRev")->GetResult();
00367
00368 pub_wheel_positions_.publish(out);
00369 }
00370 }
00371 break;
00372
00373 case ID_REPORT_TIRE_PRESSURE:
00374 {
00375 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_REPORT_TIRE_PRESSURE);
00376
00377 if (msg->dlc >= message->GetDlc()) {
00378
00379 message->SetFrame(msg);
00380
00381 dbw_pacifica_msgs::TirePressureReport out;
00382 out.header.stamp = msg->header.stamp;
00383 out.front_left = message->GetSignal("DBW_TirePressFL")->GetResult();
00384 out.front_right = message->GetSignal("DBW_TirePressFR")->GetResult();
00385 out.rear_left = message->GetSignal("DBW_TirePressRL")->GetResult();
00386 out.rear_right = message->GetSignal("DBW_TirePressRR")->GetResult();
00387 pub_tire_pressure_.publish(out);
00388 }
00389 }
00390 break;
00391
00392 case ID_REPORT_SURROUND:
00393 {
00394 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_REPORT_SURROUND);
00395
00396 if (msg->dlc >= message->GetDlc()) {
00397
00398 message->SetFrame(msg);
00399
00400 dbw_pacifica_msgs::SurroundReport out;
00401 out.header.stamp = msg->header.stamp;
00402
00403 out.front_radar_object_distance = message->GetSignal("DBW_Reserved2")->GetResult();
00404 out.rear_radar_object_distance = message->GetSignal("DBW_SonarRearDist")->GetResult();
00405
00406 out.front_radar_distance_valid = message->GetSignal("DBW_Reserved3")->GetResult() ? true : false;
00407 out.parking_sonar_data_valid = message->GetSignal("DBW_SonarVld")->GetResult() ? true : false;
00408
00409 out.rear_right.status = message->GetSignal("DBW_SonarArcNumRR")->GetResult();
00410 out.rear_left.status = message->GetSignal("DBW_SonarArcNumRL")->GetResult();
00411 out.rear_center.status = message->GetSignal("DBW_SonarArcNumRC")->GetResult();
00412
00413 out.front_right.status = message->GetSignal("DBW_SonarArcNumFR")->GetResult();
00414 out.front_left.status = message->GetSignal("DBW_SonarArcNumFL")->GetResult();
00415 out.front_center.status = message->GetSignal("DBW_SonarArcNumFC")->GetResult();
00416
00417 pub_surround_.publish(out);
00418 }
00419 }
00420 break;
00421
00422 case ID_VIN:
00423 {
00424 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_VIN);
00425
00426 if (msg->dlc >= message->GetDlc()) {
00427
00428 message->SetFrame(msg);
00429
00430 if (message->GetSignal("DBW_VinMultiplexor")->GetResult() == VIN_MUX_VIN0) {
00431 vin_.push_back(message->GetSignal("DBW_VinDigit_01")->GetResult());
00432 vin_.push_back(message->GetSignal("DBW_VinDigit_02")->GetResult());
00433 vin_.push_back(message->GetSignal("DBW_VinDigit_03")->GetResult());
00434 vin_.push_back(message->GetSignal("DBW_VinDigit_04")->GetResult());
00435 vin_.push_back(message->GetSignal("DBW_VinDigit_05")->GetResult());
00436 vin_.push_back(message->GetSignal("DBW_VinDigit_06")->GetResult());
00437 vin_.push_back(message->GetSignal("DBW_VinDigit_07")->GetResult());
00438 } else if (message->GetSignal("DBW_VinMultiplexor")->GetResult() == VIN_MUX_VIN1) {
00439 vin_.push_back(message->GetSignal("DBW_VinDigit_08")->GetResult());
00440 vin_.push_back(message->GetSignal("DBW_VinDigit_09")->GetResult());
00441 vin_.push_back(message->GetSignal("DBW_VinDigit_10")->GetResult());
00442 vin_.push_back(message->GetSignal("DBW_VinDigit_11")->GetResult());
00443 vin_.push_back(message->GetSignal("DBW_VinDigit_12")->GetResult());
00444 vin_.push_back(message->GetSignal("DBW_VinDigit_13")->GetResult());
00445 vin_.push_back(message->GetSignal("DBW_VinDigit_14")->GetResult());
00446 } else if (message->GetSignal("DBW_VinMultiplexor")->GetResult() == VIN_MUX_VIN2) {
00447 vin_.push_back(message->GetSignal("DBW_VinDigit_15")->GetResult());
00448 vin_.push_back(message->GetSignal("DBW_VinDigit_16")->GetResult());
00449 vin_.push_back(message->GetSignal("DBW_VinDigit_17")->GetResult());
00450 std_msgs::String msg; msg.data = vin_;
00451 pub_vin_.publish(msg);
00452
00453 }
00454 }
00455 }
00456 break;
00457
00458 case ID_REPORT_IMU:
00459 {
00460 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_REPORT_IMU);
00461
00462 if (msg->dlc >= message->GetDlc()) {
00463
00464 message->SetFrame(msg);
00465
00466 sensor_msgs::Imu out;
00467 out.header.stamp = msg->header.stamp;
00468 out.header.frame_id = frame_id_;
00469
00470 out.angular_velocity.z = (double)message->GetSignal("DBW_ImuYawRate")->GetResult() * (M_PI / 180.0);
00471
00472 out.linear_acceleration.x = (double)message->GetSignal("DBW_ImuAccelX")->GetResult();
00473 out.linear_acceleration.y = (double)message->GetSignal("DBW_ImuAccelY")->GetResult();
00474
00475 pub_imu_.publish(out);
00476 }
00477 }
00478 break;
00479
00480 case ID_REPORT_DRIVER_INPUT:
00481 {
00482 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_REPORT_DRIVER_INPUT);
00483
00484 if (msg->dlc >= message->GetDlc()) {
00485
00486 message->SetFrame(msg);
00487
00488 dbw_pacifica_msgs::DriverInputReport out;
00489 out.header.stamp = msg->header.stamp;
00490
00491 out.turn_signal.value = message->GetSignal("DBW_DrvInptTurnSignal")->GetResult();
00492 out.high_beam_headlights.status = message->GetSignal("DBW_DrvInptHiBeam")->GetResult();
00493 out.wiper.status = message->GetSignal("DBW_DrvInptWiper")->GetResult();
00494
00495 out.cruise_resume_button = message->GetSignal("DBW_DrvInptCruiseResumeBtn")->GetResult() ? true : false;
00496 out.cruise_cancel_button = message->GetSignal("DBW_DrvInptCruiseCancelBtn")->GetResult() ? true : false;
00497 out.cruise_accel_button = message->GetSignal("DBW_DrvInptCruiseAccelBtn")->GetResult() ? true : false;
00498 out.cruise_decel_button = message->GetSignal("DBW_DrvInptCruiseDecelBtn")->GetResult() ? true : false;
00499 out.cruise_on_off_button = message->GetSignal("DBW_DrvInptCruiseOnOffBtn")->GetResult() ? true : false;
00500
00501 out.adaptive_cruise_on_off_button = message->GetSignal("DBW_DrvInptAccOnOffBtn")->GetResult() ? true : false;
00502 out.adaptive_cruise_increase_distance_button = message->GetSignal("DBW_DrvInptAccIncDistBtn")->GetResult() ? true : false;
00503 out.adaptive_cruise_decrease_distance_button = message->GetSignal("DBW_DrvInptAccDecDistBtn")->GetResult() ? true : false;
00504
00505 out.door_or_hood_ajar = message->GetSignal("DBW_OccupAnyDoorOrHoodAjar")->GetResult() ? true : false;
00506
00507 out.airbag_deployed = message->GetSignal("DBW_OccupAnyAirbagDeployed")->GetResult() ? true : false;
00508 out.any_seatbelt_unbuckled = message->GetSignal("DBW_OccupAnySeatbeltUnbuckled")->GetResult() ? true : false;
00509
00510 pub_driver_input_.publish(out);
00511 }
00512 }
00513 break;
00514
00515 case ID_MISC_REPORT:
00516 {
00517 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_MISC_REPORT);
00518
00519 if (msg->dlc >= message->GetDlc()) {
00520
00521 message->SetFrame(msg);
00522
00523 dbw_pacifica_msgs::MiscReport out;
00524 out.header.stamp = msg->header.stamp;
00525
00526 out.fuel_level = (double)message->GetSignal("DBW_MiscFuelLvl")->GetResult();
00527
00528 out.drive_by_wire_enabled = (bool)message->GetSignal("DBW_MiscByWireEnabled")->GetResult();
00529 out.vehicle_speed = (double)message->GetSignal("DBW_MiscVehicleSpeed")->GetResult();
00530
00531 out.software_build_number = message->GetSignal("DBW_SoftwareBuildNumber")->GetResult();
00532 out.general_actuator_fault = message->GetSignal("DBW_MiscFault")->GetResult() ? true : false;
00533 out.by_wire_ready = message->GetSignal("DBW_MiscByWireReady")->GetResult() ? true : false;
00534 out.general_driver_activity = message->GetSignal("DBW_MiscDriverActivity")->GetResult() ? true : false;
00535 out.comms_fault = message->GetSignal("DBW_MiscAKitCommFault")->GetResult() ? true : false;
00536
00537 out.ambient_temp = (double)message->GetSignal("DBW_AmbientTemp")->GetResult();
00538
00539 pub_misc_.publish(out);
00540 }
00541 }
00542 break;
00543
00544 case ID_LOW_VOLTAGE_SYSTEM_REPORT:
00545 {
00546 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_LOW_VOLTAGE_SYSTEM_REPORT);
00547
00548 if (msg->dlc >= message->GetDlc()) {
00549
00550 message->SetFrame(msg);
00551
00552 dbw_pacifica_msgs::LowVoltageSystemReport lvSystemReport;
00553 lvSystemReport.header.stamp = msg->header.stamp;
00554
00555 lvSystemReport.vehicle_battery_volts = (double)message->GetSignal("DBW_LvVehBattVlt")->GetResult();
00556 lvSystemReport.vehicle_battery_current = (double)message->GetSignal("DBW_LvBattCurr")->GetResult();
00557 lvSystemReport.vehicle_alternator_current = (double)message->GetSignal("DBW_LvAlternatorCurr")->GetResult();
00558
00559 lvSystemReport.dbw_battery_volts = (double)message->GetSignal("DBW_LvDbwBattVlt")->GetResult();
00560 lvSystemReport.dcdc_current = (double)message->GetSignal("DBW_LvDcdcCurr")->GetResult();
00561
00562 lvSystemReport.aux_inverter_contactor = message->GetSignal("DBW_LvInvtrContactorCmd")->GetResult() ? true : false;
00563
00564 pub_low_voltage_system_.publish(lvSystemReport);
00565 }
00566 }
00567 break;
00568
00569 case ID_BRAKE_2_REPORT:
00570 {
00571 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_BRAKE_2_REPORT);
00572
00573 if (msg->dlc >= message->GetDlc()) {
00574 message->SetFrame(msg);
00575
00576 dbw_pacifica_msgs::Brake2Report brake2Report;
00577 brake2Report.header.stamp = msg->header.stamp;
00578
00579 brake2Report.brake_pressure = message->GetSignal("DBW_BrakePress_bar")->GetResult();
00580
00581 brake2Report.estimated_road_slope = message->GetSignal("DBW_RoadSlopeEstimate")->GetResult();
00582
00583 brake2Report.speed_set_point = message->GetSignal("DBW_SpeedSetpt")->GetResult();
00584
00585 pub_brake_2_report_.publish(brake2Report);
00586 }
00587 }
00588 break;
00589
00590 case ID_STEERING_2_REPORT:
00591 {
00592 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_STEERING_2_REPORT);
00593
00594 if (msg->dlc >= message->GetDlc()) {
00595 message->SetFrame(msg);
00596
00597 dbw_pacifica_msgs::Steering2Report steering2Report;
00598 steering2Report.header.stamp = msg->header.stamp;
00599
00600 steering2Report.vehicle_curvature_actual = message->GetSignal("DBW_SteeringVehCurvatureAct")->GetResult();
00601
00602 steering2Report.max_torque_driver = message->GetSignal("DBW_SteerTrq_Driver")->GetResult();
00603
00604 steering2Report.max_torque_motor = message->GetSignal("DBW_SteerTrq_Motor")->GetResult();
00605
00606 pub_steering_2_report_.publish(steering2Report);
00607 }
00608 }
00609 break;
00610
00611 case ID_FAULT_ACTION_REPORT:
00612 {
00613 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_FAULT_ACTION_REPORT);
00614
00615 if (msg->dlc >= message->GetDlc()) {
00616 message->SetFrame(msg);
00617
00618 dbw_pacifica_msgs::FaultActionsReport faultActionsReport;
00619 faultActionsReport.header.stamp = msg->header.stamp;
00620
00621 faultActionsReport.autonomous_disabled_no_brakes = message->GetSignal("DBW_FltAct_AutonDsblNoBrakes")->GetResult();
00622
00623 faultActionsReport.autonomous_disabled_apply_brakes = message->GetSignal("DBW_FltAct_AutonDsblApplyBrakes")->GetResult();
00624 faultActionsReport.can_gateway_disabled = message->GetSignal("DBW_FltAct_CANGatewayDsbl")->GetResult();
00625 faultActionsReport.inverter_contactor_disabled = message->GetSignal("DBW_FltAct_InvtrCntctrDsbl")->GetResult();
00626 faultActionsReport.prevent_enter_autonomous_mode = message->GetSignal("DBW_FltAct_PreventEnterAutonMode")->GetResult();
00627 faultActionsReport.warn_driver_only = message->GetSignal("DBW_FltAct_WarnDriverOnly")->GetResult();
00628
00629 pub_fault_actions_report_.publish(faultActionsReport);
00630 }
00631 }
00632 break;
00633
00634 case ID_HMI_GLOBAL_ENABLE_REPORT:
00635 {
00636 NewEagle::DbcMessage* message = dbwDbc_.GetMessageById(ID_HMI_GLOBAL_ENABLE_REPORT);
00637
00638 if (msg->dlc >= message->GetDlc()) {
00639 message->SetFrame(msg);
00640
00641 dbw_pacifica_msgs::HmiGlobalEnableReport hmiGlobalEnableReport;
00642 hmiGlobalEnableReport.header.stamp = msg->header.stamp;
00643
00644 hmiGlobalEnableReport.enable_request = message->GetSignal("HMI_GlobalByWireEnblReq")->GetResult();
00645
00646 hmiGlobalEnableReport.disable_request = message->GetSignal("HMI_GlobalByWireDisblReq")->GetResult();
00647 hmiGlobalEnableReport.checksum = message->GetSignal("HMI_GlobalEnblChecksum")->GetResult();
00648 hmiGlobalEnableReport.ecu_build_number = message->GetSignal("HMI_SoftwareBuildNumber")->GetResult();
00649 hmiGlobalEnableReport.rolling_counter = message->GetSignal("HMI_GlobalEnblRollingCntr")->GetResult();
00650
00651 pub_hmi_global_enable_report_.publish(hmiGlobalEnableReport);
00652 }
00653 }
00654 break;
00655
00656 case ID_BRAKE_CMD:
00657
00658 break;
00659 case ID_ACCELERATOR_PEDAL_CMD:
00660
00661 break;
00662 case ID_STEERING_CMD:
00663
00664 break;
00665 case ID_GEAR_CMD:
00666
00667 break;
00668 }
00669 }
00670 #if 0
00671 ROS_INFO("ena: %s, clr: %s, brake: %s, Accelerator Pedal: %s, steering: %s, gear: %s",
00672 enabled() ? "true " : "false",
00673 clear() ? "true " : "false",
00674 override_brake_ ? "true " : "false",
00675 override_accelerator_pedal_ ? "true " : "false",
00676 override_steering_ ? "true " : "false",
00677 override_gear_ ? "true " : "false"
00678 );
00679 #endif
00680 }
00681
00682 void DbwNode::recvBrakeCmd(const dbw_pacifica_msgs::BrakeCmd::ConstPtr& msg)
00683 {
00684 NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_BrakeRequest");
00685
00686 message->GetSignal("AKit_BrakePedalReq")->SetResult(0);
00687 message->GetSignal("AKit_BrakeCtrlEnblReq")->SetResult(0);
00688 message->GetSignal("AKit_BrakeCtrlReqType")->SetResult(0);
00689 message->GetSignal("AKit_BrakePcntTorqueReq")->SetResult(0);
00690 message->GetSignal("AKit_SpeedModeDecelLim")->SetResult(0);
00691 message->GetSignal("AKit_SpeedModeNegJerkLim")->SetResult(0);
00692
00693 if (enabled()) {
00694 if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::open_loop) {
00695 message->GetSignal("AKit_BrakeCtrlReqType")->SetResult(0);
00696 message->GetSignal("AKit_BrakePedalReq")->SetResult(msg->pedal_cmd);
00697 } else if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::closed_loop_actuator) {
00698 message->GetSignal("AKit_BrakeCtrlReqType")->SetResult(1);
00699 message->GetSignal("AKit_BrakePcntTorqueReq")->SetResult(msg->torque_cmd);
00700 } else if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::closed_loop_vehicle) {
00701 message->GetSignal("AKit_BrakeCtrlReqType")->SetResult(2);
00702 message->GetSignal("AKit_SpeedModeDecelLim")->SetResult(msg->decel_limit);
00703 message->GetSignal("AKit_SpeedModeNegJerkLim")->SetResult(msg->decel_negative_jerk_limit);
00704 } else {
00705 message->GetSignal("AKit_BrakeCtrlReqType")->SetResult(0);
00706 }
00707
00708 if(msg->enable) {
00709 message->GetSignal("AKit_BrakeCtrlEnblReq")->SetResult(1);
00710 }
00711
00712 }
00713
00714 NewEagle::DbcSignal* cnt = message->GetSignal("AKit_BrakeRollingCntr");
00715 cnt->SetResult(msg->rolling_counter);
00716
00717 can_msgs::Frame frame = message->GetFrame();
00718
00719 pub_can_.publish(frame);
00720 }
00721
00722 void DbwNode::recvAcceleratorPedalCmd(const dbw_pacifica_msgs::AcceleratorPedalCmd::ConstPtr& msg)
00723 {
00724 NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_AccelPdlRequest");
00725
00726 message->GetSignal("AKit_AccelPdlReq")->SetResult(0);
00727 message->GetSignal("AKit_AccelPdlEnblReq")->SetResult(0);
00728 message->GetSignal("Akit_AccelPdlIgnoreDriverOvrd")->SetResult(0);
00729 message->GetSignal("AKit_AccelPdlRollingCntr")->SetResult(0);
00730 message->GetSignal("AKit_AccelReqType")->SetResult(0);
00731 message->GetSignal("AKit_AccelPcntTorqueReq")->SetResult(0);
00732 message->GetSignal("AKit_AccelPdlChecksum")->SetResult(0);
00733 message->GetSignal("AKit_SpeedReq")->SetResult(0);
00734 message->GetSignal("AKit_SpeedModeRoadSlope")->SetResult(0);
00735 message->GetSignal("AKit_SpeedModeAccelLim")->SetResult(0);
00736 message->GetSignal("AKit_SpeedModePosJerkLim")->SetResult(0);
00737
00738 if (enabled()) {
00739
00740 if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::open_loop) {
00741 message->GetSignal("AKit_AccelReqType")->SetResult(0);
00742 message->GetSignal("AKit_AccelPdlReq")->SetResult(msg->pedal_cmd);
00743 } else if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::closed_loop_actuator) {
00744 message->GetSignal("AKit_AccelReqType")->SetResult(1);
00745 message->GetSignal("AKit_AccelPcntTorqueReq")->SetResult(msg->torque_cmd);
00746 } else if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::closed_loop_vehicle) {
00747 message->GetSignal("AKit_AccelReqType")->SetResult(2);
00748
00749 message->GetSignal("AKit_SpeedReq")->SetResult(msg->speed_cmd);
00750 message->GetSignal("AKit_SpeedModeRoadSlope")->SetResult(msg->road_slope);
00751 message->GetSignal("AKit_SpeedModeAccelLim")->SetResult(msg->accel_limit);
00752 message->GetSignal("AKit_SpeedModePosJerkLim")->SetResult(msg->accel_positive_jerk_limit);
00753 } else {
00754 message->GetSignal("AKit_AccelReqType")->SetResult(0);
00755 }
00756
00757 if(msg->enable) {
00758 message->GetSignal("AKit_AccelPdlEnblReq")->SetResult(1);
00759 }
00760 }
00761
00762 NewEagle::DbcSignal* cnt = message->GetSignal("AKit_AccelPdlRollingCntr");
00763 cnt->SetResult(msg->rolling_counter);
00764
00765 if (msg->ignore) {
00766 message->GetSignal("Akit_AccelPdlIgnoreDriverOvrd")->SetResult(1);
00767 }
00768
00769 can_msgs::Frame frame = message->GetFrame();
00770
00771 pub_can_.publish(frame);
00772 }
00773
00774 void DbwNode::recvSteeringCmd(const dbw_pacifica_msgs::SteeringCmd::ConstPtr& msg)
00775 {
00776 NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_SteeringRequest");
00777
00778 message->GetSignal("AKit_SteeringWhlAngleReq")->SetResult(0);
00779 message->GetSignal("AKit_SteeringWhlAngleVelocityLim")->SetResult(0);
00780 message->GetSignal("AKit_SteerCtrlEnblReq")->SetResult(0);
00781 message->GetSignal("AKit_SteeringWhlIgnoreDriverOvrd")->SetResult(0);
00782 message->GetSignal("AKit_SteeringWhlPcntTrqReq")->SetResult(0);
00783 message->GetSignal("AKit_SteeringReqType")->SetResult(0);
00784 message->GetSignal("AKit_SteeringVehCurvatureReq")->SetResult(0);
00785 message->GetSignal("AKit_SteeringChecksum")->SetResult(0);
00786
00787 if (enabled()) {
00788 if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::open_loop) {
00789 message->GetSignal("AKit_SteeringReqType")->SetResult(0);
00790 message->GetSignal("AKit_SteeringWhlPcntTrqReq")->SetResult(msg->torque_cmd);
00791 } else if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::closed_loop_actuator) {
00792 message->GetSignal("AKit_SteeringReqType")->SetResult(1);
00793 double scmd = std::max((float)-470.0, std::min((float)470.0, (float)(msg->angle_cmd * (180 / M_PI * 1.0))));
00794 message->GetSignal("AKit_SteeringWhlAngleReq")->SetResult(scmd);
00795 } else if (msg->control_type.value == dbw_pacifica_msgs::ActuatorControlMode::closed_loop_vehicle) {
00796 message->GetSignal("AKit_SteeringReqType")->SetResult(2);
00797 message->GetSignal("AKit_SteeringVehCurvatureReq")->SetResult(msg->vehicle_curvature_cmd);
00798 } else {
00799 message->GetSignal("AKit_SteeringReqType")->SetResult(0);
00800 }
00801
00802 if (fabsf(msg->angle_velocity) > 0)
00803 {
00804 uint16_t vcmd = std::max((float)1, std::min((float)254, (float)roundf(fabsf(msg->angle_velocity) * 180 / M_PI / 2)));
00805
00806 message->GetSignal("AKit_SteeringWhlAngleVelocityLim")->SetResult(vcmd);
00807 }
00808 if(msg->enable) {
00809 message->GetSignal("AKit_SteerCtrlEnblReq")->SetResult(1);
00810 }
00811 }
00812
00813 if (msg->ignore) {
00814 message->GetSignal("AKit_SteeringWhlIgnoreDriverOvrd")->SetResult(1);
00815 }
00816
00817 message->GetSignal("AKit_SteerRollingCntr")->SetResult(msg->rolling_counter);
00818
00819 can_msgs::Frame frame = message->GetFrame();
00820
00821 pub_can_.publish(frame);
00822 }
00823
00824 void DbwNode::recvGearCmd(const dbw_pacifica_msgs::GearCmd::ConstPtr& msg)
00825 {
00826 NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_PrndRequest");
00827
00828 message->GetSignal("AKit_PrndCtrlEnblReq")->SetResult(0);
00829 message->GetSignal("AKit_PrndStateReq")->SetResult(0);
00830 message->GetSignal("AKit_PrndChecksum")->SetResult(0);
00831
00832 if (enabled()) {
00833 if(msg->enable)
00834 {
00835 message->GetSignal("AKit_PrndCtrlEnblReq")->SetResult(1);
00836 }
00837
00838 message->GetSignal("AKit_PrndStateReq")->SetResult(msg->cmd.gear);
00839 }
00840
00841 message->GetSignal("AKit_PrndRollingCntr")->SetResult(msg->rolling_counter);
00842
00843 can_msgs::Frame frame = message->GetFrame();
00844
00845 pub_can_.publish(frame);
00846 }
00847
00848 void DbwNode::recvGlobalEnableCmd(const dbw_pacifica_msgs::GlobalEnableCmd::ConstPtr& msg)
00849 {
00850 NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_GlobalEnbl");
00851
00852 message->GetSignal("AKit_GlobalEnblRollingCntr")->SetResult(0);
00853 message->GetSignal("AKit_GlobalByWireEnblReq")->SetResult(0);
00854 message->GetSignal("AKit_EnblJoystickLimits")->SetResult(0);
00855 message->GetSignal("AKit_SoftwareBuildNumber")->SetResult(0);
00856 message->GetSignal("Akit_GlobalEnblChecksum")->SetResult(0);
00857
00858 if (enabled()) {
00859 if(msg->global_enable) {
00860 message->GetSignal("AKit_GlobalByWireEnblReq")->SetResult(1);
00861 }
00862
00863 if(msg->enable_joystick_limits) {
00864 message->GetSignal("AKit_EnblJoystickLimits")->SetResult(1);
00865 }
00866
00867 message->GetSignal("AKit_SoftwareBuildNumber")->SetResult(msg->ecu_build_number);
00868 }
00869
00870 message->GetSignal("AKit_GlobalEnblRollingCntr")->SetResult(msg->rolling_counter);
00871
00872 can_msgs::Frame frame = message->GetFrame();
00873
00874 pub_can_.publish(frame);
00875 }
00876
00877 void DbwNode::recvMiscCmd(const dbw_pacifica_msgs::MiscCmd::ConstPtr& msg)
00878 {
00879 NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_OtherActuators");
00880
00881 message->GetSignal("AKit_TurnSignalReq")->SetResult(0);
00882 message->GetSignal("AKit_RightRearDoorReq")->SetResult(0);
00883 message->GetSignal("AKit_HighBeamReq")->SetResult(0);
00884 message->GetSignal("AKit_FrontWiperReq")->SetResult(0);
00885 message->GetSignal("AKit_RearWiperReq")->SetResult(0);
00886 message->GetSignal("AKit_IgnitionReq")->SetResult(0);
00887 message->GetSignal("AKit_LeftRearDoorReq")->SetResult(0);
00888 message->GetSignal("AKit_LiftgateDoorReq")->SetResult(0);
00889 message->GetSignal("AKit_BlockBasicCruiseCtrlBtns")->SetResult(0);
00890 message->GetSignal("AKit_BlockAdapCruiseCtrlBtns")->SetResult(0);
00891 message->GetSignal("AKit_BlockTurnSigStalkInpts")->SetResult(0);
00892 message->GetSignal("AKit_OtherChecksum")->SetResult(0);
00893 message->GetSignal("AKit_HornReq")->SetResult(0);
00894 message->GetSignal("AKit_LowBeamReq")->SetResult(0);
00895
00896 if (enabled()) {
00897
00898 message->GetSignal("AKit_TurnSignalReq")->SetResult(msg->cmd.value);
00899
00900 message->GetSignal("AKit_RightRearDoorReq")->SetResult(msg->door_request_right_rear.value);
00901 message->GetSignal("AKit_HighBeamReq")->SetResult(msg->high_beam_cmd.status);
00902
00903 message->GetSignal("AKit_FrontWiperReq")->SetResult(msg->front_wiper_cmd.status);
00904 message->GetSignal("AKit_RearWiperReq")->SetResult(msg->rear_wiper_cmd.status);
00905
00906 message->GetSignal("AKit_IgnitionReq")->SetResult(msg->ignition_cmd.status);
00907
00908 message->GetSignal("AKit_LeftRearDoorReq")->SetResult(msg->door_request_left_rear.value);
00909 message->GetSignal("AKit_LiftgateDoorReq")->SetResult(msg->door_request_lift_gate.value);
00910
00911 message->GetSignal("AKit_BlockBasicCruiseCtrlBtns")->SetResult(msg->block_standard_cruise_buttons);
00912 message->GetSignal("AKit_BlockAdapCruiseCtrlBtns")->SetResult(msg->block_adaptive_cruise_buttons);
00913 message->GetSignal("AKit_BlockTurnSigStalkInpts")->SetResult(msg->block_turn_signal_stalk);
00914
00915 message->GetSignal("AKit_HornReq")->SetResult(msg->horn_cmd);
00916 message->GetSignal("AKit_LowBeamReq")->SetResult(msg->low_beam_cmd.status);
00917 }
00918
00919 message->GetSignal("AKit_OtherRollingCntr")->SetResult(msg->rolling_counter);
00920
00921 can_msgs::Frame frame = message->GetFrame();
00922
00923 pub_can_.publish(frame);
00924 }
00925
00926 bool DbwNode::publishDbwEnabled()
00927 {
00928 bool change = false;
00929 bool en = enabled();
00930 if (prev_enable_ != en) {
00931 std_msgs::Bool msg;
00932 msg.data = en;
00933 pub_sys_enable_.publish(msg);
00934 change = true;
00935 }
00936 prev_enable_ = en;
00937 return change;
00938 }
00939
00940 void DbwNode::timerCallback(const ros::TimerEvent& event)
00941 {
00942 if (clear()) {
00943 can_msgs::Frame out;
00944 out.is_extended = false;
00945
00946 if (override_brake_) {
00947
00948 NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_BrakeRequest");
00949 message->GetSignal("AKit_BrakePedalReq")->SetResult(0);
00950 message->GetSignal("AKit_BrakeCtrlEnblReq")->SetResult(0);
00951
00952 pub_can_.publish(message->GetFrame());
00953 }
00954
00955 if (override_accelerator_pedal_)
00956 {
00957
00958 NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_AccelPdlRequest");
00959 message->GetSignal("AKit_AccelPdlReq")->SetResult(0);
00960 message->GetSignal("AKit_AccelPdlEnblReq")->SetResult(0);
00961 message->GetSignal("Akit_AccelPdlIgnoreDriverOvrd")->SetResult(0);
00962
00963 pub_can_.publish(message->GetFrame());
00964 }
00965
00966 if (override_steering_) {
00967
00968 NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_SteeringRequest");
00969 message->GetSignal("AKit_SteeringWhlAngleReq")->SetResult(0);
00970 message->GetSignal("AKit_SteeringWhlAngleVelocityLim")->SetResult(0);
00971 message->GetSignal("AKit_SteeringWhlIgnoreDriverOvrd")->SetResult(0);
00972 message->GetSignal("AKit_SteeringWhlPcntTrqReq")->SetResult(0);
00973
00974
00975
00976 pub_can_.publish(message->GetFrame());
00977 }
00978
00979 if (override_gear_) {
00980 NewEagle::DbcMessage* message = dbwDbc_.GetMessage("AKit_GearRequest");
00981 message->GetSignal("AKit_PrndStateCmd")->SetResult(0);
00982 message->GetSignal("AKit_PrndChecksum")->SetResult(0);
00983 pub_can_.publish(message->GetFrame());
00984 }
00985 }
00986 }
00987
00988 void DbwNode::enableSystem()
00989 {
00990 if (!enable_) {
00991 if (fault()) {
00992 if (fault_steering_cal_) {
00993 ROS_WARN("DBW system not enabled. Steering calibration fault.");
00994 }
00995 if (fault_brakes_) {
00996 ROS_WARN("DBW system not enabled. Braking fault.");
00997 }
00998 if (fault_accelerator_pedal_) {
00999 ROS_WARN("DBW system not enabled. Accelerator Pedal fault.");
01000 }
01001 if (fault_steering_) {
01002 ROS_WARN("DBW system not enabled. Steering fault.");
01003 }
01004 if (fault_watchdog_) {
01005 ROS_WARN("DBW system not enabled. Watchdog fault.");
01006 }
01007 } else {
01008 enable_ = true;
01009 if (publishDbwEnabled()) {
01010 ROS_INFO("DBW system enabled.");
01011 } else {
01012 ROS_INFO("DBW system enable requested. Waiting for ready.");
01013 }
01014 }
01015 }
01016 }
01017
01018 void DbwNode::disableSystem()
01019 {
01020 if (enable_) {
01021 enable_ = false;
01022 publishDbwEnabled();
01023 ROS_WARN("DBW system disabled.");
01024 }
01025 }
01026
01027 void DbwNode::buttonCancel()
01028 {
01029 if (enable_) {
01030 enable_ = false;
01031 publishDbwEnabled();
01032 ROS_WARN("DBW system disabled. Cancel button pressed.");
01033 }
01034 }
01035
01036 void DbwNode::overrideBrake(bool override)
01037 {
01038 bool en = enabled();
01039 if (override && en) {
01040 enable_ = false;
01041 }
01042 override_brake_ = override;
01043 if (publishDbwEnabled()) {
01044 if (en) {
01045 ROS_WARN("DBW system disabled. Driver override on brake/Accelerator Pedal pedal.");
01046 } else {
01047 ROS_INFO("DBW system enabled.");
01048 }
01049 }
01050 }
01051
01052 void DbwNode::overrideAcceleratorPedal(bool override)
01053 {
01054 bool en = enabled();
01055 if (override && en) {
01056 enable_ = false;
01057 }
01058 override_accelerator_pedal_ = override;
01059 if (publishDbwEnabled()) {
01060 if (en) {
01061 ROS_WARN("DBW system disabled. Driver override on brake/Accelerator Pedal pedal.");
01062 } else {
01063 ROS_INFO("DBW system enabled.");
01064 }
01065 }
01066 }
01067
01068 void DbwNode::overrideSteering(bool override)
01069 {
01070 bool en = enabled();
01071 if (override && en) {
01072 enable_ = false;
01073 }
01074 override_steering_ = override;
01075 if (publishDbwEnabled()) {
01076 if (en) {
01077 ROS_WARN("DBW system disabled. Driver override on steering wheel.");
01078 } else {
01079 ROS_INFO("DBW system enabled.");
01080 }
01081 }
01082 }
01083
01084 void DbwNode::overrideGear(bool override)
01085 {
01086 bool en = enabled();
01087 if (override && en) {
01088 enable_ = false;
01089 }
01090 override_gear_ = override;
01091 if (publishDbwEnabled()) {
01092 if (en) {
01093 ROS_WARN("DBW system disabled. Driver override on shifter.");
01094 } else {
01095 ROS_INFO("DBW system enabled.");
01096 }
01097 }
01098 }
01099
01100 void DbwNode::timeoutBrake(bool timeout, bool enabled)
01101 {
01102 if (!timeout_brakes_ && enabled_brakes_ && timeout && !enabled) {
01103 ROS_WARN("Brake subsystem disabled after 100ms command timeout");
01104 }
01105 timeout_brakes_ = timeout;
01106 enabled_brakes_ = enabled;
01107 }
01108
01109 void DbwNode::timeoutAcceleratorPedal(bool timeout, bool enabled)
01110 {
01111 if (!timeout_accelerator_pedal_ && enabled_accelerator_pedal_ && timeout && !enabled) {
01112 ROS_WARN("Accelerator Pedal subsystem disabled after 100ms command timeout");
01113 }
01114 timeout_accelerator_pedal_ = timeout;
01115 enabled_accelerator_pedal_ = enabled;
01116 }
01117
01118 void DbwNode::timeoutSteering(bool timeout, bool enabled)
01119 {
01120 if (!timeout_steering_ && enabled_steering_ && timeout && !enabled) {
01121 ROS_WARN("Steering subsystem disabled after 100ms command timeout");
01122 }
01123 timeout_steering_ = timeout;
01124 enabled_steering_ = enabled;
01125 }
01126
01127 void DbwNode::faultBrakes(bool fault)
01128 {
01129 bool en = enabled();
01130 if (fault && en) {
01131 enable_ = false;
01132 }
01133 fault_brakes_ = fault;
01134 if (publishDbwEnabled()) {
01135 if (en) {
01136 ROS_ERROR("DBW system disabled. Braking fault.");
01137 } else {
01138 ROS_INFO("DBW system enabled.");
01139 }
01140 }
01141 }
01142
01143 void DbwNode::faultAcceleratorPedal(bool fault)
01144 {
01145 bool en = enabled();
01146 if (fault && en) {
01147 enable_ = false;
01148 }
01149 fault_accelerator_pedal_ = fault;
01150 if (publishDbwEnabled()) {
01151 if (en) {
01152 ROS_ERROR("DBW system disabled. Accelerator Pedal fault.");
01153 } else {
01154 ROS_INFO("DBW system enabled.");
01155 }
01156 }
01157 }
01158
01159 void DbwNode::faultSteering(bool fault)
01160 {
01161 bool en = enabled();
01162 if (fault && en) {
01163 enable_ = false;
01164 }
01165 fault_steering_ = fault;
01166 if (publishDbwEnabled()) {
01167 if (en) {
01168 ROS_ERROR("DBW system disabled. Steering fault.");
01169 } else {
01170 ROS_INFO("DBW system enabled.");
01171 }
01172 }
01173 }
01174
01175 void DbwNode::faultSteeringCal(bool fault)
01176 {
01177 bool en = enabled();
01178 if (fault && en) {
01179 enable_ = false;
01180 }
01181 fault_steering_cal_ = fault;
01182 if (publishDbwEnabled()) {
01183 if (en) {
01184 ROS_ERROR("DBW system disabled. Steering calibration fault.");
01185 } else {
01186 ROS_INFO("DBW system enabled.");
01187 }
01188 }
01189 }
01190
01191 void DbwNode::faultWatchdog(bool fault, uint8_t src, bool braking)
01192 {
01193 bool en = enabled();
01194 if (fault && en) {
01195 enable_ = false;
01196 }
01197 fault_watchdog_ = fault;
01198 if (publishDbwEnabled()) {
01199 if (en) {
01200 ROS_ERROR("DBW system disabled. Watchdog fault.");
01201 } else {
01202 ROS_INFO("DBW system enabled.");
01203 }
01204 }
01205 if (braking && !fault_watchdog_using_brakes_) {
01206 ROS_WARN("Watchdog event: Alerting driver and applying brakes.");
01207 } else if (!braking && fault_watchdog_using_brakes_) {
01208 ROS_INFO("Watchdog event: Driver has successfully taken control.");
01209 }
01210 if (fault && src && !fault_watchdog_warned_) {
01211 ROS_WARN("Watchdog event: Unknown Fault!");
01212
01213
01214
01215
01216
01217
01218
01219
01220
01221
01222
01223
01224
01225
01226
01227
01228
01229
01230
01231
01232
01233
01234
01235
01236
01237
01238
01239
01240
01241
01242
01243
01244
01245
01246
01247
01248
01249
01250
01251
01252
01253
01254
01255
01256
01257
01258
01259 fault_watchdog_warned_ = true;
01260 } else if (!fault) {
01261 fault_watchdog_warned_ = false;
01262 }
01263 fault_watchdog_using_brakes_ = braking;
01264 if (fault && !fault_watchdog_using_brakes_ && fault_watchdog_warned_) {
01265 ROS_WARN_THROTTLE(2.0, "Watchdog event: Press left OK button on the steering wheel or cycle power to clear event.");
01266 }
01267 }
01268
01269 void DbwNode::faultWatchdog(bool fault, uint8_t src) {
01270 faultWatchdog(fault, src, fault_watchdog_using_brakes_);
01271 }
01272
01273 void DbwNode::publishJointStates(const ros::Time &stamp, const dbw_pacifica_msgs::WheelSpeedReport *wheels, const dbw_pacifica_msgs::SteeringReport *steering)
01274 {
01275 double dt = (stamp - joint_state_.header.stamp).toSec();
01276 if (wheels) {
01277 joint_state_.velocity[JOINT_FL] = wheels->front_left;
01278 joint_state_.velocity[JOINT_FR] = wheels->front_right;
01279 joint_state_.velocity[JOINT_RL] = wheels->rear_left;
01280 joint_state_.velocity[JOINT_RR] = wheels->rear_right;
01281 }
01282 if (steering) {
01283 const double L = acker_wheelbase_;
01284 const double W = acker_track_;
01285 const double r = L / tan(steering->steering_wheel_angle / steering_ratio_);
01286 joint_state_.position[JOINT_SL] = atan(L / (r - W/2));
01287 joint_state_.position[JOINT_SR] = atan(L / (r + W/2));
01288 }
01289 if (dt < 0.5) {
01290 for (unsigned int i = JOINT_FL; i <= JOINT_RR; i++) {
01291 joint_state_.position[i] = fmod(joint_state_.position[i] + dt * joint_state_.velocity[i], 2*M_PI);
01292 }
01293 }
01294 joint_state_.header.stamp = stamp;
01295 pub_joint_states_.publish(joint_state_);
01296 }
01297
01298 }