Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
dbw_polaris_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 (bool force=false)
 
void publishJointStates (const ros::Time &stamp, const dbw_polaris_msgs::SteeringReport *steering)
 
void recvBrakeCmd (const dbw_polaris_msgs::BrakeCmd::ConstPtr &msg)
 
void recvCalibrateSteering (const std_msgs::Empty::ConstPtr &msg)
 
void recvCAN (const can_msgs::Frame::ConstPtr &msg)
 
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_polaris_msgs::GearCmd::ConstPtr &msg)
 
void recvSteeringCmd (const dbw_polaris_msgs::SteeringCmd::ConstPtr &msg)
 
void recvThrottleCmd (const dbw_polaris_msgs::ThrottleCmd::ConstPtr &msg)
 
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 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_
 
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_can_
 
ros::Publisher pub_gear_
 
ros::Publisher pub_imu_
 
ros::Publisher pub_joint_states_
 
ros::Publisher pub_steering_
 
ros::Publisher pub_sys_enable_
 
ros::Publisher pub_throttle_
 
ros::Publisher pub_twist_
 
ros::Publisher pub_vin_
 
double steering_ratio_
 
ros::Subscriber sub_brake_
 
ros::Subscriber sub_calibrate_steering_
 
ros::Subscriber sub_can_
 
ros::Subscriber sub_disable_
 
ros::Subscriber sub_enable_
 
ros::Subscriber sub_gear_
 
ros::Subscriber sub_steering_
 
ros::Subscriber sub_throttle_
 
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 96 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 189 of file DbwNode.h.

Constructor & Destructor Documentation

◆ DbwNode()

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

Definition at line 71 of file DbwNode.cpp.

◆ ~DbwNode()

dbw_polaris_can::DbwNode::~DbwNode ( )

Definition at line 160 of file DbwNode.cpp.

Member Function Documentation

◆ buttonCancel()

void dbw_polaris_can::DbwNode::buttonCancel ( )
private

Definition at line 834 of file DbwNode.cpp.

◆ clear()

bool dbw_polaris_can::DbwNode::clear ( )
inlineprivate

Definition at line 169 of file DbwNode.h.

◆ disableSystem()

void dbw_polaris_can::DbwNode::disableSystem ( )
private

Definition at line 825 of file DbwNode.cpp.

◆ enabled()

bool dbw_polaris_can::DbwNode::enabled ( )
inlineprivate

Definition at line 170 of file DbwNode.h.

◆ enableSystem()

void dbw_polaris_can::DbwNode::enableSystem ( )
private

Definition at line 795 of file DbwNode.cpp.

◆ fault()

bool dbw_polaris_can::DbwNode::fault ( )
inlineprivate

Definition at line 167 of file DbwNode.h.

◆ faultBrakes()

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

Definition at line 943 of file DbwNode.cpp.

◆ faultSteering()

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

Definition at line 975 of file DbwNode.cpp.

◆ faultSteeringCal()

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

Definition at line 991 of file DbwNode.cpp.

◆ faultThrottle()

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

Definition at line 959 of file DbwNode.cpp.

◆ faultWatchdog() [1/2]

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

Definition at line 1007 of file DbwNode.cpp.

◆ faultWatchdog() [2/2]

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

Definition at line 1084 of file DbwNode.cpp.

◆ override()

bool dbw_polaris_can::DbwNode::override ( )
inlineprivate

Definition at line 168 of file DbwNode.h.

◆ overrideBrake()

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

Definition at line 843 of file DbwNode.cpp.

◆ overrideGear()

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

Definition at line 900 of file DbwNode.cpp.

◆ overrideSteering()

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

Definition at line 881 of file DbwNode.cpp.

◆ overrideThrottle()

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

Definition at line 862 of file DbwNode.cpp.

◆ publishDbwEnabled()

bool dbw_polaris_can::DbwNode::publishDbwEnabled ( bool  force = false)
private

Definition at line 736 of file DbwNode.cpp.

◆ publishJointStates()

void dbw_polaris_can::DbwNode::publishJointStates ( const ros::Time stamp,
const dbw_polaris_msgs::SteeringReport *  steering 
)
private

Definition at line 1088 of file DbwNode.cpp.

◆ recvBrakeCmd()

void dbw_polaris_can::DbwNode::recvBrakeCmd ( const dbw_polaris_msgs::BrakeCmd::ConstPtr &  msg)
private

Definition at line 573 of file DbwNode.cpp.

◆ recvCalibrateSteering()

void dbw_polaris_can::DbwNode::recvCalibrateSteering ( const std_msgs::Empty::ConstPtr &  msg)
private

Definition at line 720 of file DbwNode.cpp.

