Class AdmittanceController

Inheritance Relationships

Base Type

  • public controller_interface::ChainableControllerInterface

Class Documentation

class AdmittanceController : public controller_interface::ChainableControllerInterface

Public Functions

ADMITTANCE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_init () override
ADMITTANCE_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override

Export configuration of required state interfaces.

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

ADMITTANCE_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override

Export configuration of required state interfaces.

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

ADMITTANCE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
ADMITTANCE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
ADMITTANCE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
ADMITTANCE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &previous_state) override
ADMITTANCE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_error (const rclcpp_lifecycle::State &previous_state) override
ADMITTANCE_CONTROLLER_PUBLIC controller_interface::return_type update_and_write_commands (const rclcpp::Time &time, const rclcpp::Duration &period) override

Protected Types

template<typename T>
using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>

Protected Functions

std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override
controller_interface::return_type update_reference_from_subscribers() override
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 Attributes

size_t num_joints_ = 0
std::vector<std::string> command_joint_names_
InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_
InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_
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_ = {hardware_interface::HW_IF_POSITION, hardware_interface::HW_IF_VELOCITY, hardware_interface::HW_IF_ACCELERATION}
const std::vector<std::string> allowed_reference_interfaces_types_ = {hardware_interface::HW_IF_POSITION, hardware_interface::HW_IF_VELOCITY}
std::vector<std::reference_wrapper<double>> position_reference_
std::vector<std::reference_wrapper<double>> velocity_reference_
std::unique_ptr<admittance_controller::AdmittanceRule> admittance_
std::unique_ptr<semantic_components::ForceTorqueSensor> force_torque_sensor_
rclcpp::Subscription<trajectory_msgs::msg::JointTrajectoryPoint>::SharedPtr input_joint_command_subscriber_
rclcpp::Publisher<control_msgs::msg::AdmittanceControllerState>::SharedPtr s_publisher_
std::shared_ptr<admittance_controller::ParamListener> parameter_handler_
std::shared_ptr<trajectory_msgs::msg::JointTrajectoryPoint> joint_command_msg_
realtime_tools::RealtimeBuffer<std::shared_ptr<trajectory_msgs::msg::JointTrajectoryPoint>> input_joint_command_
std::unique_ptr<realtime_tools::RealtimePublisher<ControllerStateMsg>> state_publisher_
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_