Base class for a controller manager. More...
#include <controller_manager.h>
Public Member Functions | |
bool | addJointHandle (JointHandlePtr &j) |
Add a joint handle. | |
ControllerManager () | |
HandlePtr | getHandle (const std::string &name) |
Get the handle associated with a particular joint/controller name. | |
JointHandlePtr | getJointHandle (const std::string &name) |
Get the joint handle associated with a particular joint name. | |
virtual int | init (ros::NodeHandle &nh) |
Startup the controller manager, loading default controllers. | |
virtual int | requestStart (const std::string &name) |
Start a controller. | |
virtual int | requestStop (const std::string &name) |
Stop a controller. | |
virtual void | reset () |
Reset all controllers. | |
virtual void | update (const ros::Time &time, const ros::Duration &dt) |
Update active controllers. | |
virtual | ~ControllerManager () |
Ensure proper shutdown with virtual destructor. | |
Private Types | |
typedef std::vector < ControllerLoaderPtr > | ControllerList |
typedef std::vector < JointHandlePtr > | JointHandleList |
typedef actionlib::SimpleActionServer < robot_controllers_msgs::QueryControllerStatesAction > | server_t |
Private Member Functions | |
void | execute (const robot_controllers_msgs::QueryControllerStatesGoalConstPtr &goal) |
Action callback. | |
void | getState (robot_controllers_msgs::QueryControllerStatesResult &result) |
Fill in the current state of controllers. | |
bool | load (const std::string &name) |
Load a controller. | |
Private Attributes | |
ControllerList | controllers_ |
JointHandleList | joints_ |
boost::shared_ptr< server_t > | server_ |
Base class for a controller manager.
Definition at line 48 of file controller_manager.h.
typedef std::vector<ControllerLoaderPtr> robot_controllers::ControllerManager::ControllerList [private] |
Definition at line 52 of file controller_manager.h.
typedef std::vector<JointHandlePtr> robot_controllers::ControllerManager::JointHandleList [private] |
Definition at line 53 of file controller_manager.h.
typedef actionlib::SimpleActionServer<robot_controllers_msgs::QueryControllerStatesAction> robot_controllers::ControllerManager::server_t [private] |
Definition at line 50 of file controller_manager.h.
Definition at line 37 of file controller_manager.cpp.
virtual robot_controllers::ControllerManager::~ControllerManager | ( | ) | [inline, virtual] |
Ensure proper shutdown with virtual destructor.
Definition at line 59 of file controller_manager.h.
Add a joint handle.
Definition at line 206 of file controller_manager.cpp.
void robot_controllers::ControllerManager::execute | ( | const robot_controllers_msgs::QueryControllerStatesGoalConstPtr & | goal | ) | [private] |
Action callback.
Definition at line 246 of file controller_manager.cpp.
HandlePtr robot_controllers::ControllerManager::getHandle | ( | const std::string & | name | ) |
Get the handle associated with a particular joint/controller name.
name | The name of the joint/controller. |
Definition at line 213 of file controller_manager.cpp.
JointHandlePtr robot_controllers::ControllerManager::getJointHandle | ( | const std::string & | name | ) |
Get the joint handle associated with a particular joint name.
name | The name of the joint. |
This is mainly a convienence function.
Definition at line 233 of file controller_manager.cpp.
void robot_controllers::ControllerManager::getState | ( | robot_controllers_msgs::QueryControllerStatesResult & | result | ) | [private] |
Fill in the current state of controllers.
Definition at line 346 of file controller_manager.cpp.
int robot_controllers::ControllerManager::init | ( | ros::NodeHandle & | nh | ) | [virtual] |
Startup the controller manager, loading default controllers.
nh | The proper node handle for finding parameters. |
Note: JointHandles should be added before this is called.
Definition at line 41 of file controller_manager.cpp.
bool robot_controllers::ControllerManager::load | ( | const std::string & | name | ) | [private] |
Load a controller.
Definition at line 368 of file controller_manager.cpp.
int robot_controllers::ControllerManager::requestStart | ( | const std::string & | name | ) | [virtual] |
Start a controller.
Definition at line 85 of file controller_manager.cpp.
int robot_controllers::ControllerManager::requestStop | ( | const std::string & | name | ) | [virtual] |
Stop a controller.
Definition at line 162 of file controller_manager.cpp.
void robot_controllers::ControllerManager::reset | ( | ) | [virtual] |
Reset all controllers.
Definition at line 197 of file controller_manager.cpp.
void robot_controllers::ControllerManager::update | ( | const ros::Time & | time, |
const ros::Duration & | dt | ||
) | [virtual] |
Update active controllers.
Definition at line 184 of file controller_manager.cpp.
Definition at line 111 of file controller_manager.h.
Definition at line 112 of file controller_manager.h.
boost::shared_ptr<server_t> robot_controllers::ControllerManager::server_ [private] |
Definition at line 114 of file controller_manager.h.