ros2_control - humble
Loading...
Searching...
No Matches
Classes | Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | List of all members
controller_manager::ControllerManager Class Reference
Inheritance diagram for controller_manager::ControllerManager:
Inheritance graph
[legend]
Collaboration diagram for controller_manager::ControllerManager:
Collaboration graph
[legend]

Public Member Functions

CONTROLLER_MANAGER_PUBLIC ControllerManager (std::unique_ptr< hardware_interface::ResourceManager > resource_manager, std::shared_ptr< rclcpp::Executor > executor, const std::string &manager_node_name="controller_manager", const std::string &namespace_="", const rclcpp::NodeOptions &options=get_cm_node_options())
 
CONTROLLER_MANAGER_PUBLIC ControllerManager (std::shared_ptr< rclcpp::Executor > executor, const std::string &manager_node_name="controller_manager", const std::string &namespace_="", const rclcpp::NodeOptions &options=get_cm_node_options())
 
CONTROLLER_MANAGER_PUBLIC void robot_description_callback (const std_msgs::msg::String &msg)
 
CONTROLLER_MANAGER_PUBLIC void init_resource_manager (const std::string &robot_description)
 
CONTROLLER_MANAGER_PUBLIC controller_interface::ControllerInterfaceBaseSharedPtr load_controller (const std::string &controller_name, const std::string &controller_type)
 
CONTROLLER_MANAGER_PUBLIC controller_interface::ControllerInterfaceBaseSharedPtr load_controller (const std::string &controller_name)
 load_controller loads a controller by name, the type must be defined in the parameter server.
 
CONTROLLER_MANAGER_PUBLIC controller_interface::return_type unload_controller (const std::string &controller_name)
 
CONTROLLER_MANAGER_PUBLIC std::vector< ControllerSpecget_loaded_controllers () const
 
template<typename T , typename std::enable_if< std::is_convertible< T *, controller_interface::ControllerInterfaceBase * >::value, T >::type * = nullptr>
controller_interface::ControllerInterfaceBaseSharedPtr add_controller (std::shared_ptr< T > controller, const std::string &controller_name, const std::string &controller_type)
 
CONTROLLER_MANAGER_PUBLIC controller_interface::return_type configure_controller (const std::string &controller_name)
 configure_controller Configure controller by name calling their "configure" method.
 
CONTROLLER_MANAGER_PUBLIC controller_interface::return_type switch_controller (const std::vector< std::string > &start_controllers, const std::vector< std::string > &stop_controllers, int strictness, bool activate_asap=kWaitForAllResources, const rclcpp::Duration &timeout=rclcpp::Duration::from_nanoseconds(kInfiniteTimeout))
 switch_controller Stops some controllers and start others.
 
CONTROLLER_MANAGER_PUBLIC void read (const rclcpp::Time &time, const rclcpp::Duration &period)
 Read values to state interfaces.
 
CONTROLLER_MANAGER_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period)
 Run update on controllers.
 
CONTROLLER_MANAGER_PUBLIC void write (const rclcpp::Time &time, const rclcpp::Duration &period)
 Write values from command interfaces.
 
CONTROLLER_MANAGER_PUBLIC unsigned int get_update_rate () const
 Deterministic (real-time safe) callback group, e.g., update function.
 

Static Public Attributes

static constexpr bool kWaitForAllResources = false
 
static constexpr auto kInfiniteTimeout = 0
 

Protected Member Functions

CONTROLLER_MANAGER_PUBLIC void init_services ()
 
CONTROLLER_MANAGER_PUBLIC controller_interface::ControllerInterfaceBaseSharedPtr add_controller_impl (const ControllerSpec &controller)
 
CONTROLLER_MANAGER_PUBLIC void manage_switch ()
 
CONTROLLER_MANAGER_PUBLIC void deactivate_controllers ()
 
CONTROLLER_MANAGER_PUBLIC void switch_chained_mode (const std::vector< std::string > &chained_mode_switch_list, bool to_chained_mode)
 
CONTROLLER_MANAGER_PUBLIC void activate_controllers ()
 
CONTROLLER_MANAGER_PUBLIC void activate_controllers_asap ()
 
CONTROLLER_MANAGER_PUBLIC void list_controllers_srv_cb (const std::shared_ptr< controller_manager_msgs::srv::ListControllers::Request > request, std::shared_ptr< controller_manager_msgs::srv::ListControllers::Response > response)
 
CONTROLLER_MANAGER_PUBLIC void list_hardware_interfaces_srv_cb (const std::shared_ptr< controller_manager_msgs::srv::ListHardwareInterfaces::Request > request, std::shared_ptr< controller_manager_msgs::srv::ListHardwareInterfaces::Response > response)
 
CONTROLLER_MANAGER_PUBLIC void load_controller_service_cb (const std::shared_ptr< controller_manager_msgs::srv::LoadController::Request > request, std::shared_ptr< controller_manager_msgs::srv::LoadController::Response > response)
 
