Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
raptor_dbw_can::DbwNode Class Reference

#include <DbwNode.h>

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 raptor_dbw_msgs::WheelSpeedReport *wheels, const raptor_dbw_msgs::SteeringReport *steering)
 
void recvAcceleratorPedalCmd (const raptor_dbw_msgs::AcceleratorPedalCmd::ConstPtr &msg)
 
void recvBrakeCmd (const raptor_dbw_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 raptor_dbw_msgs::GearCmd::ConstPtr &msg)
 
void recvGlobalEnableCmd (const raptor_dbw_msgs::GlobalEnableCmd::ConstPtr &msg)
 
void recvMiscCmd (const raptor_dbw_msgs::MiscCmd::ConstPtr &msg)
 
void recvSteeringCmd (const raptor_dbw_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 118 of file DbwNode.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
private
Enumerator
JOINT_FL 
JOINT_FR 
JOINT_RL 
JOINT_RR 
JOINT_SL 
JOINT_SR 
JOINT_COUNT 

Definition at line 214 of file DbwNode.h.

Constructor & Destructor Documentation

◆ DbwNode()

raptor_dbw_can::DbwNode::DbwNode ( ros::NodeHandle node,
ros::NodeHandle priv_nh 
)

Definition at line 75 of file DbwNode.cpp.

◆ ~DbwNode()

raptor_dbw_can::DbwNode::~DbwNode ( )

Definition at line 177 of file DbwNode.cpp.

Member Function Documentation

◆ buttonCancel()

void raptor_dbw_can::DbwNode::buttonCancel ( )
private

Definition at line 1038 of file DbwNode.cpp.

◆ clear()

bool raptor_dbw_can::DbwNode::clear ( )
inlineprivate

Definition at line 194 of file DbwNode.h.

◆ disableSystem()

void raptor_dbw_can::DbwNode::disableSystem ( )
private

Definition at line 1029 of file DbwNode.cpp.

◆ enabled()

bool raptor_dbw_can::DbwNode::enabled ( )
inlineprivate

Definition at line 195 of file DbwNode.h.

◆ enableSystem()

void raptor_dbw_can::DbwNode::enableSystem ( )
private

Definition at line 999 of file DbwNode.cpp.

◆ fault()

bool raptor_dbw_can::DbwNode::fault ( )
inlineprivate

Definition at line 192 of file DbwNode.h.

◆ faultAcceleratorPedal()

void raptor_dbw_can::DbwNode::faultAcceleratorPedal ( bool  fault)
private

Definition at line 1154 of file DbwNode.cpp.

◆ faultBrakes()

void raptor_dbw_can::DbwNode::faultBrakes ( bool  fault)
private

Definition at line 1138 of file DbwNode.cpp.

◆ faultSteering()

void raptor_dbw_can::DbwNode::faultSteering ( bool  fault)
private

Definition at line 1170 of file DbwNode.cpp.

◆ faultSteeringCal()

void raptor_dbw_can::DbwNode::faultSteeringCal ( bool  fault)
private

Definition at line 1186 of file DbwNode.cpp.

◆ faultWatchdog() [1/2]

void raptor_dbw_can::DbwNode::faultWatchdog ( bool  fault,
uint8_t  src,
bool  braking 
)
private

Definition at line 1202 of file DbwNode.cpp.

◆ faultWatchdog() [2/2]

void raptor_dbw_can::DbwNode::faultWatchdog ( bool  fault,
uint8_t  src = 0 
)
private

Definition at line 1280 of file DbwNode.cpp.

◆ override()

bool raptor_dbw_can::DbwNode::override ( )
inlineprivate

Definition at line 193 of file DbwNode.h.

◆ overrideAcceleratorPedal()

void raptor_dbw_can::DbwNode::overrideAcceleratorPedal ( bool  override)
private

Definition at line 1063 of file DbwNode.cpp.

◆ overrideBrake()

void raptor_dbw_can::DbwNode::overrideBrake ( bool  override)
private

Definition at line 1047 of file DbwNode.cpp.

◆ overrideGear()

void raptor_dbw_can::DbwNode::overrideGear ( bool  override)
private

Definition at line 1095 of file DbwNode.cpp.

◆ overrideSteering()

void raptor_dbw_can::DbwNode::overrideSteering ( bool  override)
private

Definition at line 1079 of file DbwNode.cpp.

◆ publishDbwEnabled()

bool raptor_dbw_can::DbwNode::publishDbwEnabled ( )
private

Definition at line 937 of file DbwNode.cpp.

◆ publishJointStates()

void raptor_dbw_can::DbwNode::publishJointStates ( const ros::Time stamp,
const raptor_dbw_msgs::WheelSpeedReport *  wheels,
const raptor_dbw_msgs::SteeringReport *  steering 
)
private

Definition at line 1284 of file DbwNode.cpp.

◆ recvAcceleratorPedalCmd()

void raptor_dbw_can::DbwNode::recvAcceleratorPedalCmd ( const raptor_dbw_msgs::AcceleratorPedalCmd::ConstPtr &  msg)
private

Definition at line 733 of file DbwNode.cpp.

◆ recvBrakeCmd()

void raptor_dbw_can::DbwNode::recvBrakeCmd ( const raptor_dbw_msgs::BrakeCmd::ConstPtr &  msg)
private

Definition at line 693 of file DbwNode.cpp.

◆ recvCAN()

void raptor_dbw_can::DbwNode::recvCAN ( const can_msgs::Frame::ConstPtr &  msg)
private

Definition at line 191 of file DbwNode.cpp.

◆ recvCanGps()

void raptor_dbw_can::DbwNode::recvCanGps ( const std::vector< can_msgs::Frame::ConstPtr > &  msgs)
private

◆ recvCanImu()

void raptor_dbw_can::DbwNode::recvCanImu ( const std::vector< can_msgs::Frame::ConstPtr > &  msgs)
private

◆ recvDisable()

void raptor_dbw_can::DbwNode::recvDisable ( const std_msgs::Empty::ConstPtr &  msg)
private

Definition at line 186 of file DbwNode.cpp.

◆ recvEnable()

void raptor_dbw_can::DbwNode::recvEnable ( const std_msgs::Empty::ConstPtr &  msg)
private

Definition at line 181 of file DbwNode.cpp.

◆ recvGearCmd()

void raptor_dbw_can::DbwNode::recvGearCmd ( const raptor_dbw_msgs::GearCmd::ConstPtr &  msg)
private

Definition at line 835 of file DbwNode.cpp.

◆ recvGlobalEnableCmd()

void raptor_dbw_can::DbwNode::recvGlobalEnableCmd ( const raptor_dbw_msgs::GlobalEnableCmd::ConstPtr &  msg)
private

Definition at line 859 of file DbwNode.cpp.

◆ recvMiscCmd()

void raptor_dbw_can::DbwNode::recvMiscCmd ( const raptor_dbw_msgs::MiscCmd::ConstPtr &  msg)
private

Definition at line 888 of file DbwNode.cpp.

◆ recvSteeringCmd()

void raptor_dbw_can::DbwNode::recvSteeringCmd ( const raptor_dbw_msgs::SteeringCmd::ConstPtr &  msg)
private

Definition at line 785 of file DbwNode.cpp.

◆ timeoutAcceleratorPedal()

void raptor_dbw_can::DbwNode::timeoutAcceleratorPedal ( bool  timeout,
bool  enabled 
)
private

Definition at line 1120 of file DbwNode.cpp.

◆ timeoutBrake()

void raptor_dbw_can::DbwNode::timeoutBrake ( bool  timeout,
bool  enabled 
)
private

Definition at line 1111 of file DbwNode.cpp.

◆ timeoutSteering()

void raptor_dbw_can::DbwNode::timeoutSteering ( bool  timeout,
bool  enabled 
)
private

Definition at line 1129 of file DbwNode.cpp.

◆ timerCallback()

void raptor_dbw_can::DbwNode::timerCallback ( const ros::TimerEvent event)
private

Definition at line 951 of file DbwNode.cpp.

Member Data Documentation

◆ acker_track_

double raptor_dbw_can::DbwNode::acker_track_
private

Definition at line 236 of file DbwNode.h.

◆ acker_wheelbase_

double raptor_dbw_can::DbwNode::acker_wheelbase_
private

Definition at line 235 of file DbwNode.h.

◆ buttons_

bool raptor_dbw_can::DbwNode::buttons_
private

Definition at line 232 of file DbwNode.h.

◆ count_

uint32_t raptor_dbw_can::DbwNode::count_
private

Definition at line 279 of file DbwNode.h.

◆ dbcFile_

std::string raptor_dbw_can::DbwNode::dbcFile_
private

Definition at line 275 of file DbwNode.h.

◆ dbwDbc_

NewEagle::Dbc raptor_dbw_can::DbwNode::dbwDbc_
private

Definition at line 274 of file DbwNode.h.

◆ enable_

bool raptor_dbw_can::DbwNode::enable_
private

Definition at line 173 of file DbwNode.h.

◆ enabled_accelerator_pedal_

bool raptor_dbw_can::DbwNode::enabled_accelerator_pedal_
private

Definition at line 189 of file DbwNode.h.

◆ enabled_brakes_

bool raptor_dbw_can::DbwNode::enabled_brakes_
private

Definition at line 188 of file DbwNode.h.

◆ enabled_steering_

bool raptor_dbw_can::DbwNode::enabled_steering_
private

Definition at line 190 of file DbwNode.h.

◆ fault_accelerator_pedal_

bool raptor_dbw_can::DbwNode::fault_accelerator_pedal_
private

Definition at line 179 of file DbwNode.h.

◆ fault_brakes_

bool raptor_dbw_can::DbwNode::fault_brakes_
private

Definition at line 178 of file DbwNode.h.

◆ fault_steering_

bool raptor_dbw_can::DbwNode::fault_steering_
private

Definition at line 180 of file DbwNode.h.

◆ fault_steering_cal_

bool raptor_dbw_can::DbwNode::fault_steering_cal_
private

Definition at line 181 of file DbwNode.h.

◆ fault_watchdog_

bool raptor_dbw_can::DbwNode::fault_watchdog_
private

Definition at line 182 of file DbwNode.h.

◆ fault_watchdog_using_brakes_

bool raptor_dbw_can::DbwNode::fault_watchdog_using_brakes_
private

Definition at line 183 of file DbwNode.h.

◆ fault_watchdog_warned_

bool raptor_dbw_can::DbwNode::fault_watchdog_warned_
private

Definition at line 184 of file DbwNode.h.

◆ frame_id_

std::string raptor_dbw_can::DbwNode::frame_id_
private

Definition at line 229 of file DbwNode.h.

◆ gear_warned_

bool raptor_dbw_can::DbwNode::gear_warned_
private

Definition at line 191 of file DbwNode.h.

◆ joint_state_

sensor_msgs::JointState raptor_dbw_can::DbwNode::joint_state_
private

Definition at line 223 of file DbwNode.h.

◆ override_accelerator_pedal_

bool raptor_dbw_can::DbwNode::override_accelerator_pedal_
private

Definition at line 175 of file DbwNode.h.

◆ override_brake_

bool raptor_dbw_can::DbwNode::override_brake_
private

Definition at line 174 of file DbwNode.h.

◆ override_gear_

bool raptor_dbw_can::DbwNode::override_gear_
private

Definition at line 177 of file DbwNode.h.

◆ override_steering_

bool raptor_dbw_can::DbwNode::override_steering_
private

Definition at line 176 of file DbwNode.h.

◆ pdu1_relay_pub_

ros::Publisher raptor_dbw_can::DbwNode::pdu1_relay_pub_
private

Definition at line 278 of file DbwNode.h.

◆ prev_enable_

bool raptor_dbw_can::DbwNode::prev_enable_
private

Definition at line 172 of file DbwNode.h.

◆ pub_accel_pedal_

ros::Publisher raptor_dbw_can::DbwNode::pub_accel_pedal_
private

Definition at line 253 of file DbwNode.h.

◆ pub_brake_

ros::Publisher raptor_dbw_can::DbwNode::pub_brake_
private

Definition at line 252 of file DbwNode.h.

◆ pub_brake_2_report_

ros::Publisher raptor_dbw_can::DbwNode::pub_brake_2_report_
private

Definition at line 269 of file DbwNode.h.

◆ pub_can_

ros::Publisher raptor_dbw_can::DbwNode::pub_can_
private

Definition at line 251 of file DbwNode.h.

◆ pub_driver_input_

ros::Publisher raptor_dbw_can::DbwNode::pub_driver_input_
private

Definition at line 266 of file DbwNode.h.

◆ pub_fault_actions_report_

ros::Publisher raptor_dbw_can::DbwNode::pub_fault_actions_report_
private

Definition at line 271 of file DbwNode.h.

◆ pub_gear_

ros::Publisher raptor_dbw_can::DbwNode::pub_gear_
private

Definition at line 255 of file DbwNode.h.

◆ pub_hmi_global_enable_report_

ros::Publisher raptor_dbw_can::DbwNode::pub_hmi_global_enable_report_
private

Definition at line 272 of file DbwNode.h.

◆ pub_imu_

ros::Publisher raptor_dbw_can::DbwNode::pub_imu_
private

Definition at line 261 of file DbwNode.h.

◆ pub_joint_states_

ros::Publisher raptor_dbw_can::DbwNode::pub_joint_states_
private

Definition at line 262 of file DbwNode.h.

◆ pub_low_voltage_system_

ros::Publisher raptor_dbw_can::DbwNode::pub_low_voltage_system_
private

Definition at line 267 of file DbwNode.h.

◆ pub_misc_

ros::Publisher raptor_dbw_can::DbwNode::pub_misc_
private

Definition at line 256 of file DbwNode.h.

◆ pub_steering_

ros::Publisher raptor_dbw_can::DbwNode::pub_steering_
private

Definition at line 254 of file DbwNode.h.

◆ pub_steering_2_report_

ros::Publisher raptor_dbw_can::DbwNode::pub_steering_2_report_
private

Definition at line 270 of file DbwNode.h.

◆ pub_surround_

ros::Publisher raptor_dbw_can::DbwNode::pub_surround_
private

Definition at line 260 of file DbwNode.h.

◆ pub_sys_enable_

ros::Publisher raptor_dbw_can::DbwNode::pub_sys_enable_
private

Definition at line 265 of file DbwNode.h.

◆ pub_tire_pressure_

ros::Publisher raptor_dbw_can::DbwNode::pub_tire_pressure_
private

Definition at line 259 of file DbwNode.h.

◆ pub_twist_

ros::Publisher raptor_dbw_can::DbwNode::pub_twist_
private

Definition at line 263 of file DbwNode.h.

◆ pub_vin_

ros::Publisher raptor_dbw_can::DbwNode::pub_vin_
private

Definition at line 264 of file DbwNode.h.

◆ pub_wheel_positions_

ros::Publisher raptor_dbw_can::DbwNode::pub_wheel_positions_
private

Definition at line 258 of file DbwNode.h.

◆ pub_wheel_speeds_

ros::Publisher raptor_dbw_can::DbwNode::pub_wheel_speeds_
private

Definition at line 257 of file DbwNode.h.

◆ steering_ratio_

double raptor_dbw_can::DbwNode::steering_ratio_
private

Definition at line 237 of file DbwNode.h.

◆ sub_accelerator_pedal_

ros::Subscriber raptor_dbw_can::DbwNode::sub_accelerator_pedal_
private

Definition at line 244 of file DbwNode.h.

◆ sub_brake_

ros::Subscriber raptor_dbw_can::DbwNode::sub_brake_
private

Definition at line 243 of file DbwNode.h.

◆ sub_can_

ros::Subscriber raptor_dbw_can::DbwNode::sub_can_
private

Definition at line 242 of file DbwNode.h.

◆ sub_disable_

ros::Subscriber raptor_dbw_can::DbwNode::sub_disable_
private

Definition at line 241 of file DbwNode.h.

◆ sub_enable_

ros::Subscriber raptor_dbw_can::DbwNode::sub_enable_
private

Definition at line 240 of file DbwNode.h.

◆ sub_gear_

ros::Subscriber raptor_dbw_can::DbwNode::sub_gear_
private

Definition at line 246 of file DbwNode.h.

◆ sub_global_enable_

ros::Subscriber raptor_dbw_can::DbwNode::sub_global_enable_
private

Definition at line 248 of file DbwNode.h.

◆ sub_misc_

ros::Subscriber raptor_dbw_can::DbwNode::sub_misc_
private

Definition at line 247 of file DbwNode.h.

◆ sub_steering_

ros::Subscriber raptor_dbw_can::DbwNode::sub_steering_
private

Definition at line 245 of file DbwNode.h.

◆ timeout_accelerator_pedal_

bool raptor_dbw_can::DbwNode::timeout_accelerator_pedal_
private

Definition at line 186 of file DbwNode.h.

◆ timeout_brakes_

bool raptor_dbw_can::DbwNode::timeout_brakes_
private

Definition at line 185 of file DbwNode.h.

◆ timeout_steering_

bool raptor_dbw_can::DbwNode::timeout_steering_
private

Definition at line 187 of file DbwNode.h.

◆ timer_

ros::Timer raptor_dbw_can::DbwNode::timer_
private

Definition at line 171 of file DbwNode.h.

◆ vin_

std::string raptor_dbw_can::DbwNode::vin_
private

Definition at line 226 of file DbwNode.h.


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


raptor_dbw_can
Author(s): Ryan Borchert
autogenerated on Sat Apr 9 2022 02:34:35