Public Member Functions | Private Types | Private Member Functions | Private Attributes
dbw_pacifica_can::DbwNode Class Reference

#include <DbwNode.h>

List of all members.

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_

Detailed Description

Definition at line 85 of file DbwNode.h.


Member Enumeration Documentation

anonymous enum [private]
Enumerator:
JOINT_FL 
JOINT_FR 
JOINT_RL 
JOINT_RR 
JOINT_SL 
JOINT_SR 
JOINT_COUNT 

Definition at line 148 of file DbwNode.h.


Constructor & Destructor Documentation

Definition at line 42 of file DbwNode.cpp.

Definition at line 144 of file DbwNode.cpp.


Member Function Documentation

Definition at line 1027 of file DbwNode.cpp.

bool dbw_pacifica_can::DbwNode::clear ( ) [inline, private]

Definition at line 128 of file DbwNode.h.

Definition at line 1018 of file DbwNode.cpp.

bool dbw_pacifica_can::DbwNode::enabled ( ) [inline, private]

Definition at line 129 of file DbwNode.h.

Definition at line 988 of file DbwNode.cpp.

bool dbw_pacifica_can::DbwNode::fault ( ) [inline, private]

Definition at line 126 of file DbwNode.h.

void dbw_pacifica_can::DbwNode::faultAcceleratorPedal ( bool  fault) [private]

Definition at line 1143 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::faultBrakes ( bool  fault) [private]

Definition at line 1127 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::faultSteering ( bool  fault) [private]

Definition at line 1159 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::faultSteeringCal ( bool  fault) [private]

Definition at line 1175 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::faultWatchdog ( bool  fault,
uint8_t  src,
bool  braking 
) [private]

Definition at line 1191 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::faultWatchdog ( bool  fault,
uint8_t  src = 0 
) [private]

Definition at line 1269 of file DbwNode.cpp.

bool dbw_pacifica_can::DbwNode::override ( ) [inline, private]

Definition at line 127 of file DbwNode.h.

void dbw_pacifica_can::DbwNode::overrideAcceleratorPedal ( bool  override) [private]

Definition at line 1052 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::overrideBrake ( bool  override) [private]

Definition at line 1036 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::overrideGear ( bool  override) [private]

Definition at line 1084 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::overrideSteering ( bool  override) [private]

Definition at line 1068 of file DbwNode.cpp.

Definition at line 926 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::publishJointStates ( const ros::Time stamp,
const dbw_pacifica_msgs::WheelSpeedReport *  wheels,
const dbw_pacifica_msgs::SteeringReport *  steering 
) [private]

Definition at line 1273 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::recvAcceleratorPedalCmd ( const dbw_pacifica_msgs::AcceleratorPedalCmd::ConstPtr &  msg) [private]

Definition at line 722 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::recvBrakeCmd ( const dbw_pacifica_msgs::BrakeCmd::ConstPtr &  msg) [private]

Definition at line 682 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::recvCAN ( const can_msgs::Frame::ConstPtr &  msg) [private]

Definition at line 158 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::recvCanGps ( const std::vector< can_msgs::Frame::ConstPtr > &  msgs) [private]
void dbw_pacifica_can::DbwNode::recvCanImu ( const std::vector< can_msgs::Frame::ConstPtr > &  msgs) [private]
void dbw_pacifica_can::DbwNode::recvDisable ( const std_msgs::Empty::ConstPtr &  msg) [private]

Definition at line 153 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::recvEnable ( const std_msgs::Empty::ConstPtr &  msg) [private]

Definition at line 148 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::recvGearCmd ( const dbw_pacifica_msgs::GearCmd::ConstPtr &  msg) [private]

Definition at line 824 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::recvGlobalEnableCmd ( const dbw_pacifica_msgs::GlobalEnableCmd::ConstPtr &  msg) [private]

Definition at line 848 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::recvMiscCmd ( const dbw_pacifica_msgs::MiscCmd::ConstPtr &  msg) [private]

Definition at line 877 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::recvSteeringCmd ( const dbw_pacifica_msgs::SteeringCmd::ConstPtr &  msg) [private]