CONTROLLER_MANAGER_PUBLIC void configure_controller_service_cb (const std::shared_ptr< controller_manager_msgs::srv::ConfigureController::Request > request, std::shared_ptr< controller_manager_msgs::srv::ConfigureController::Response > response)
 
CONTROLLER_MANAGER_PUBLIC void reload_controller_libraries_service_cb (const std::shared_ptr< controller_manager_msgs::srv::ReloadControllerLibraries::Request > request, std::shared_ptr< controller_manager_msgs::srv::ReloadControllerLibraries::Response > response)
 
CONTROLLER_MANAGER_PUBLIC void switch_controller_service_cb (const std::shared_ptr< controller_manager_msgs::srv::SwitchController::Request > request, std::shared_ptr< controller_manager_msgs::srv::SwitchController::Response > response)
 
CONTROLLER_MANAGER_PUBLIC void unload_controller_service_cb (const std::shared_ptr< controller_manager_msgs::srv::UnloadController::Request > request, std::shared_ptr< controller_manager_msgs::srv::UnloadController::Response > response)
 
CONTROLLER_MANAGER_PUBLIC void list_controller_types_srv_cb (const std::shared_ptr< controller_manager_msgs::srv::ListControllerTypes::Request > request, std::shared_ptr< controller_manager_msgs::srv::ListControllerTypes::Response > response)
 
CONTROLLER_MANAGER_PUBLIC void list_hardware_components_srv_cb (const std::shared_ptr< controller_manager_msgs::srv::ListHardwareComponents::Request > request, std::shared_ptr< controller_manager_msgs::srv::ListHardwareComponents::Response > response)
 
CONTROLLER_MANAGER_PUBLIC void set_hardware_component_state_srv_cb (const std::shared_ptr< controller_manager_msgs::srv::SetHardwareComponentState::Request > request, std::shared_ptr< controller_manager_msgs::srv::SetHardwareComponentState::Response > response)
 

Protected Attributes

unsigned int update_loop_counter_ = 0
 
unsigned int update_rate_ = 100
 
std::vector< std::vector< std::string > > chained_controllers_configuration_
 
std::unique_ptr< hardware_interface::ResourceManagerresource_manager_
 

Member Function Documentation

◆ configure_controller()

controller_interface::return_type controller_manager::ControllerManager::configure_controller ( const std::string &  controller_name)

configure_controller Configure controller by name calling their "configure" method.

Parameters
[in]controller_nameas a string.
Returns
configure controller response
See also
Documentation in controller_manager_msgs/ConfigureController.srv

◆ get_update_rate()

unsigned int controller_manager::ControllerManager::get_update_rate ( ) const

Deterministic (real-time safe) callback group, e.g., update function.

Deterministic (real-time safe) callback group for the update function. Default behavior is read hardware, update controller and finally write new values to the hardware.

◆ load_controller()

controller_interface::ControllerInterfaceBaseSharedPtr controller_manager::ControllerManager::load_controller ( const std::string &  controller_name)

load_controller loads a controller by name, the type must be defined in the parameter server.

Parameters
[in]controller_nameas a string.
Returns
controller
See also
Documentation in controller_manager_msgs/LoadController.srv

◆ read()

void controller_manager::ControllerManager::read ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)

Read values to state interfaces.

Read current values from hardware to state interfaces. The method called in the (real-time) control loop.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured period of the last control loop iteration

◆ switch_chained_mode()

void controller_manager::ControllerManager::switch_chained_mode ( const std::vector< std::string > &  chained_mode_switch_list,
bool  to_chained_mode 
)
protected

Switch chained mode for all the controllers with respect to the following cases:

  • a preceding controller is getting activated --> switch controller to chained mode;
  • all preceding controllers are deactivated --> switch controller from chained mode.
Parameters
[in]chained_mode_switch_listlist of controller to switch chained mode.
[in]to_chained_modeflag if controller should be switched to or from chained mode.

◆ switch_controller()

controller_interface::return_type controller_manager::ControllerManager::switch_controller ( const std::vector< std::string > &  start_controllers,
const std::vector< std::string > &  stop_controllers,
int  strictness,
bool  activate_asap = kWaitForAllResources,
const rclcpp::Duration &  timeout = rclcpp::Duration::from_nanoseconds(kInfiniteTimeout) 
)

switch_controller Stops some controllers and start others.

Parameters
[in]start_controllersis a list of controllers to start
[in]stop_controllersis a list of controllers to stop
[in]setlevel of strictness (BEST_EFFORT or STRICT)
See also
Documentation in controller_manager_msgs/SwitchController.srv
Note
The following is the case of the real controllers that are deactivated and doesn't include the chained controllers that are deactivated and activated

◆ update()

controller_interface::return_type controller_manager::ControllerManager::update ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)

Run update on controllers.

Call update of all controllers. The method called in the (real-time) control loop.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured period of the last control loop iteration

◆ write()

void controller_manager::ControllerManager::write ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)

Write values from command interfaces.

Write values from command interface into hardware. The method called in the (real-time) control loop.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured period of the last control loop iteration

The documentation for this class was generated from the following files: