45 #include <controller_manager_msgs/ListControllerTypes.h> 46 #include <controller_manager_msgs/ListControllers.h> 47 #include <controller_manager_msgs/ReloadControllerLibraries.h> 48 #include <controller_manager_msgs/LoadController.h> 49 #include <controller_manager_msgs/UnloadController.h> 50 #include <controller_manager_msgs/SwitchController.h> 144 const std::vector<std::string>& stop_controllers,
145 const int strictness,
bool start_asap = WAIT_FOR_ALL_RESOURCES,
146 double timeout = INFINITE_TIMEOUT);
225 controller_manager_msgs::ListControllerTypes::Response &resp);
227 controller_manager_msgs::ListControllers::Response &resp);
229 controller_manager_msgs::SwitchController::Response &resp);
231 controller_manager_msgs::LoadController::Response &resp);
233 controller_manager_msgs::UnloadController::Response &resp);
235 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_
void startControllersAsap(const ros::Time &time)
static constexpr double INFINITE_TIMEOUT
ros::ServiceServer srv_switch_controller_
bool loadController(const std::string &name)
Load a new controller by name.
void stopControllers(const ros::Time &time)
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_
void manageSwitch(const ros::Time &time)
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)
bool switchController(const std::vector< std::string > &start_controllers, const std::vector< std::string > &stop_controllers, const int strictness, bool start_asap=WAIT_FOR_ALL_RESOURCES, double timeout=INFINITE_TIMEOUT)
Switch multiple controllers simultaneously.
virtual controller_interface::ControllerBase * getControllerByName(const std::string &name)
Get a controller by name.
ros::ServiceServer srv_list_controllers_
bool unloadController(const std::string &name)
Unload a controller by name.
SwitchParams switch_params_
bool listControllersSrv(controller_manager_msgs::ListControllers::Request &req, controller_manager_msgs::ListControllers::Response &resp)
static constexpr bool WAIT_FOR_ALL_RESOURCES
ROSTIME_DECL const Time TIME_MAX
virtual ~ControllerManager()=default
bool unloadControllerSrv(controller_manager_msgs::UnloadController::Request &req, controller_manager_msgs::UnloadController::Response &resp)
std::shared_ptr< ControllerLoaderInterface > ControllerLoaderInterfaceSharedPtr
ros::ServiceServer srv_unload_controller_
ros::ServiceServer srv_list_controller_types_
std::mutex services_lock_
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)
void startControllers(const ros::Time &time)
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.
std::recursive_mutex controllers_lock_
Mutex protecting the current controllers list.