#include <controller_updater.h>
Public Types | |
typedef std::map< std::string, JointNames > | ControllerJoints |
enum | ControllerState { RUNNING, STOPPED } |
typedef std::map< std::string, ControllerState > | ControllerStates |
Public Member Functions | |
ControllerUpdater (ros::NodeHandle nh) | |
void | registerUpdateCb (const Callback &cb) |
virtual | ~ControllerUpdater () |
Private Types | |
typedef boost::function< void(const ControllerStates &states, const ControllerJoints &joints)> | Callback |
Private Member Functions | |
void | mainLoop () |
Private Attributes | |
ros::ServiceClient | cm_client_ |
ControllerStates | last_cstates_ |
boost::thread | main_thread_ |
ros::NodeHandle | nh_ |
Callback | update_cb_ |
ros::Timer | update_timer_ |
Keeps track of controller statuses by polling the controller manager. The service call happens in a separate thread to not disrupt the main code.
Definition at line 55 of file controller_updater.h.
typedef boost::function<void(const ControllerStates& states, const ControllerJoints& joints)> play_motion::ControllerUpdater::Callback [private] |
Definition at line 69 of file controller_updater.h.
typedef std::map<std::string, JointNames> play_motion::ControllerUpdater::ControllerJoints |
Definition at line 65 of file controller_updater.h.
typedef std::map<std::string, ControllerState> play_motion::ControllerUpdater::ControllerStates |
Definition at line 64 of file controller_updater.h.
Definition at line 58 of file controller_updater.h.
Definition at line 53 of file controller_updater.cpp.
play_motion::ControllerUpdater::~ControllerUpdater | ( | ) | [virtual] |
Definition at line 59 of file controller_updater.cpp.
void play_motion::ControllerUpdater::mainLoop | ( | ) | [private] |
Definition at line 74 of file controller_updater.cpp.
void play_motion::ControllerUpdater::registerUpdateCb | ( | const Callback & | cb | ) | [inline] |
Definition at line 75 of file controller_updater.h.
Definition at line 84 of file controller_updater.h.
Definition at line 85 of file controller_updater.h.
boost::thread play_motion::ControllerUpdater::main_thread_ [private] |
Definition at line 82 of file controller_updater.h.
Definition at line 80 of file controller_updater.h.
Definition at line 83 of file controller_updater.h.
Definition at line 81 of file controller_updater.h.