Loading [MathJax]/jax/output/HTML-CSS/config.js
ros2_control - rolling
All Classes Namespaces Functions Variables Typedefs Enumerations Pages
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

 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 &node_namespace="", const rclcpp::NodeOptions &options=get_cm_node_options())
 
 ControllerManager (std::shared_ptr< rclcpp::Executor > executor, const std::string &manager_node_name="controller_manager", const std::string &node_namespace="", const rclcpp::NodeOptions &options=get_cm_node_options())
 
 ControllerManager (std::shared_ptr< rclcpp::Executor > executor, const std::string &urdf, bool activate_all_hw_components, const std::string &manager_node_name="controller_manager", const std::string &node_namespace="", const rclcpp::NodeOptions &options=get_cm_node_options())
 
bool shutdown_controllers ()
 Shutdown all controllers in the controller manager.
 
void robot_description_callback (const std_msgs::msg::String &msg)
 
void init_resource_manager (const std::string &robot_description)
 
controller_interface::ControllerInterfaceBaseSharedPtr load_controller (const std::string &controller_name, const std::string &controller_type)
 
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_interface::return_type unload_controller (const std::string &controller_name)
 
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_interface::ControllerInterfaceBaseSharedPtr add_controller (const ControllerSpec &controller_spec)
 
controller_interface::return_type configure_controller (const std::string &controller_name)
 configure_controller Configure controller by name calling their "configure" method.
 
controller_interface::return_type switch_controller (const std::vector< std::string > &activate_controllers, const std::vector< std::string > &deactivate_controllers, int strictness, bool activate_asap=kWaitForAllResources, const rclcpp::Duration &timeout=rclcpp::Duration::from_nanoseconds(kInfiniteTimeout))
 switch_controller Deactivates some controllers and activates others.
 
controller_interface::return_type switch_controller_cb (const std::vector< std::string > &activate_controllers, const std::vector< std::string > &deactivate_controllers, int strictness, bool activate_asap, const rclcpp::Duration &timeout, std::string &message)
 switch_controller Deactivates some controllers and activates others.
 
void read (const rclcpp::Time &time, const rclcpp::Duration &period)
 Read values to state interfaces.
 
controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period)
 Run update on controllers.
 
void write (const rclcpp::Time &time, const rclcpp::Duration &period)
 Write values from command interfaces.
 
bool is_resource_manager_initialized () const
 Deterministic (real-time safe) callback group, e.g., update function.
 
unsigned int get_update_rate () const
 Update rate of the main control loop in the controller manager.
 
rclcpp::Clock::SharedPtr get_trigger_clock () const
 Get the trigger clock of the controller manager.
 

Static Public Attributes

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

Protected Member Functions

void init_services ()
 
controller_interface::ControllerInterfaceBaseSharedPtr add_controller_impl (const ControllerSpec &controller)
 
void manage_switch ()
 
void deactivate_controllers (const std::vector< ControllerSpec > &rt_controller_list, const std::vector< std::string > controllers_to_deactivate)
 Deactivate chosen controllers from real-time controller list.
 
void switch_chained_mode (const std::vector< std::string > &chained_mode_switch_list, bool to_chained_mode)
 
void activate_controllers (const std::vector< ControllerSpec > &rt_controller_list, const std::vector< std::string > controllers_to_activate)
 Activate chosen controllers from real-time controller list.
 
void activate_controllers_asap (const std::vector< ControllerSpec > &rt_controller_list, const std::vector< std::string > controllers_to_activate)
 Activate chosen controllers from real-time controller list.
 
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)
 
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)
 
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)
 
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)
 
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)
 
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)
 
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)
 
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)
 
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)
 
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_
 
std::vector< std::vector< std::string > > chained_controllers_configuration_
 
std::unique_ptr< hardware_interface::ResourceManagerresource_manager_
 

Member Function Documentation

◆ activate_controllers()

void controller_manager::ControllerManager::activate_controllers ( const std::vector< ControllerSpec > &  rt_controller_list,
const std::vector< std::string >  controllers_to_activate 
)
protected

Activate chosen controllers from real-time controller list.

Activate controllers with names controllers_to_activate from list rt_controller_list. The controller list will be iterated as many times as there are controller names.

