Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
dbw_fca_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 faultBrakes (bool fault)
 
void faultSteering (bool fault)
 
void faultSteeringCal (bool fault)
 
void faultThrottle (bool fault)
 
void faultWatchdog (bool fault, uint8_t src, bool braking)
 
void faultWatchdog (bool fault, uint8_t src=0)
 
bool override ()
 
void overrideBrake (bool override, bool timeout)
 
void overrideGear (bool override)
 
void overrideSteering (bool override, bool timeout)
 
void overrideThrottle (bool override, bool timeout)
 
bool publishDbwEnabled ()
 
void publishJointStates (const ros::Time &stamp, const dbw_fca_msgs::SteeringReport *steering)
 
void recvBrakeCmd (const dbw_fca_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_fca_msgs::GearCmd::ConstPtr &msg)
 
void recvMiscCmd (const dbw_fca_msgs::MiscCmd::ConstPtr &msg)
 
void recvSteeringCmd (const dbw_fca_msgs::SteeringCmd::ConstPtr &msg)
 
void recvThrottleCmd (const dbw_fca_msgs::ThrottleCmd::ConstPtr &msg)
 
void recvTurnSignalCmd (const dbw_fca_msgs::MiscCmd::ConstPtr &msg)
 
float speedSign () const
 
void timeoutBrake (bool timeout, bool enabled)
 
void timeoutSteering (bool timeout, bool enabled)
 
void timeoutThrottle (bool timeout, bool enabled)
 
void timerCallback (const ros::TimerEvent &event)
 

Static Private Member Functions

template<typename T >
static int sgn (T val)
 

Private Attributes

double acker_track_
 
double acker_wheelbase_
 
std::map< uint8_t, std::string > bdate_
 
bool buttons_
 
bool enable_
 
bool enable_joint_states_
 
bool enabled_brakes_
 
bool enabled_steering_
 
bool enabled_throttle_
 
bool fault_brakes_
 
bool fault_steering_
 
bool fault_steering_cal_
 
bool fault_throttle_
 
bool fault_watchdog_
 
bool fault_watchdog_using_brakes_
 
bool fault_watchdog_warned_
 
PlatformMap firmware_
 
std::string frame_id_
 
bool gear_warned_
 
sensor_msgs::JointState joint_state_
 
std::string ldate_
 
bool override_brake_
 
bool override_gear_
 
bool override_steering_
 
bool override_throttle_
 
bool pedal_luts_
 
bool prev_enable_
 
ros::Publisher pub_brake_
 
ros::Publisher pub_brake_info_
 
ros::Publisher pub_can_
 
ros::Publisher pub_fuel_level_
 
ros::Publisher pub_gear_
 
ros::Publisher pub_gps_fix_
 
ros::Publisher pub_gps_fix_dr
 
ros::Publisher pub_gps_time_
 
ros::Publisher pub_imu_
 
ros::Publisher pub_joint_states_
 
ros::Publisher pub_misc_1_
 
ros::Publisher pub_misc_2_
 
ros::Publisher pub_steering_
 
ros::Publisher pub_sys_enable_
 
ros::Publisher pub_throttle_
 
ros::Publisher pub_throttle_info_
 
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_brake_
 
ros::Subscriber sub_can_
 
ros::Subscriber sub_disable_
 
ros::Subscriber sub_enable_
 
ros::Subscriber sub_gear_
 
ros::Subscriber sub_misc_
 
ros::Subscriber sub_steering_
 
ros::Subscriber sub_throttle_
 
ros::Subscriber sub_turn_signal_
 
dataspeed_can_msg_filters::ApproximateTime sync_gps_
 
dataspeed_can_msg_filters::ApproximateTime sync_imu_
 
bool timeout_brakes_
 
bool timeout_steering_
 
bool timeout_throttle_
 
ros::Timer timer_
 
std::string vin_
 
bool warn_cmds_
 
double wheel_radius_
 

Detailed Description

Definition at line 75 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 138 of file DbwNode.h.

Constructor & Destructor Documentation

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

Definition at line 79 of file DbwNode.cpp.

dbw_fca_can::DbwNode::~DbwNode ( )

Definition at line 191 of file DbwNode.cpp.

Member Function Documentation

void dbw_fca_can::DbwNode::buttonCancel ( )
private

Definition at line 1156 of file DbwNode.cpp.

bool dbw_fca_can::DbwNode::clear ( )
inlineprivate

Definition at line 118 of file DbwNode.h.

void dbw_fca_can::DbwNode::disableSystem ( )
private

Definition at line 1147 of file DbwNode.cpp.

bool dbw_fca_can::DbwNode::enabled ( )
inlineprivate

Definition at line 119 of file DbwNode.h.

void dbw_fca_can::DbwNode::enableSystem ( )
private

Definition at line 1117 of file DbwNode.cpp.

bool dbw_fca_can::DbwNode::fault ( )
inlineprivate

Definition at line 116 of file DbwNode.h.

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

Definition at line 1265 of file DbwNode.cpp.

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

Definition at line 1297 of file DbwNode.cpp.

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

