| 
Public Member Functions | 
|  | DbwNode (ros::NodeHandle &node, ros::NodeHandle &priv_nh) | 
|  | ~DbwNode () | 
| 
Private Types | 
| enum | { JOINT_FL =  0, 
JOINT_FR, 
JOINT_RL, 
JOINT_RR,
 JOINT_SL, 
JOINT_SR, 
JOINT_COUNT
 }
 | 
| 
Private Member Functions | 
| void | buttonCancel () | 
| bool | clear () | 
| void | disableSystem () | 
| bool | enabled () | 
| void | enableSystem () | 
| bool | fault () | 
| void | faultAcceleratorPedal (bool fault) | 
| void | faultBrakes (bool fault) | 
| void | faultSteering (bool fault) | 
| void | faultSteeringCal (bool fault) | 
| void | faultWatchdog (bool fault, uint8_t src, bool braking) | 
| void | faultWatchdog (bool fault, uint8_t src=0) | 
| bool | override () | 
| void | overrideAcceleratorPedal (bool override) | 
| void | overrideBrake (bool override) | 
| void | overrideGear (bool override) | 
| void | overrideSteering (bool override) | 
| bool | publishDbwEnabled () | 
| void | publishJointStates (const ros::Time &stamp, const dbw_pacifica_msgs::WheelSpeedReport *wheels, const dbw_pacifica_msgs::SteeringReport *steering) | 
| void | recvAcceleratorPedalCmd (const dbw_pacifica_msgs::AcceleratorPedalCmd::ConstPtr &msg) | 
| void | recvBrakeCmd (const dbw_pacifica_msgs::BrakeCmd::ConstPtr &msg) | 
| void | recvCAN (const can_msgs::Frame::ConstPtr &msg) | 
| void | recvCanGps (const std::vector< can_msgs::Frame::ConstPtr > &msgs) | 
| void | recvCanImu (const std::vector< can_msgs::Frame::ConstPtr > &msgs) | 
| void | recvDisable (const std_msgs::Empty::ConstPtr &msg) | 
| void | recvEnable (const std_msgs::Empty::ConstPtr &msg) | 
| void | recvGearCmd (const dbw_pacifica_msgs::GearCmd::ConstPtr &msg) | 
| void | recvGlobalEnableCmd (const dbw_pacifica_msgs::GlobalEnableCmd::ConstPtr &msg) | 
| void | recvMiscCmd (const dbw_pacifica_msgs::MiscCmd::ConstPtr &msg) | 
| void | recvSteeringCmd (const dbw_pacifica_msgs::SteeringCmd::ConstPtr &msg) | 
| void | timeoutAcceleratorPedal (bool timeout, bool enabled) | 
| void | timeoutBrake (bool timeout, bool enabled) | 
| void | timeoutSteering (bool timeout, bool enabled) | 
| void | timerCallback (const ros::TimerEvent &event) | 
| 
Private Attributes | 
| double | acker_track_ | 
| double | acker_wheelbase_ | 
| bool | buttons_ | 
| uint32_t | count_ | 
| std::string | dbcFile_ | 
| NewEagle::Dbc | dbwDbc_ | 
| bool | enable_ | 
| bool | enabled_accelerator_pedal_ | 
| bool | enabled_brakes_ | 
| bool | enabled_steering_ | 
| bool | fault_accelerator_pedal_ | 
| bool | fault_brakes_ | 
| bool | fault_steering_ | 
| bool | fault_steering_cal_ | 
| bool | fault_watchdog_ | 
| bool | fault_watchdog_using_brakes_ | 
| bool | fault_watchdog_warned_ | 
| std::string | frame_id_ | 
| bool | gear_warned_ | 
| sensor_msgs::JointState | joint_state_ | 
| bool | override_accelerator_pedal_ | 
| bool | override_brake_ | 
| bool | override_gear_ | 
| bool | override_steering_ | 
| ros::Publisher | pdu1_relay_pub_ | 
| bool | prev_enable_ | 
| ros::Publisher | pub_accel_pedal_ | 
| ros::Publisher | pub_brake_ | 
| ros::Publisher | pub_brake_2_report_ | 
| ros::Publisher | pub_can_ | 
| ros::Publisher | pub_driver_input_ | 
| ros::Publisher | pub_fault_actions_report_ | 
| ros::Publisher | pub_gear_ | 
| ros::Publisher | pub_hmi_global_enable_report_ | 
| ros::Publisher | pub_imu_ | 
| ros::Publisher | pub_joint_states_ | 
| ros::Publisher | pub_low_voltage_system_ | 
| ros::Publisher | pub_misc_ | 
| ros::Publisher | pub_steering_ | 
| ros::Publisher | pub_steering_2_report_ | 
| ros::Publisher | pub_surround_ | 
| ros::Publisher | pub_sys_enable_ | 
| ros::Publisher | pub_tire_pressure_ | 
| ros::Publisher | pub_twist_ | 
| ros::Publisher | pub_vin_ | 
| ros::Publisher | pub_wheel_positions_ | 
| ros::Publisher | pub_wheel_speeds_ | 
| double | steering_ratio_ | 
| ros::Subscriber | sub_accelerator_pedal_ | 
| ros::Subscriber | sub_brake_ | 
| ros::Subscriber | sub_can_ | 
| ros::Subscriber | sub_disable_ | 
| ros::Subscriber | sub_enable_ | 
| ros::Subscriber | sub_gear_ | 
| ros::Subscriber | sub_global_enable_ | 
| ros::Subscriber | sub_misc_ | 
| ros::Subscriber | sub_steering_ | 
| bool | timeout_accelerator_pedal_ | 
| bool | timeout_brakes_ | 
| bool | timeout_steering_ | 
| ros::Timer | timer_ | 
| std::string | vin_ | 
Definition at line 85 of file DbwNode.h.