◆ recvCAN()

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

Definition at line 174 of file DbwNode.cpp.

◆ recvCanImu()

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

Definition at line 522 of file DbwNode.cpp.

◆ recvDisable()

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

Definition at line 169 of file DbwNode.cpp.

◆ recvEnable()

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

Definition at line 164 of file DbwNode.cpp.

◆ recvGearCmd()

void dbw_polaris_can::DbwNode::recvGearCmd ( const dbw_polaris_msgs::GearCmd::ConstPtr &  msg)
private

Definition at line 703 of file DbwNode.cpp.

◆ recvSteeringCmd()

void dbw_polaris_can::DbwNode::recvSteeringCmd ( const dbw_polaris_msgs::SteeringCmd::ConstPtr &  msg)
private

Definition at line 657 of file DbwNode.cpp.

◆ recvThrottleCmd()

void dbw_polaris_can::DbwNode::recvThrottleCmd ( const dbw_polaris_msgs::ThrottleCmd::ConstPtr &  msg)
private

Definition at line 613 of file DbwNode.cpp.

◆ sgn()

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

Definition at line 202 of file DbwNode.h.

◆ timeoutBrake()

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

Definition at line 916 of file DbwNode.cpp.

◆ timeoutSteering()

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

Definition at line 934 of file DbwNode.cpp.

◆ timeoutThrottle()

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

Definition at line 925 of file DbwNode.cpp.

◆ timerCallback()

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

Definition at line 749 of file DbwNode.cpp.

Member Data Documentation

◆ acker_track_

double dbw_polaris_can::DbwNode::acker_track_
private

Definition at line 225 of file DbwNode.h.

◆ acker_wheelbase_

double dbw_polaris_can::DbwNode::acker_wheelbase_
private

Definition at line 224 of file DbwNode.h.

◆ bdate_

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

Definition at line 209 of file DbwNode.h.

◆ enable_

bool dbw_polaris_can::DbwNode::enable_
private

Definition at line 148 of file DbwNode.h.

◆ enabled_brakes_

bool dbw_polaris_can::DbwNode::enabled_brakes_
private

Definition at line 163 of file DbwNode.h.

◆ enabled_steering_

bool dbw_polaris_can::DbwNode::enabled_steering_
private

Definition at line 165 of file DbwNode.h.

◆ enabled_throttle_

bool dbw_polaris_can::DbwNode::enabled_throttle_
private

Definition at line 164 of file DbwNode.h.

◆ fault_brakes_

bool dbw_polaris_can::DbwNode::fault_brakes_
private

Definition at line 153 of file DbwNode.h.

◆ fault_steering_

bool dbw_polaris_can::DbwNode::fault_steering_
private

Definition at line 155 of file DbwNode.h.

◆ fault_steering_cal_

bool dbw_polaris_can::DbwNode::fault_steering_cal_
private

Definition at line 156 of file DbwNode.h.

◆ fault_throttle_

bool dbw_polaris_can::DbwNode::fault_throttle_
private

Definition at line 154 of file DbwNode.h.

◆ fault_watchdog_

bool dbw_polaris_can::DbwNode::fault_watchdog_
private

Definition at line 157 of file DbwNode.h.

◆ fault_watchdog_using_brakes_

bool dbw_polaris_can::DbwNode::fault_watchdog_using_brakes_
private

Definition at line 158 of file DbwNode.h.

◆ fault_watchdog_warned_

bool dbw_polaris_can::DbwNode::fault_watchdog_warned_
private

Definition at line 159 of file DbwNode.h.

◆ firmware_

PlatformMap dbw_polaris_can::DbwNode::firmware_
private

Definition at line 212 of file DbwNode.h.

◆ frame_id_

std::string dbw_polaris_can::DbwNode::frame_id_
private

Definition at line 215 of file DbwNode.h.

◆ gear_warned_

bool dbw_polaris_can::DbwNode::gear_warned_
private

Definition at line 166 of file DbwNode.h.

◆ joint_state_

sensor_msgs::JointState dbw_polaris_can::DbwNode::joint_state_
private

Definition at line 198 of file DbwNode.h.

◆ ldate_

std::string dbw_polaris_can::DbwNode::ldate_
private

Definition at line 208 of file DbwNode.h.

◆ override_brake_

bool dbw_polaris_can::DbwNode::override_brake_
private

Definition at line 149 of file DbwNode.h.

◆ override_gear_

bool dbw_polaris_can::DbwNode::override_gear_
private

Definition at line 152 of file DbwNode.h.

◆ override_steering_

bool dbw_polaris_can::DbwNode::override_steering_
private

Definition at line 151 of file DbwNode.h.

◆ override_throttle_

