Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes
dbw_fca_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 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 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 recvSteeringCmd (const dbw_fca_msgs::SteeringCmd::ConstPtr &msg)
void recvThrottleCmd (const dbw_fca_msgs::ThrottleCmd::ConstPtr &msg)
void recvTurnSignalCmd (const dbw_fca_msgs::TurnSignalCmd::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_
bool buttons_
std::string date_
bool enable_
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_
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_joint_states_
ros::Publisher pub_misc_1_
ros::Publisher pub_steering_
ros::Publisher pub_sys_enable_
ros::Publisher pub_throttle_
ros::Publisher pub_throttle_info_
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_steering_
ros::Subscriber sub_throttle_
ros::Subscriber sub_turn_signal_
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 69 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 129 of file DbwNode.h.


Constructor & Destructor Documentation

Definition at line 60 of file DbwNode.cpp.

Definition at line 154 of file DbwNode.cpp.


Member Function Documentation

Definition at line 848 of file DbwNode.cpp.

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

Definition at line 109 of file DbwNode.h.

Definition at line 839 of file DbwNode.cpp.

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

Definition at line 110 of file DbwNode.h.

Definition at line 809 of file DbwNode.cpp.

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

Definition at line 107 of file DbwNode.h.

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

Definition at line 957 of file DbwNode.cpp.

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

Definition at line 989 of file DbwNode.cpp.

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

Definition at line 1005 of file DbwNode.cpp.

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

Definition at line 973 of file DbwNode.cpp.

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

Definition at line 1021 of file DbwNode.cpp.

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

Definition at line 1098 of file DbwNode.cpp.

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

Definition at line 108 of file DbwNode.h.

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

Definition at line 857 of file DbwNode.cpp.

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

Definition at line 914 of file DbwNode.cpp.

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

Definition at line 895 of file DbwNode.cpp.

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

Definition at line 876 of file DbwNode.cpp.

Definition at line 755 of file DbwNode.cpp.

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

Definition at line 1102 of file DbwNode.cpp.

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

Definition at line 555 of file DbwNode.cpp.

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

: Multiplex PI/PC/PO types

Definition at line 168 of file DbwNode.cpp.

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

Definition at line 163 of file DbwNode.cpp.

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

Definition at line 158 of file DbwNode.cpp.

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

Definition at line 724 of file DbwNode.cpp.

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

Definition at line 678 of file DbwNode.cpp.

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

Definition at line 632 of file DbwNode.cpp.

void dbw_fca_can::DbwNode::recvTurnSignalCmd ( const dbw_fca_msgs::TurnSignalCmd::ConstPtr &  msg) [private]

Definition at line 741 of file DbwNode.cpp.

template<typename T >
static int dbw_fca_can::DbwNode::sgn ( T  val) [inline, static, private]

Definition at line 142 of file DbwNode.h.

float dbw_fca_can::DbwNode::speedSign ( ) const [inline, private]

Definition at line 147 of file DbwNode.h.

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

Definition at line 930 of file DbwNode.cpp.

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

Definition at line 948 of file DbwNode.cpp.

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

Definition at line 939 of file DbwNode.cpp.

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

Definition at line 769 of file DbwNode.cpp.


Member Data Documentation

Definition at line 173 of file DbwNode.h.

Definition at line 172 of file DbwNode.h.

Definition at line 166 of file DbwNode.h.

std::string dbw_fca_can::DbwNode::date_ [private]

Definition at line 154 of file DbwNode.h.

Definition at line 88 of file DbwNode.h.

Definition at line 103 of file DbwNode.h.

Definition at line 105 of file DbwNode.h.

Definition at line 104 of file DbwNode.h.

Definition at line 93 of file DbwNode.h.

Definition at line 95 of file DbwNode.h.

Definition at line 96 of file DbwNode.h.

Definition at line 94 of file DbwNode.h.

Definition at line 97 of file DbwNode.h.

Definition at line 98 of file DbwNode.h.

Definition at line 99 of file DbwNode.h.

Definition at line 157 of file DbwNode.h.

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

Definition at line 160 of file DbwNode.h.

Definition at line 106 of file DbwNode.h.

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

Definition at line 138 of file DbwNode.h.

Definition at line 89 of file DbwNode.h.

Definition at line 92 of file DbwNode.h.

Definition at line 91 of file DbwNode.h.

Definition at line 90 of file DbwNode.h.

Definition at line 169 of file DbwNode.h.

Definition at line 87 of file DbwNode.h.

Definition at line 189 of file DbwNode.h.

Definition at line 197 of file DbwNode.h.

Definition at line 188 of file DbwNode.h.

Definition at line 196 of file DbwNode.h.

Definition at line 192 of file DbwNode.h.

Definition at line 199 of file DbwNode.h.

Definition at line 193 of file DbwNode.h.

Definition at line 191 of file DbwNode.h.

Definition at line 202 of file DbwNode.h.

Definition at line 190 of file DbwNode.h.

Definition at line 198 of file DbwNode.h.

Definition at line 200 of file DbwNode.h.

Definition at line 201 of file DbwNode.h.

Definition at line 195 of file DbwNode.h.

Definition at line 194 of file DbwNode.h.

Definition at line 174 of file DbwNode.h.

Definition at line 181 of file DbwNode.h.

Definition at line 180 of file DbwNode.h.

Definition at line 179 of file DbwNode.h.

Definition at line 178 of file DbwNode.h.

Definition at line 184 of file DbwNode.h.

Definition at line 183 of file DbwNode.h.

Definition at line 182 of file DbwNode.h.

Definition at line 185 of file DbwNode.h.

Definition at line 100 of file DbwNode.h.

Definition at line 102 of file DbwNode.h.

Definition at line 101 of file DbwNode.h.

Definition at line 86 of file DbwNode.h.

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

Definition at line 153 of file DbwNode.h.

Definition at line 163 of file DbwNode.h.

Definition at line 175 of file DbwNode.h.


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


dbw_fca_can
Author(s): Kevin Hallenbeck
autogenerated on Sat May 4 2019 02:40:31