#include <motors_monitor.h>
Public Member Functions | |
MotorsMonitor (ros::NodeHandle *nh) | |
bool | ok () |
Protected Member Functions | |
int | lookForSeriousFault (uint8_t, const int) |
void | motor_feedback (const roboteq_msgs::FeedbackConstPtr, const int) |
void | motor_status (const roboteq_msgs::StatusConstPtr &, const int) |
void | msg_watchdog (const ros::TimerEvent &) |
Protected Attributes | |
ros::Publisher | estop_pub_ |
int | fault_level_ [4] |
ros::Subscriber | fb_sub_ [4] |
roboteq_msgs::FeedbackConstPtr | last_received_feedback_ [4] |
roboteq_msgs::StatusConstPtr | last_received_status_ [4] |
ros::Duration | motors_timeout_ |
ros::NodeHandle | nh_ |
ros::Subscriber | stat_sub_ [4] |
Definition at line 11 of file motors_monitor.h.
Definition at line 33 of file motors_monitor.cpp.
int MotorsMonitor::lookForSeriousFault | ( | uint8_t | fault_code, |
const int | motor_num | ||
) | [protected] |
Definition at line 90 of file motors_monitor.cpp.
void MotorsMonitor::motor_feedback | ( | const roboteq_msgs::FeedbackConstPtr | msg, |
const int | motor_num | ||
) | [protected] |
Definition at line 131 of file motors_monitor.cpp.
void MotorsMonitor::motor_status | ( | const roboteq_msgs::StatusConstPtr & | msg, |
const int | motor_num | ||
) | [protected] |
Definition at line 135 of file motors_monitor.cpp.
void MotorsMonitor::msg_watchdog | ( | const ros::TimerEvent & | ) | [protected] |
bool MotorsMonitor::ok | ( | ) |
Called in the context of whether cmd_vels may be passed through as safe.
Definition at line 64 of file motors_monitor.cpp.
ros::Publisher MotorsMonitor::estop_pub_ [protected] |
Definition at line 29 of file motors_monitor.h.
int MotorsMonitor::fault_level_[4] [protected] |
Definition at line 26 of file motors_monitor.h.
ros::Subscriber MotorsMonitor::fb_sub_[4] [protected] |
Definition at line 28 of file motors_monitor.h.
roboteq_msgs::FeedbackConstPtr MotorsMonitor::last_received_feedback_[4] [protected] |
Definition at line 32 of file motors_monitor.h.
roboteq_msgs::StatusConstPtr MotorsMonitor::last_received_status_[4] [protected] |
Definition at line 31 of file motors_monitor.h.
ros::Duration MotorsMonitor::motors_timeout_ [protected] |
Definition at line 30 of file motors_monitor.h.
ros::NodeHandle MotorsMonitor::nh_ [protected] |
Definition at line 18 of file motors_monitor.h.
ros::Subscriber MotorsMonitor::stat_sub_[4] [protected] |
Definition at line 28 of file motors_monitor.h.