Go to the documentation of this file.
41 #include <can_msgs/Frame.h>
43 #include <dbw_polaris_msgs/BrakeCmd.h>
44 #include <dbw_polaris_msgs/BrakeReport.h>
45 #include <dbw_polaris_msgs/ThrottleCmd.h>
46 #include <dbw_polaris_msgs/ThrottleReport.h>
47 #include <dbw_polaris_msgs/SteeringCmd.h>
48 #include <dbw_polaris_msgs/SteeringReport.h>
49 #include <dbw_polaris_msgs/GearCmd.h>
50 #include <dbw_polaris_msgs/GearReport.h>
51 #include <sensor_msgs/Imu.h>
52 #include <sensor_msgs/JointState.h>
53 #include <geometry_msgs/TwistStamped.h>
54 #include <std_msgs/Empty.h>
55 #include <std_msgs/Bool.h>
56 #include <std_msgs/String.h>
72 void recvEnable(
const std_msgs::Empty::ConstPtr& msg);
73 void recvDisable(
const std_msgs::Empty::ConstPtr& msg);
74 void recvCAN(
const can_msgs::Frame::ConstPtr& msg);
75 void recvCanImu(
const std::vector<can_msgs::Frame::ConstPtr> &msgs);
76 void recvBrakeCmd(
const dbw_polaris_msgs::BrakeCmd::ConstPtr& msg);
77 void recvThrottleCmd(
const dbw_polaris_msgs::ThrottleCmd::ConstPtr& msg);
78 void recvSteeringCmd(
const dbw_polaris_msgs::SteeringCmd::ConstPtr& msg);
79 void recvGearCmd(
const dbw_polaris_msgs::GearCmd::ConstPtr& msg);
138 template <
typename T>
static int sgn(T val) {
139 return ((T)0 < val) - (val < (T)0);
145 std::map<uint8_t, std::string>
bdate_;
193 #endif // _DBW_NODE_H_
void faultBrakes(bool fault)
void faultSteeringCal(bool fault)
ros::Publisher pub_joint_states_
dataspeed_can_msg_filters::ApproximateTime sync_imu_
void recvGearCmd(const dbw_polaris_msgs::GearCmd::ConstPtr &msg)
ros::Subscriber sub_gear_
void recvSteeringCmd(const dbw_polaris_msgs::SteeringCmd::ConstPtr &msg)
ros::Subscriber sub_brake_
void timerCallback(const ros::TimerEvent &event)
ros::Publisher pub_throttle_
ros::Subscriber sub_enable_
bool fault_watchdog_using_brakes_
sensor_msgs::JointState joint_state_
void recvThrottleCmd(const dbw_polaris_msgs::ThrottleCmd::ConstPtr &msg)
ros::Subscriber sub_steering_
ros::Subscriber sub_throttle_
ros::Subscriber sub_calibrate_steering_
ros::Publisher pub_sys_enable_
bool fault_watchdog_warned_
void recvBrakeCmd(const dbw_polaris_msgs::BrakeCmd::ConstPtr &msg)
ros::Publisher pub_twist_
void recvCAN(const can_msgs::Frame::ConstPtr &msg)
void recvCalibrateSteering(const std_msgs::Empty::ConstPtr &msg)
void faultWatchdog(bool fault, uint8_t src, bool braking)
void faultSteering(bool fault)
void recvCanImu(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
void faultThrottle(bool fault)
void recvEnable(const std_msgs::Empty::ConstPtr &msg)
void recvDisable(const std_msgs::Empty::ConstPtr &msg)
ros::Publisher pub_brake_
std::map< uint8_t, std::string > bdate_
ros::Subscriber sub_disable_
void timeoutThrottle(bool timeout, bool enabled)
ros::Publisher pub_steering_
void overrideSteering(bool override, bool timeout)
void timeoutSteering(bool timeout, bool enabled)
DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
bool publishDbwEnabled(bool force=false)
void overrideThrottle(bool override, bool timeout)
void publishJointStates(const ros::Time &stamp, const dbw_polaris_msgs::SteeringReport *steering)
void timeoutBrake(bool timeout, bool enabled)
void overrideBrake(bool override, bool timeout)
void overrideGear(bool override)
dbw_polaris_can
Author(s): Kevin Hallenbeck
autogenerated on Thu Jan 4 2024 03:36:18