bool dbw_polaris_can::DbwNode::override_throttle_
private

Definition at line 150 of file DbwNode.h.

◆ pedal_luts_

bool dbw_polaris_can::DbwNode::pedal_luts_
private

Definition at line 221 of file DbwNode.h.

◆ prev_enable_

bool dbw_polaris_can::DbwNode::prev_enable_
private

Definition at line 147 of file DbwNode.h.

◆ pub_brake_

ros::Publisher dbw_polaris_can::DbwNode::pub_brake_
private

Definition at line 241 of file DbwNode.h.

◆ pub_can_

ros::Publisher dbw_polaris_can::DbwNode::pub_can_
private

Definition at line 240 of file DbwNode.h.

◆ pub_gear_

ros::Publisher dbw_polaris_can::DbwNode::pub_gear_
private

Definition at line 244 of file DbwNode.h.

◆ pub_imu_

ros::Publisher dbw_polaris_can::DbwNode::pub_imu_
private

Definition at line 245 of file DbwNode.h.

◆ pub_joint_states_

ros::Publisher dbw_polaris_can::DbwNode::pub_joint_states_
private

Definition at line 246 of file DbwNode.h.

◆ pub_steering_

ros::Publisher dbw_polaris_can::DbwNode::pub_steering_
private

Definition at line 243 of file DbwNode.h.

◆ pub_sys_enable_

ros::Publisher dbw_polaris_can::DbwNode::pub_sys_enable_
private

Definition at line 249 of file DbwNode.h.

◆ pub_throttle_

ros::Publisher dbw_polaris_can::DbwNode::pub_throttle_
private

Definition at line 242 of file DbwNode.h.

◆ pub_twist_

ros::Publisher dbw_polaris_can::DbwNode::pub_twist_
private

Definition at line 247 of file DbwNode.h.

◆ pub_vin_

ros::Publisher dbw_polaris_can::DbwNode::pub_vin_
private

Definition at line 248 of file DbwNode.h.

◆ steering_ratio_

double dbw_polaris_can::DbwNode::steering_ratio_
private

Definition at line 226 of file DbwNode.h.

◆ sub_brake_

ros::Subscriber dbw_polaris_can::DbwNode::sub_brake_
private

Definition at line 233 of file DbwNode.h.

◆ sub_calibrate_steering_

ros::Subscriber dbw_polaris_can::DbwNode::sub_calibrate_steering_
private

Definition at line 237 of file DbwNode.h.

◆ sub_can_

ros::Subscriber dbw_polaris_can::DbwNode::sub_can_
private

Definition at line 232 of file DbwNode.h.

◆ sub_disable_

ros::Subscriber dbw_polaris_can::DbwNode::sub_disable_
private

Definition at line 231 of file DbwNode.h.

◆ sub_enable_

ros::Subscriber dbw_polaris_can::DbwNode::sub_enable_
private

Definition at line 230 of file DbwNode.h.

◆ sub_gear_

ros::Subscriber dbw_polaris_can::DbwNode::sub_gear_
private

Definition at line 236 of file DbwNode.h.

◆ sub_steering_

ros::Subscriber dbw_polaris_can::DbwNode::sub_steering_
private

Definition at line 235 of file DbwNode.h.

◆ sub_throttle_

ros::Subscriber dbw_polaris_can::DbwNode::sub_throttle_
private

Definition at line 234 of file DbwNode.h.

◆ sync_imu_

dataspeed_can_msg_filters::ApproximateTime dbw_polaris_can::DbwNode::sync_imu_
private

Definition at line 252 of file DbwNode.h.

◆ timeout_brakes_

bool dbw_polaris_can::DbwNode::timeout_brakes_
private

Definition at line 160 of file DbwNode.h.

◆ timeout_steering_

bool dbw_polaris_can::DbwNode::timeout_steering_
private

Definition at line 162 of file DbwNode.h.

◆ timeout_throttle_

bool dbw_polaris_can::DbwNode::timeout_throttle_
private

Definition at line 161 of file DbwNode.h.

◆ timer_

ros::Timer dbw_polaris_can::DbwNode::timer_
private

Definition at line 146 of file DbwNode.h.

◆ vin_

std::string dbw_polaris_can::DbwNode::vin_
private

Definition at line 207 of file DbwNode.h.

◆ warn_cmds_

bool dbw_polaris_can::DbwNode::warn_cmds_
private

Definition at line 218 of file DbwNode.h.

◆ wheel_radius_

double dbw_polaris_can::DbwNode::wheel_radius_
private

Definition at line 227 of file DbwNode.h.


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


dbw_polaris_can
Author(s): Kevin Hallenbeck
autogenerated on Thu Jan 4 2024 03:36:18