Class SpringActuatorController

Inheritance Relationships

Base Type

  • public controller_interface::ControllerInterface

Class Documentation

class SpringActuatorController : public controller_interface::ControllerInterface

A ROS 2 controller that simulates a spring-like behavior on a specified joint (e.g., a “trigger”), while optionally leaving other joints unaltered or with minimal torque.

The parameters for this controller (e.g., stiffness, neutral position, friction compensation, etc.) are obtained via a parameter listener defined in spring_actuator_controller_parameters.hpp.

Public Functions

SPRING_ACTUATOR_CONTROLLER_PUBLIC SpringActuatorController()
SPRING_ACTUATOR_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
SPRING_ACTUATOR_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
SPRING_ACTUATOR_CONTROLLER_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override
SPRING_ACTUATOR_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_init () override
SPRING_ACTUATOR_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
SPRING_ACTUATOR_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
SPRING_ACTUATOR_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
SPRING_ACTUATOR_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &previous_state) override
SPRING_ACTUATOR_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_error (const rclcpp_lifecycle::State &previous_state) override
SPRING_ACTUATOR_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &previous_state) override

Protected Types

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

Store references to command and state interfaces for each joint and interface type.

For each interface type (effort, position, velocity, etc.), we have a vector of references, each corresponding to a particular joint. joint_command_interface_[i][j] gives the reference for the j-th joint’s i-th command interface type.

Protected Functions

std::string formatVector(const std::vector<double> &vec)

Utility to convert a vector of doubles into a comma-separated string.

Parameters:

vec – The vector of doubles to format.

Returns:

A string representation of the vector.

Protected Attributes

std::shared_ptr<ParamListener> param_listener_

Param listener and the parameter struct holding all configuration values (e.g., spring stiffness, friction thresholds, etc.).

Params params_
bool dither_switch_

Switch for dithering logic to overcome static friction.

std::vector<std::string> state_interface_types_ = {hardware_interface::HW_IF_POSITION, hardware_interface::HW_IF_VELOCITY,}

Types of state interfaces we want: position, velocity.

std::vector<std::string> command_interface_types_ = {hardware_interface::HW_IF_EFFORT}

Types of command interfaces we want: effort.

size_t dof_

Number of degrees of freedom for the robot/joints we are controlling. This is typically the size of params_.joints.

std::vector<std::string> command_joint_names_

The names of joints we issue commands for. Could match joint_names_ or be a subset, depending on parameter usage.

InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_
InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_
std::vector<std::string> joint_names_

Names of the joints managed by this controller (from parameters)

size_t n_joints_

Number of joints, should match joint_names_.size()

std::vector<double> joint_positions_

Cached vectors for joint positions and velocities read during update()

std::vector<double> joint_velocities_