#include <esc_ros.h>
Public Member Functions | |
virtual void | enableCallback (std_msgs::Bool msg) |
ESCROS (ros::NodeHandle *n=NULL) | |
virtual void | init (ESC *esc) |
virtual void | reset () |
virtual void | spin () |
virtual void | step () |
virtual | ~ESCROS () |
Protected Member Functions | |
virtual void | objValCallback (std_msgs::Float32 msg) |
virtual void | objValWithStateCallback (esc_ros::StateValue msg) |
Protected Attributes | |
bool | enabled_ |
ESC * | esc_ |
bool | first_obj_val_received_ |
bool | initialized_ |
bool | monitor_ |
ros::NodeHandle * | n_ |
double | obj_val_ |
unsigned int | opt_dim_ |
double | period_ |
ros::Publisher | pub_monitor_ |
ros::Publisher | pub_ref_ |
ros::Publisher | pub_stopped_ |
bool | reference_zeroed_ |
std::vector< double > | state_vec_ |
ros::Subscriber | sub_enable_ |
ros::Subscriber | sub_obj_val_ |
ESCROS::ESCROS | ( | ros::NodeHandle * | n = NULL | ) |
Definition at line 14 of file esc_ros.cpp.
virtual ESCROS::~ESCROS | ( | ) | [inline, virtual] |
void ESCROS::enableCallback | ( | std_msgs::Bool | msg | ) | [virtual] |
Definition at line 87 of file esc_ros.cpp.
void ESCROS::init | ( | ESC * | esc | ) | [virtual] |
Definition at line 20 of file esc_ros.cpp.
void ESCROS::objValCallback | ( | std_msgs::Float32 | msg | ) | [protected, virtual] |
Definition at line 71 of file esc_ros.cpp.
void ESCROS::objValWithStateCallback | ( | esc_ros::StateValue | msg | ) | [protected, virtual] |
Definition at line 61 of file esc_ros.cpp.
void ESCROS::reset | ( | ) | [virtual] |
Definition at line 79 of file esc_ros.cpp.
void ESCROS::spin | ( | ) | [virtual] |
Definition at line 160 of file esc_ros.cpp.
void ESCROS::step | ( | ) | [virtual] |
Definition at line 99 of file esc_ros.cpp.
bool ESCROS::enabled_ [protected] |
ESC* ESCROS::esc_ [protected] |
bool ESCROS::first_obj_val_received_ [protected] |
bool ESCROS::initialized_ [protected] |
bool ESCROS::monitor_ [protected] |
ros::NodeHandle* ESCROS::n_ [protected] |
double ESCROS::obj_val_ [protected] |
unsigned int ESCROS::opt_dim_ [protected] |
double ESCROS::period_ [protected] |
ros::Publisher ESCROS::pub_monitor_ [protected] |
ros::Publisher ESCROS::pub_ref_ [protected] |
ros::Publisher ESCROS::pub_stopped_ [protected] |
bool ESCROS::reference_zeroed_ [protected] |
std::vector<double> ESCROS::state_vec_ [protected] |
ros::Subscriber ESCROS::sub_enable_ [protected] |
ros::Subscriber ESCROS::sub_obj_val_ [protected] |