33 #ifndef CONTROLLER_MANAGER_CONTROLLER_MANAGER_H 34 #define CONTROLLER_MANAGER_CONTROLLER_MANAGER_H 46 #include <controller_manager_msgs/ListControllerTypes.h> 47 #include <controller_manager_msgs/ListControllers.h> 48 #include <controller_manager_msgs/ReloadControllerLibraries.h> 49 #include <controller_manager_msgs/LoadController.h> 50 #include <controller_manager_msgs/UnloadController.h> 51 #include <controller_manager_msgs/SwitchController.h> 52 #include <boost/thread/condition.hpp> 53 #include <boost/thread/recursive_mutex.hpp> 140 const std::vector<std::string>& stop_controllers,
141 const int strictness);
202 controller_manager_msgs::ListControllerTypes::Response &resp);
204 controller_manager_msgs::ListControllers::Response &resp);
206 controller_manager_msgs::SwitchController::Response &resp);
208 controller_manager_msgs::LoadController::Response &resp);
210 controller_manager_msgs::UnloadController::Response &resp);
212 controller_manager_msgs::ReloadControllerLibraries::Response &resp);
bool switchControllerSrv(controller_manager_msgs::SwitchController::Request &req, controller_manager_msgs::SwitchController::Response &resp)
void getControllerNames(std::vector< std::string > &v)
ROS Controller Manager and Runner.
bool loadControllerSrv(controller_manager_msgs::LoadController::Request &req, controller_manager_msgs::LoadController::Response &resp)
std::vector< controller_interface::ControllerBase * > stop_request_
ros::ServiceServer srv_switch_controller_
bool loadController(const std::string &name)
Load a new controller by name.
boost::mutex services_lock_
bool switchController(const std::vector< std::string > &start_controllers, const std::vector< std::string > &stop_controllers, const int strictness)
Switch multiple controllers simultaneously.
int used_by_realtime_
The index of the controllers list being used in the real-time thread.
ros::ServiceServer srv_load_controller_
std::vector< ControllerSpec > controllers_lists_[2]
Double-buffered controllers list.
ros::ServiceServer srv_reload_libraries_
hardware_interface::RobotHW * robot_hw_
std::vector< controller_interface::ControllerBase * > start_request_
bool listControllerTypesSrv(controller_manager_msgs::ListControllerTypes::Request &req, controller_manager_msgs::ListControllerTypes::Response &resp)
virtual controller_interface::ControllerBase * getControllerByName(const std::string &name)
Get a controller by name.
ros::ServiceServer srv_list_controllers_
virtual ~ControllerManager()
bool unloadController(const std::string &name)
Unload a controller by name.
bool listControllersSrv(controller_manager_msgs::ListControllers::Request &req, controller_manager_msgs::ListControllers::Response &resp)
bool unloadControllerSrv(controller_manager_msgs::UnloadController::Request &req, controller_manager_msgs::UnloadController::Response &resp)
boost::recursive_mutex controllers_lock_
Mutex protecting the current controllers list.
ros::ServiceServer srv_unload_controller_
ros::ServiceServer srv_list_controller_types_
std::list< ControllerLoaderInterfaceSharedPtr > controller_loaders_
std::list< hardware_interface::ControllerInfo > switch_start_list_
int current_controllers_list_
The index of the current controllers list.
bool reloadControllerLibrariesSrv(controller_manager_msgs::ReloadControllerLibraries::Request &req, controller_manager_msgs::ReloadControllerLibraries::Response &resp)
ControllerManager(hardware_interface::RobotHW *robot_hw, const ros::NodeHandle &nh=ros::NodeHandle())
Constructor.
void registerControllerLoader(ControllerLoaderInterfaceSharedPtr controller_loader)
Register a controller loader.
std::list< hardware_interface::ControllerInfo > switch_stop_list_
void update(const ros::Time &time, const ros::Duration &period, bool reset_controllers=false)
Update all active controllers.