ros2_control - rolling
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
admittance_controller::AdmittanceController Class Reference
Inheritance diagram for admittance_controller::AdmittanceController:
Inheritance graph
[legend]
Collaboration diagram for admittance_controller::AdmittanceController:
Collaboration graph
[legend]

Public Member Functions

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
 Export configuration of required state interfaces.
 
controller_interface::InterfaceConfiguration state_interface_configuration () const override
 Export configuration of 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
 
controller_interface::CallbackReturn on_error (const rclcpp_lifecycle::State &previous_state) override
 
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.
 
- Public Member Functions inherited from controller_interface::ChainableControllerInterface
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.
 
- Public Member Functions inherited from controller_interface::ControllerInterfaceBase
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 &params)
 
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.
 

Protected Member Functions

std::vector< hardware_interface::CommandInterfaceon_export_reference_interfaces () override
 Virtual method implemented by chainable controllers to export read/write interfaces.
 
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.
 
void read_state_from_hardware (trajectory_msgs::msg::JointTrajectoryPoint &state_current, geometry_msgs::msg::Wrench &ft_values)
 Read values from hardware interfaces and set corresponding fields of state_current and ft_values.
 
void read_state_reference_interfaces (trajectory_msgs::msg::JointTrajectoryPoint &state)
 Set fields of state_reference with values from controllers exported position and velocity references.
 
void write_state_to_hardware (const trajectory_msgs::msg::JointTrajectoryPoint &state_command)
 Write values from state_command to claimed hardware interfaces.
 
- Protected Member Functions inherited from controller_interface::ChainableControllerInterface
virtual std::vector< hardware_interface::StateInterfaceon_export_state_interfaces ()
 Virtual method that each chainable controller should implement to export its read-only chainable interfaces.
 
virtual std::vector< hardware_interface::StateInterface::SharedPtr > on_export_state_interfaces_list ()
 Virtual method implemented by chainable controllers to export read-only interfaces.
 
virtual std::vector< hardware_interface::CommandInterface::SharedPtr > on_export_reference_interfaces_list ()
 Virtual method that each chainable controller should implement to export its read/write chainable interfaces.
 
virtual bool on_set_chained_mode (bool chained_mode)
 Virtual method that each chainable controller should implement to switch chained mode.
 

Protected Attributes

size_t num_joints_ = 0
 
std::vector< std::string > command_joint_names_
 
bool has_position_state_interface_ = false
 
bool has_velocity_state_interface_ = false
 
bool has_acceleration_state_interface_ = false
 
bool has_position_command_interface_ = false
 
bool has_velocity_command_interface_ = false
 
bool has_acceleration_command_interface_ = false
 
bool has_effort_command_interface_ = false
 
const std::vector< std::string > allowed_interface_types_
 
std::vector< std::reference_wrapper< double > > position_reference_
 
std::vector< std::reference_wrapper< double > > velocity_reference_
 
std::unique_ptr< admittance_controller::AdmittanceRuleadmittance_
 
std::unique_ptr< semantic_components::ForceTorqueSensorforce_torque_sensor_
 
rclcpp::Subscription< trajectory_msgs::msg::JointTrajectoryPoint >::SharedPtr input_joint_command_subscriber_
 
rclcpp::Subscription< geometry_msgs::msg::WrenchStamped >::SharedPtr input_wrench_command_subscriber_
 
rclcpp::Publisher< control_msgs::msg::AdmittanceControllerState >::SharedPtr s_publisher_
 
std::shared_ptr< admittance_controller::ParamListener > parameter_handler_
 
realtime_tools::RealtimeThreadSafeBox< trajectory_msgs::msg::JointTrajectoryPoint > input_joint_command_
 
realtime_tools::RealtimeThreadSafeBox< geometry_msgs::msg::WrenchStamped > input_wrench_command_
 
std::unique_ptr< realtime_tools::RealtimePublisher< ControllerStateMsg > > state_publisher_
 
ControllerStateMsg state_msg_
 
