31 #ifndef ROBOT_CONTROLLERS_INTERFACE_CONTROLLER_MANAGER_H 32 #define ROBOT_CONTROLLERS_INTERFACE_CONTROLLER_MANAGER_H 38 #include <robot_controllers_msgs/QueryControllerStatesAction.h> 103 void execute(
const robot_controllers_msgs::QueryControllerStatesGoalConstPtr&
goal);
106 void getState(robot_controllers_msgs::QueryControllerStatesResult&
result);
109 bool load(
const std::string& name);
119 #endif // ROBOT_CONTROLLERS_INTERFACE_CONTROLLER_MANAGER_H virtual void reset()
Reset all controllers.
std::vector< JointHandlePtr > JointHandleList
bool load(const std::string &name)
Load a controller.
virtual int init(ros::NodeHandle &nh)
Startup the controller manager, loading default controllers.
virtual int requestStart(const std::string &name)
Start a controller.
actionlib::SimpleActionServer< robot_controllers_msgs::QueryControllerStatesAction > server_t
HandlePtr getHandle(const std::string &name)
Get the handle associated with a particular joint/controller name.
bool addJointHandle(JointHandlePtr &j)
Add a joint handle.
Base class for a controller manager.
virtual int requestStop(const std::string &name)
Stop a controller.
std::vector< ControllerLoaderPtr > ControllerList
void execute(const robot_controllers_msgs::QueryControllerStatesGoalConstPtr &goal)
Action callback.
void getState(robot_controllers_msgs::QueryControllerStatesResult &result)
Fill in the current state of controllers.
boost::shared_ptr< server_t > server_
ControllerList controllers_
JointHandlePtr getJointHandle(const std::string &name)
Get the joint handle associated with a particular joint name.
virtual ~ControllerManager()
Ensure proper shutdown with virtual destructor.
virtual void update(const ros::Time &time, const ros::Duration &dt)
Update active controllers.