Definition at line 1313 of file DbwNode.cpp.

void dbw_fca_can::DbwNode::faultThrottle ( bool  fault)
private

Definition at line 1281 of file DbwNode.cpp.

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

Definition at line 1329 of file DbwNode.cpp.

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

Definition at line 1406 of file DbwNode.cpp.

bool dbw_fca_can::DbwNode::override ( )
inlineprivate

Definition at line 117 of file DbwNode.h.

void dbw_fca_can::DbwNode::overrideBrake ( bool  override,
bool  timeout 
)
private

Definition at line 1165 of file DbwNode.cpp.

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

Definition at line 1222 of file DbwNode.cpp.

void dbw_fca_can::DbwNode::overrideSteering ( bool  override,
bool  timeout 
)
private

Definition at line 1203 of file DbwNode.cpp.

void dbw_fca_can::DbwNode::overrideThrottle ( bool  override,
bool  timeout 
)
private

Definition at line 1184 of file DbwNode.cpp.

bool dbw_fca_can::DbwNode::publishDbwEnabled ( )
private

Definition at line 1063 of file DbwNode.cpp.

void dbw_fca_can::DbwNode::publishJointStates ( const ros::Time stamp,
const dbw_fca_msgs::SteeringReport *  steering 
)
private

Definition at line 1410 of file DbwNode.cpp.

void dbw_fca_can::DbwNode::recvBrakeCmd ( const dbw_fca_msgs::BrakeCmd::ConstPtr &  msg)
private

Definition at line 844 of file DbwNode.cpp.

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

Definition at line 205 of file DbwNode.cpp.

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

Definition at line 785 of file DbwNode.cpp.

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

Definition at line 749 of file DbwNode.cpp.

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

Definition at line 200 of file DbwNode.cpp.

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

Definition at line 195 of file DbwNode.cpp.

void dbw_fca_can::DbwNode::recvGearCmd ( const dbw_fca_msgs::GearCmd::ConstPtr &  msg)
private

Definition at line 1007 of file DbwNode.cpp.

void dbw_fca_can::DbwNode::recvMiscCmd ( const dbw_fca_msgs::MiscCmd::ConstPtr &  msg)
private

Definition at line 1029 of file DbwNode.cpp.

void dbw_fca_can::DbwNode::recvSteeringCmd ( const dbw_fca_msgs::SteeringCmd::ConstPtr &  msg)
private

Definition at line 963 of file DbwNode.cpp.

void dbw_fca_can::DbwNode::recvThrottleCmd ( const dbw_fca_msgs::ThrottleCmd::ConstPtr &  msg)
private

Definition at line 919 of file DbwNode.cpp.

void dbw_fca_can::DbwNode::recvTurnSignalCmd ( const dbw_fca_msgs::MiscCmd::ConstPtr &  msg)
private

Definition at line 1024 of file DbwNode.cpp.

template<typename T >
static int dbw_fca_can::DbwNode::sgn ( val)
inlinestaticprivate

Definition at line 151 of file DbwNode.h.

float dbw_fca_can::DbwNode::speedSign ( ) const
inlineprivate

Definition at line 156 of file DbwNode.h.

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

Definition at line 1238 of file DbwNode.cpp.

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

Definition at line 1256 of file DbwNode.cpp.

void dbw_fca_can::DbwNode::timeoutThrottle ( bool  timeout,
bool  enabled 
)
private

Definition at line 1247 of file DbwNode.cpp.

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

Definition at line 1077 of file DbwNode.cpp.

Member Data Documentation

double dbw_fca_can::DbwNode::acker_track_
private

Definition at line 183 of file DbwNode.h.

double dbw_fca_can::DbwNode::acker_wheelbase_
private

Definition at line 182 of file DbwNode.h.

std::map<uint8_t, std::string> dbw_fca_can::DbwNode::bdate_
private

Definition at line 164 of file DbwNode.h.

bool dbw_fca_can::DbwNode::buttons_
private

Definition at line 176 of file DbwNode.h.

bool dbw_fca_can::DbwNode::enable_
private

Definition at line 97 of file DbwNode.h.

bool dbw_fca_can::DbwNode::enable_joint_states_
private

Definition at line 188 of file DbwNode.h.

bool dbw_fca_can::DbwNode::enabled_brakes_
private

Definition at line 112 of file DbwNode.h.

bool dbw_fca_can::DbwNode::enabled_steering_
private

Definition at line 114 of file DbwNode.h.

bool dbw_fca_can::DbwNode::enabled_throttle_
private

Definition at line 113 of file DbwNode.h.

bool dbw_fca_can::DbwNode::fault_brakes_
private

Definition at line 102 of file DbwNode.h.

bool dbw_fca_can::DbwNode::fault_steering_
private

Definition at line 104 of file DbwNode.h.

bool dbw_fca_can::DbwNode::fault_steering_cal_
private

Definition at line 105 of file DbwNode.h.

bool dbw_fca_can::DbwNode::fault_throttle_
private

Definition at line 103 of file DbwNode.h.

bool dbw_fca_can::DbwNode::fault_watchdog_
private

Definition at line 106 of file DbwNode.h.