trajectory_msgs::msg::JointTrajectoryPoint joint_command_msg_
 
geometry_msgs::msg::WrenchStamped wrench_command_msg_
 
trajectory_msgs::msg::JointTrajectoryPoint last_commanded_
 
trajectory_msgs::msg::JointTrajectoryPoint last_reference_
 
trajectory_msgs::msg::JointTrajectoryPoint reference_
 
trajectory_msgs::msg::JointTrajectoryPoint joint_state_
 
trajectory_msgs::msg::JointTrajectoryPoint reference_admittance_
 
geometry_msgs::msg::Wrench ft_values_
 
- Protected Attributes inherited from controller_interface::ChainableControllerInterface
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_
 
- Protected Attributes inherited from controller_interface::ControllerInterfaceBase
std::vector< hardware_interface::LoanedCommandInterfacecommand_interfaces_
 Loaned command interfaces.
 
std::vector< hardware_interface::LoanedStateInterfacestate_interfaces_
 Loaned state interfaces.
 
pal_statistics::RegistrationsRAII stats_registrations_
 

Member Function Documentation

◆ command_interface_configuration()

controller_interface::InterfaceConfiguration admittance_controller::AdmittanceController::command_interface_configuration ( ) const
overridevirtual

Export configuration of required state interfaces.

Allowed types of state interfaces are hardware_interface::POSITION, hardware_interface::VELOCITY, hardware_interface::ACCELERATION.

Implements controller_interface::ControllerInterfaceBase.

◆ on_export_reference_interfaces()

std::vector< hardware_interface::CommandInterface > admittance_controller::AdmittanceController::on_export_reference_interfaces ( )
overrideprotectedvirtual

Virtual method implemented by chainable controllers to export read/write interfaces.

Each chainable controller implements this methods where all input (command) interfaces are exported. The method has the same meaning as export_command_interface method from hardware_interface::SystemInterface or hardware_interface::ActuatorInterface.

Returns
list of CommandInterfaces that other controller can use as their outputs.

Reimplemented from controller_interface::ChainableControllerInterface.

◆ on_init()

controller_interface::CallbackReturn admittance_controller::AdmittanceController::on_init ( )
overridevirtual

Extending interface with initialization method which is individual for each controller.

Implements controller_interface::ControllerInterfaceBase.

◆ state_interface_configuration()

controller_interface::InterfaceConfiguration admittance_controller::AdmittanceController::state_interface_configuration ( ) const
overridevirtual

Export configuration of required state interfaces.

Allowed types of state interfaces are hardware_interface::POSITION, hardware_interface::VELOCITY, hardware_interface::ACCELERATION.

Implements controller_interface::ControllerInterfaceBase.

◆ update_and_write_commands()

controller_interface::return_type admittance_controller::AdmittanceController::update_and_write_commands ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
overridevirtual

Execute calculations of the controller and update command interfaces.

Update method for chainable controllers. In this method is valid to assume that \reference_interfaces_ hold the values for calculation of the commands in the current control step. This means that this method is called after \update_reference_from_subscribers if controller is not in chained mode.

Returns
return_type::OK if calculation and writing of interface is successfully, otherwise return_type::ERROR.

Implements controller_interface::ChainableControllerInterface.

◆ update_reference_from_subscribers()

controller_interface::return_type admittance_controller::AdmittanceController::update_reference_from_subscribers ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
overrideprotectedvirtual

Update reference from input topics when not in chained mode.

Each chainable controller implements this method to update reference from subscribers when not in chained mode.

Returns
return_type::OK if update is successfully, otherwise return_type::ERROR.

Implements controller_interface::ChainableControllerInterface.

Member Data Documentation

◆ allowed_interface_types_

const std::vector<std::string> admittance_controller::AdmittanceController::allowed_interface_types_
protected
Initial value:
= {
constexpr char HW_IF_ACCELERATION[]
Constant defining acceleration interface name.
Definition hardware_interface_type_values.hpp:25
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface name.
Definition hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface name.
Definition hardware_interface_type_values.hpp:21

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