|
| controller_interface::CallbackReturn | on_init () override |
| | Extending interface with initialization method which is individual for each controller.
|
| |
| controller_interface::InterfaceConfiguration | command_interface_configuration () const override |
| | Get configuration for controller's required command interfaces.
|
| |
| controller_interface::InterfaceConfiguration | state_interface_configuration () const override |
| | Get configuration for controller's required state interfaces.
|
| |
|
controller_interface::CallbackReturn | on_configure (const rclcpp_lifecycle::State &previous_state) override |
| |
|
controller_interface::CallbackReturn | on_activate (const rclcpp_lifecycle::State &previous_state) override |
| |
|
controller_interface::CallbackReturn | on_deactivate (const rclcpp_lifecycle::State &previous_state) override |
| |
|
void | reset_buffers () |
| |
| controller_interface::return_type | update_reference_from_subscribers (const rclcpp::Time &time, const rclcpp::Duration &period) override |
| | Update reference from input topics when not in chained mode.
|
| |
| controller_interface::return_type | update_and_write_commands (const rclcpp::Time &time, const rclcpp::Duration &period) override |
| | Execute calculations of the controller and update command interfaces.
|
| |
|
void | set_odometry (const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< control_msgs::srv::SetOdometry::Request > req, std::shared_ptr< control_msgs::srv::SetOdometry::Response > res) |
| |
| return_type | update (const rclcpp::Time &time, const rclcpp::Duration &period) final |
| | Control step. Updates command interfaces from reference inputs and current states. The method called in the (real-time) control loop.
|
| |
| bool | is_chainable () const final |
| | Get information if a controller is chainable.
|
| |
| std::vector< hardware_interface::StateInterface::ConstSharedPtr > | export_state_interfaces () final |
| | Export interfaces for a chainable controller that can be used as state interface by other controllers.
|
| |
| std::vector< hardware_interface::CommandInterface::SharedPtr > | export_reference_interfaces () final |
| | Export interfaces for a chainable controller that can be used as command interface of other controllers.
|
| |
| bool | set_chained_mode (bool chained_mode) final |
| | Set chained mode of a chainable controller. This method triggers internal processes to switch a chainable controller to "chained" mode and vice-versa. Setting controller to "chained" mode usually involves the usage of the controller's reference interfaces by the other controllers.
|
| |
| bool | is_in_chained_mode () const final |
| | Get information if a controller is currently in chained mode.
|
| |
| virtual void | assign_interfaces (std::vector< hardware_interface::LoanedCommandInterface > &&command_interfaces, std::vector< hardware_interface::LoanedStateInterface > &&state_interfaces) |
| | Method that assigns the Loaned interfaces to the controller.
|
| |
| virtual void | release_interfaces () |
| | Method that releases the Loaned interfaces from the controller.
|
| |
|
return_type | init (const std::string &controller_name, const std::string &urdf, unsigned int cm_update_rate, const std::string &node_namespace, const rclcpp::NodeOptions &node_options) |
| |
|
return_type | init (const controller_interface::ControllerInterfaceParams ¶ms) |
| |
| const rclcpp_lifecycle::State & | configure () |
| | Custom configure method to read additional parameters for controller-nodes.
|
| |
| ControllerUpdateStatus | trigger_update (const rclcpp::Time &time, const rclcpp::Duration &period) |
| | Trigger update method. This method is used by the controller_manager to trigger the update method of the controller. The method is used to trigger the update method of the controller synchronously or asynchronously, based on the controller configuration. The method called in the (real-time) control loop.
|
| |
|
std::shared_ptr< rclcpp_lifecycle::LifecycleNode > | get_node () |
| |
|
std::shared_ptr< const rclcpp_lifecycle::LifecycleNode > | get_node () const |
| |
| const rclcpp_lifecycle::State & | get_lifecycle_state () const |
| | Get the current lifecycle state of the controller node.
|
| |
| uint8_t | get_lifecycle_id () const |
| | Get the lifecycle id of the controller node that is cached internally to avoid calls to get_lifecycle_state() in the real-time control loop.
|
| |
|
unsigned int | get_update_rate () const |
| |
|
bool | is_async () const |
| |
|
const std::string & | get_robot_description () const |
| |
|
const std::unordered_map< std::string, joint_limits::JointLimits > & | get_hard_joint_limits () const |
| | Get the unordered map of joint limits that are defined in the robot description.
|
| |
|
const std::unordered_map< std::string, joint_limits::SoftJointLimits > & | get_soft_joint_limits () const |
| | Get the unordered map of soft joint limits that are defined in the robot description.
|
| |
| virtual rclcpp::NodeOptions | define_custom_node_options () const |
| | Method used by the controller_manager for base NodeOptions to instantiate the Lifecycle node of the controller upon loading the controller.
|
| |
| template<typename ParameterT > |
| auto | auto_declare (const std::string &name, const ParameterT &default_value) |
| | Declare and initialize a parameter with a type.
|
| |
| void | wait_for_trigger_update_to_finish () |
| | Method to wait for any running async update cycle to finish after finishing the current cycle. This is needed to be called before deactivating the controller by the controller_manager, so that the interfaces still exist when the controller finishes its cycle and then it's exits.
|
| |
| void | prepare_for_deactivation () |
| | Method to prepare the controller for deactivation. This method is called by the controller manager before deactivating the controller. The method is used to prepare the controller for deactivation, e.g., to stop triggering the update cycles further. This method is especially needed for controllers running in async mode and different frequency than the control manager.
|
| |
|
std::string | get_name () const |
| |
| void | enable_introspection (bool enable) |
| | Enable or disable introspection of the controller.
|
| |
|
|
std::shared_ptr< mecanum_drive_controller::ParamListener > | param_listener_ |
| |
|
mecanum_drive_controller::Params | params_ |
| |
| std::vector< std::string > | command_joint_names_ |
| |
| std::vector< std::string > | state_joint_names_ |
| |
|
realtime_tools::RealtimeThreadSafeBox< ControllerReferenceMsg > | input_ref_ |
| |
|
ControllerReferenceMsg | current_ref_ |
| |
|
rclcpp::Duration | ref_timeout_ = rclcpp::Duration::from_seconds(0.0) |
| |
|
rclcpp::Subscription< ControllerReferenceMsg >::SharedPtr | ref_subscriber_ = nullptr |
| |
|
rclcpp::Publisher< OdomStateMsg >::SharedPtr | odom_s_publisher_ |
| |
|
std::unique_ptr< OdomStatePublisher > | rt_odom_state_publisher_ |
| |
|
OdomStateMsg | odom_state_msg_ |
| |
|
rclcpp::Publisher< TfStateMsg >::SharedPtr | tf_odom_s_publisher_ |
| |
|
std::unique_ptr< TfStatePublisher > | rt_tf_odom_state_publisher_ |
| |
|
TfStateMsg | tf_odom_state_msg_ |
| |
|
rclcpp::Publisher< ControllerStateMsg >::SharedPtr | controller_s_publisher_ |
| |
|
std::unique_ptr< ControllerStatePublisher > | controller_state_publisher_ |
| |
|
ControllerStateMsg | controller_state_msg_ |
| |
|
Odometry | odometry_ |
| |
|
rclcpp::Service< control_msgs::srv::SetOdometry >::SharedPtr | set_odom_service_ |
| |
|
std::atomic< bool > | set_odom_requested_ {false} |
| |
|
realtime_tools::RealtimeThreadSafeBox< control_msgs::srv::SetOdometry::Request > | requested_odom_params_ |
| |
|
std::queue< std::array< double, 3 > > | previous_two_commands_ |
| |
|
std::vector< std::string > | exported_state_interface_names_ |
| | Storage of values for state interfaces.
|
| |
|
std::vector< hardware_interface::StateInterface::SharedPtr > | ordered_exported_state_interfaces_ |
| |
|
std::unordered_map< std::string, hardware_interface::StateInterface::SharedPtr > | exported_state_interfaces_ |
| |
|
std::vector< double > | state_interfaces_values_ |
| |
|
std::vector< std::string > | exported_reference_interface_names_ |
| | Storage of values for reference interfaces.
|
| |
|
std::vector< double > | reference_interfaces_ |
| |
|
std::vector< hardware_interface::CommandInterface::SharedPtr > | ordered_exported_reference_interfaces_ |
| |
|
std::unordered_map< std::string, hardware_interface::CommandInterface::SharedPtr > | exported_reference_interfaces_ |
| |
| std::vector< hardware_interface::LoanedCommandInterface > | command_interfaces_ |
| | Loaned command interfaces.
|
| |
| std::vector< hardware_interface::LoanedStateInterface > | state_interfaces_ |
| | Loaned state interfaces.
|
| |
|
pal_statistics::RegistrationsRAII | stats_registrations_ |
| |