Definition at line 774 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::timeoutAcceleratorPedal ( bool  timeout,
bool  enabled 
) [private]

Definition at line 1109 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::timeoutBrake ( bool  timeout,
bool  enabled 
) [private]

Definition at line 1100 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::timeoutSteering ( bool  timeout,
bool  enabled 
) [private]

Definition at line 1118 of file DbwNode.cpp.

void dbw_pacifica_can::DbwNode::timerCallback ( const ros::TimerEvent event) [private]

Definition at line 940 of file DbwNode.cpp.


Member Data Documentation

Definition at line 170 of file DbwNode.h.

Definition at line 169 of file DbwNode.h.

Definition at line 166 of file DbwNode.h.

Definition at line 213 of file DbwNode.h.

std::string dbw_pacifica_can::DbwNode::dbcFile_ [private]

Definition at line 209 of file DbwNode.h.

Definition at line 208 of file DbwNode.h.

Definition at line 107 of file DbwNode.h.

Definition at line 123 of file DbwNode.h.

Definition at line 122 of file DbwNode.h.

Definition at line 124 of file DbwNode.h.

Definition at line 113 of file DbwNode.h.

Definition at line 112 of file DbwNode.h.

Definition at line 114 of file DbwNode.h.

Definition at line 115 of file DbwNode.h.

Definition at line 116 of file DbwNode.h.

Definition at line 117 of file DbwNode.h.

Definition at line 118 of file DbwNode.h.

std::string dbw_pacifica_can::DbwNode::frame_id_ [private]

Definition at line 163 of file DbwNode.h.

Definition at line 125 of file DbwNode.h.

sensor_msgs::JointState dbw_pacifica_can::DbwNode::joint_state_ [private]

Definition at line 157 of file DbwNode.h.

Definition at line 109 of file DbwNode.h.

Definition at line 108 of file DbwNode.h.

Definition at line 111 of file DbwNode.h.

Definition at line 110 of file DbwNode.h.

Definition at line 212 of file DbwNode.h.

Definition at line 106 of file DbwNode.h.

Definition at line 187 of file DbwNode.h.

Definition at line 186 of file DbwNode.h.

Definition at line 203 of file DbwNode.h.

Definition at line 185 of file DbwNode.h.

Definition at line 200 of file DbwNode.h.

Definition at line 205 of file DbwNode.h.

Definition at line 189 of file DbwNode.h.

Definition at line 206 of file DbwNode.h.

Definition at line 195 of file DbwNode.h.

Definition at line 196 of file DbwNode.h.

Definition at line 201 of file DbwNode.h.

Definition at line 190 of file DbwNode.h.

Definition at line 188 of file DbwNode.h.

Definition at line 204 of file DbwNode.h.

Definition at line 194 of file DbwNode.h.

Definition at line 199 of file DbwNode.h.

Definition at line 193 of file DbwNode.h.

Definition at line 197 of file DbwNode.h.

Definition at line 198 of file DbwNode.h.

Definition at line 192 of file DbwNode.h.

Definition at line 191 of file DbwNode.h.

Definition at line 171 of file DbwNode.h.

Definition at line 178 of file DbwNode.h.

Definition at line 177 of file DbwNode.h.

Definition at line 176 of file DbwNode.h.

Definition at line 175 of file DbwNode.h.

Definition at line 174 of file DbwNode.h.

Definition at line 180 of file DbwNode.h.

Definition at line 182 of file DbwNode.h.

Definition at line 181 of file DbwNode.h.

Definition at line 179 of file DbwNode.h.

Definition at line 120 of file DbwNode.h.

Definition at line 119 of file DbwNode.h.

Definition at line 121 of file DbwNode.h.

Definition at line 105 of file DbwNode.h.

std::string dbw_pacifica_can::DbwNode::vin_ [private]

Definition at line 160 of file DbwNode.h.


The documentation for this class was generated from the following files:


dbw_pacifica_can
Author(s): Ryan Borchert
autogenerated on Mon Jun 24 2019 19:18:33