Control Libraries 7.4.0
Loading...
Searching...
No Matches
Public Member Functions | List of all members
controllers::impedance::VelocityImpedance< S > Class Template Reference

A velocity impedance is a normal impedance controller that only uses velocity input and integrates it for position error. More...

#include <VelocityImpedance.hpp>

Inheritance diagram for controllers::impedance::VelocityImpedance< S >:
controllers::impedance::Impedance< S > controllers::IController< S > state_representation::ParameterMap

Public Member Functions

 VelocityImpedance (unsigned int dimensions=6)
 Base constructor.
 
 VelocityImpedance (const std::list< std::shared_ptr< state_representation::ParameterInterface > > &parameters, unsigned int dimensions=6)
 Constructor from an initial parameter list.
 
compute_command (const S &desired_state, const S &feedback_state) override
 Compute the force (task space) or torque (joint space) command based on the input state of the system as the error between the desired state and the real state.
 
CartesianState compute_command (const CartesianState &desired_state, const CartesianState &feedback_state)
 
JointState compute_command (const JointState &desired_state, const JointState &feedback_state)
 
- Public Member Functions inherited from controllers::impedance::Impedance< S >
 Impedance (unsigned int dimensions=6)
 Base constructor.
 
 Impedance (const std::list< std::shared_ptr< state_representation::ParameterInterface > > &parameters, unsigned int dimensions=6)
 Constructor from an initial parameter list.
 
CartesianState compute_command (const CartesianState &command_state, const CartesianState &feedback_state)
 
JointState compute_command (const JointState &command_state, const JointState &feedback_state)
 
- Public Member Functions inherited from controllers::IController< S >
 IController ()=default
 Empty constructor.
 
virtual ~IController ()=default
 Empty destructor.
 
state_representation::JointState compute_command (const S &command_state, const S &feedback_state, const state_representation::Jacobian &jacobian)
 Compute the command output in joint space.
 
state_representation::JointState compute_command (const S &command_state, const S &feedback_state, const state_representation::JointPositions &joint_positions, const std::string &frame="")
 Compute the command output in joint space from command and feedback states in task space.
 
const robot_model::Modelget_robot_model ()
 Get the robot model associated with the controller.
 
void set_robot_model (const robot_model::Model &robot_model)
 Set the robot model associated with the controller.
 
- Public Member Functions inherited from state_representation::ParameterMap
 ParameterMap ()=default
 Empty constructor.
 
 ParameterMap (const ParameterInterfaceList &parameters)
 Construct the parameter map with an initial list of parameters.
 
 ParameterMap (const ParameterInterfaceMap &parameters)
 Construct the parameter map with an initial map of parameters.
 
std::shared_ptr< ParameterInterfaceget_parameter (const std::string &name) const
 Get a parameter by its name.
 
ParameterInterfaceMap get_parameters () const
 Get a map of all the <name, parameter> pairs.
 
template<typename T >
get_parameter_value (const std::string &name) const
 Get a parameter value by its name.
 
ParameterInterfaceList get_parameter_list () const
 Get a list of all the parameters.
 
void set_parameter (const std::shared_ptr< ParameterInterface > &parameter)
 Set a parameter.
 
void set_parameters (const ParameterInterfaceList &parameters)
 Set parameters from a list of parameters.
 
void set_parameters (const ParameterInterfaceMap &parameters)
 Set parameters from a map with <name, parameter> pairs.
 
template<typename T >
void set_parameter_value (const std::string &name, const T &value)
 Set a parameter value by its name.
 
void remove_parameter (const std::string &name)
 Remove a parameter from the parameter map.
 

Additional Inherited Members

- Protected Member Functions inherited from controllers::impedance::Impedance< S >
void clamp_force (Eigen::VectorXd &force)
 
void validate_and_set_parameter (const std::shared_ptr< state_representation::ParameterInterface > &parameter) override
 Validate and set parameters for damping, stiffness and inertia gain matrices.
 