bool dbw_fca_can::DbwNode::fault_watchdog_using_brakes_
private

Definition at line 107 of file DbwNode.h.

bool dbw_fca_can::DbwNode::fault_watchdog_warned_
private

Definition at line 108 of file DbwNode.h.

PlatformMap dbw_fca_can::DbwNode::firmware_
private

Definition at line 167 of file DbwNode.h.

std::string dbw_fca_can::DbwNode::frame_id_
private

Definition at line 170 of file DbwNode.h.

bool dbw_fca_can::DbwNode::gear_warned_
private

Definition at line 115 of file DbwNode.h.

sensor_msgs::JointState dbw_fca_can::DbwNode::joint_state_
private

Definition at line 147 of file DbwNode.h.

std::string dbw_fca_can::DbwNode::ldate_
private

Definition at line 163 of file DbwNode.h.

bool dbw_fca_can::DbwNode::override_brake_
private

Definition at line 98 of file DbwNode.h.

bool dbw_fca_can::DbwNode::override_gear_
private

Definition at line 101 of file DbwNode.h.

bool dbw_fca_can::DbwNode::override_steering_
private

Definition at line 100 of file DbwNode.h.

bool dbw_fca_can::DbwNode::override_throttle_
private

Definition at line 99 of file DbwNode.h.

bool dbw_fca_can::DbwNode::pedal_luts_
private

Definition at line 179 of file DbwNode.h.

bool dbw_fca_can::DbwNode::prev_enable_
private

Definition at line 96 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_brake_
private

Definition at line 203 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_brake_info_
private

Definition at line 213 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_can_
private

Definition at line 202 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_fuel_level_
private

Definition at line 212 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_gear_
private

Definition at line 206 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_gps_fix_
private

Definition at line 216 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_gps_fix_dr
private

Definition at line 218 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_gps_time_
private

Definition at line 217 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_imu_
private

Definition at line 215 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_joint_states_
private

Definition at line 219 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_misc_1_
private

Definition at line 207 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_misc_2_
private

Definition at line 208 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_steering_
private

Definition at line 205 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_sys_enable_
private

Definition at line 222 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_throttle_
private

Definition at line 204 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_throttle_info_
private

Definition at line 214 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_tire_pressure_
private

Definition at line 211 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_twist_
private

Definition at line 220 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_vin_
private

Definition at line 221 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_wheel_positions_
private

Definition at line 210 of file DbwNode.h.

ros::Publisher dbw_fca_can::DbwNode::pub_wheel_speeds_
private

Definition at line 209 of file DbwNode.h.

double dbw_fca_can::DbwNode::steering_ratio_
private

Definition at line 184 of file DbwNode.h.

ros::Subscriber dbw_fca_can::DbwNode::sub_brake_
private

Definition at line 194 of file DbwNode.h.

ros::Subscriber dbw_fca_can::DbwNode::sub_can_
private

Definition at line 193 of file DbwNode.h.

ros::Subscriber dbw_fca_can::DbwNode::sub_disable_
private

Definition at line 192 of file DbwNode.h.

ros::Subscriber dbw_fca_can::DbwNode::sub_enable_
private

Definition at line 191 of file DbwNode.h.

ros::Subscriber dbw_fca_can::DbwNode::sub_gear_
private

Definition at line 197 of file DbwNode.h.

ros::Subscriber dbw_fca_can::DbwNode::sub_misc_
private

Definition at line 199 of file DbwNode.h.

ros::Subscriber dbw_fca_can::DbwNode::sub_steering_
private

Definition at line 196 of file DbwNode.h.

ros::Subscriber dbw_fca_can::DbwNode::sub_throttle_
private

Definition at line 195 of file DbwNode.h.

ros::Subscriber dbw_fca_can::DbwNode::sub_turn_signal_
private

Definition at line 198 of file DbwNode.h.

dataspeed_can_msg_filters::ApproximateTime dbw_fca_can::DbwNode::sync_gps_
private

Definition at line 226 of file DbwNode.h.

dataspeed_can_msg_filters::ApproximateTime dbw_fca_can::DbwNode::sync_imu_
private

Definition at line 225 of file DbwNode.h.

bool dbw_fca_can::DbwNode::timeout_brakes_
private

Definition at line 109 of file DbwNode.h.

bool dbw_fca_can::DbwNode::timeout_steering_
private

Definition at line 111 of file DbwNode.h.

bool dbw_fca_can::DbwNode::timeout_throttle_
private

Definition at line 110 of file DbwNode.h.

ros::Timer dbw_fca_can::DbwNode::timer_
private

Definition at line 95 of file DbwNode.h.

std::string dbw_fca_can::DbwNode::vin_
private

Definition at line 162 of file DbwNode.h.

bool dbw_fca_can::DbwNode::warn_cmds_
private

Definition at line 173 of file DbwNode.h.

double dbw_fca_can::DbwNode::wheel_radius_
private

Definition at line 185 of file DbwNode.h.


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


dbw_fca_can
Author(s): Kevin Hallenbeck
autogenerated on Wed May 12 2021 02:14:05