37 plugin_loader_(
"robot_controllers",
"robot_controllers::Controller"),
45 std::string controller_type;
47 if (nh.
getParam(
"type", controller_type))
bool stop(bool force)
This calls through to controller, saves state locally.
pluginlib::ClassLoader< robot_controllers::Controller > plugin_loader_
void update(const ros::Time &time, const ros::Duration &dt)
If controller is active, calls through to controller.
ControllerPtr getController()
Returns the controller held by this loader.
bool start()
This calls through to controller, saves state locally.
Base class for a controller manager.
ControllerLoader()
Initialize this loader.
bool init(const std::string &name, ControllerManager *manager)
Load the controller.
bool isActive()
Returns true if the controller is active.
bool getParam(const std::string &key, std::string &s) const
bool reset()
This calls through to controller.
#define ROS_ERROR_STREAM(args)
ControllerPtr controller_