Eigen::MatrixXd gain_matrix_from_parameter (const std::shared_ptr< state_representation::ParameterInterface > &parameter)
 Convert a parameterized gain to a gain matrix.
 
- Protected Member Functions inherited from state_representation::ParameterMap
virtual void validate_and_set_parameter (const std::shared_ptr< ParameterInterface > &parameter)
 Validate and set a parameter in the map.
 
void assert_parameter_valid (const std::shared_ptr< ParameterInterface > &parameter)
 Check if a parameter exists and has the expected type, throw an exception otherwise.
 
- Protected Attributes inherited from controllers::impedance::Impedance< S >
std::shared_ptr< state_representation::Parameter< Eigen::MatrixXd > > stiffness_
 stiffness matrix of the controller associated to position
 
std::shared_ptr< state_representation::Parameter< Eigen::MatrixXd > > damping_
 damping matrix of the controller associated to velocity
 
std::shared_ptr< state_representation::Parameter< Eigen::MatrixXd > > inertia_
 inertia matrix of the controller associated to acceleration
 
std::shared_ptr< state_representation::Parameter< bool > > feed_forward_force_
 flag to decide if force error should be passed on
 
std::shared_ptr< state_representation::Parameter< Eigen::VectorXd > > force_limit_
 vector of force limits for each degree of freedom
 
const unsigned int dimensions_
 dimensionality of the control space and associated gain matrices
 
- Protected Attributes inherited from controllers::IController< S >
std::shared_ptr< robot_model::Modelrobot_model_
 The robot model associated with the controller.
 
- Protected Attributes inherited from state_representation::ParameterMap
ParameterInterfaceMap parameters_
 map of parameters by name
 

Detailed Description

template<class S>
class controllers::impedance::VelocityImpedance< S >

A velocity impedance is a normal impedance controller that only uses velocity input and integrates it for position error.

Template Parameters
Sthe space of the controller (either CartesianState or JointState)

Definition at line 15 of file VelocityImpedance.hpp.

Constructor & Destructor Documentation

◆ VelocityImpedance() [1/2]

template<class S >
controllers::impedance::VelocityImpedance< S >::VelocityImpedance ( unsigned int  dimensions = 6)
explicit

Base constructor.

This initializes all gain matrices to the identity matrix of the corresponding dimensionality.

Parameters
dimensionsThe number of dimensions associated with the controller

Definition at line 46 of file VelocityImpedance.hpp.

◆ VelocityImpedance() [2/2]

template<class S >
controllers::impedance::VelocityImpedance< S >::VelocityImpedance ( const std::list< std::shared_ptr< state_representation::ParameterInterface > > &  parameters,
unsigned int  dimensions = 6 
)
explicit

Constructor from an initial parameter list.

Parameters
parametersA parameter list containing initial gain values
dimensionsThe number of dimensions associated with the controller

Definition at line 52 of file VelocityImpedance.hpp.

Member Function Documentation

◆ compute_command() [1/3]

CartesianState controllers::impedance::VelocityImpedance< CartesianState >::compute_command ( const CartesianState desired_state,
const CartesianState feedback_state 
)

Definition at line 22 of file VelocityImpedance.cpp.

◆ compute_command() [2/3]

JointState controllers::impedance::VelocityImpedance< JointState >::compute_command ( const JointState desired_state,
const JointState feedback_state 
)

Definition at line 38 of file VelocityImpedance.cpp.

◆ compute_command() [3/3]

template<class S >
S controllers::impedance::VelocityImpedance< S >::compute_command ( const S &  desired_state,
const S &  feedback_state 
)
overridevirtual

Compute the force (task space) or torque (joint space) command based on the input state of the system as the error between the desired state and the real state.

Parameters
desired_statethe desired state to reach
feedback_statethe real state of the system as read from feedback loop
Returns
the output command at the input state

Reimplemented from controllers::impedance::Impedance< S >.

Definition at line 16 of file VelocityImpedance.cpp.


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