Parameters
[in]rt_controller_listcontrollers in the real-time list.
[in]controllers_to_activatenames of the controller that have to be activated.

◆ activate_controllers_asap()

void controller_manager::ControllerManager::activate_controllers_asap ( const std::vector< ControllerSpec > &  rt_controller_list,
const std::vector< std::string >  controllers_to_activate 
)
protected

Activate chosen controllers from real-time controller list.

Activate controllers with names controllers_to_activate from list rt_controller_list. The controller list will be iterated as many times as there are controller names.

NOTE: There is currently not difference to activate_controllers method. Check https://github.com/ros-controls/ros2_control/issues/263 for more information.

Parameters
[in]rt_controller_listcontrollers in the real-time list.
[in]controllers_to_activatenames of the controller that have to be activated.

◆ 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

◆ deactivate_controllers()

void controller_manager::ControllerManager::deactivate_controllers ( const std::vector< ControllerSpec > &  rt_controller_list,
const std::vector< std::string >  controllers_to_deactivate 
)
protected

Deactivate chosen controllers from real-time controller list.

Deactivate controllers with names controllers_to_deactivate from list rt_controller_list. The controller list will be iterated as many times as there are controller names.

Parameters
[in]rt_controller_listcontrollers in the real-time list.
[in]controllers_to_deactivatenames of the controller that have to be deactivated.

◆ get_trigger_clock()

rclcpp::Clock::SharedPtr controller_manager::ControllerManager::get_trigger_clock ( ) const

Get the trigger clock of the controller manager.

Get the trigger clock of the controller manager. The method is used to get the clock that is used for triggering the controllers and the hardware components.

Note
When the use_sim_time parameter is set to true, the clock will be the ROS clock. Otherwise, the clock will be the Steady Clock.
Returns
trigger clock of the controller manager.

◆ get_update_rate()

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

Update rate of the main control loop in the controller manager.

Update rate of the main control loop in the controller manager. The method is used for per-controller update rate support.

Returns
update rate of the controller manager.

◆ is_resource_manager_initialized()

bool controller_manager::ControllerManager::is_resource_manager_initialized ( ) const
inline

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. Interface for external components to check if Resource Manager is initialized. Checks if components in Resource Manager are loaded and initialized.

Returns
true if they are initialized, false otherwise.

◆ 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

◆ shutdown_controllers()

bool controller_manager::ControllerManager::shutdown_controllers ( )

Shutdown all controllers in the controller manager.

Returns
true if all controllers are successfully shutdown, false otherwise.

◆ 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 > &  activate_controllers,
const std::vector< std::string > &  deactivate_controllers,
int  strictness,
bool  activate_asap = kWaitForAllResources,
const rclcpp::Duration &  timeout = rclcpp::Duration::from_nanoseconds(kInfiniteTimeout) 
)

switch_controller Deactivates some controllers and activates others.

Parameters
[in]activate_controllersis a list of controllers to activate.
[in]deactivate_controllersis a list of controllers to deactivate.
[in]setlevel of strictness (BEST_EFFORT or STRICT)
[in]activate_asapflag to activate controllers as soon as possible.
[in]timeoutto wait for the controllers to be switched.
See also
Documentation in controller_manager_msgs/SwitchController.srv

◆ switch_controller_cb()

controller_interface::return_type controller_manager::ControllerManager::switch_controller_cb ( const std::vector< std::string > &  activate_controllers,
const std::vector< std::string > &  deactivate_controllers,
int  strictness,
bool  activate_asap,
const rclcpp::Duration &  timeout,
std::string &  message 
)

switch_controller Deactivates some controllers and activates others.

Parameters
[in]activate_controllersis a list of controllers to activate.
[in]deactivate_controllersis a list of controllers to deactivate.
[in]setlevel of strictness (BEST_EFFORT or STRICT)
[in]activate_asapflag to activate controllers as soon as possible.
[in]timeoutto wait for the controllers to be switched.
[out]messagedescribing the result of the switch.
See also
Documentation in controller_manager_msgs/SwitchController.srv

◆ 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
Note
The factor 0.99 is used to avoid the controllers skipping update cycles due to the jitter in the system sleep cycles.

◆ 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: