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

Definition of an impedance controller in either joint or task space. More...

#include <Impedance.hpp>

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

Public Member Functions

 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.
 
compute_command (const S &command_state, const S &feedback_state) override
 Compute the command output based on the commanded state and a feedback state To be redefined based on the actual controller implementation.
 
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.
 

Protected Member Functions

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

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::Impedance< S >

Definition of an impedance controller in either joint or task space.

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

Definition at line 18 of file Impedance.hpp.

Constructor & Destructor Documentation

◆ Impedance() [1/2]

template<class S >
controllers::impedance::Impedance< S >::Impedance ( 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 76 of file Impedance.hpp.

◆ Impedance() [2/2]

template<class S >
controllers::impedance::Impedance< S >::Impedance ( 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 94 of file Impedance.hpp.

Member Function Documentation

◆ clamp_force()

template<class S >
void controllers::impedance::Impedance< S >::clamp_force ( Eigen::VectorXd &  force)
protected

Definition at line 102 of file Impedance.hpp.

◆ compute_command() [1/3]

CartesianState controllers::impedance::Impedance< CartesianState >::compute_command ( const CartesianState command_state,
const CartesianState feedback_state 
)

Definition at line 17 of file Impedance.cpp.

◆ compute_command() [2/3]

JointState controllers::impedance::Impedance< JointState >::compute_command ( const JointState command_state,
const JointState feedback_state 
)

Definition at line 50 of file Impedance.cpp.

◆ compute_command() [3/3]

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

Compute the command output based on the commanded state and a feedback state To be redefined based on the actual controller implementation.

Parameters
command_stateThe input state to the controller
feedback_stateThe current state of the system given as feedback
Returns
The output command in the same state space as the input

Implements controllers::IController< S >.

Reimplemented in controllers::impedance::VelocityImpedance< S >, and controllers::impedance::VelocityImpedance< state_representation::CartesianState >.

Definition at line 12 of file Impedance.cpp.

◆ gain_matrix_from_parameter()

template<class S >
Eigen::MatrixXd controllers::impedance::Impedance< S >::gain_matrix_from_parameter ( const std::shared_ptr< state_representation::ParameterInterface > &  parameter)
protected

Convert a parameterized gain to a gain matrix.

Parameters
parameterA parameter interface pointer of type double, double array or matrix
Returns
A square gain matrix

Definition at line 135 of file Impedance.hpp.

◆ validate_and_set_parameter()

template<class S >
void controllers::impedance::Impedance< S >::validate_and_set_parameter ( const std::shared_ptr< state_representation::ParameterInterface > &  parameter)
overrideprotected

Validate and set parameters for damping, stiffness and inertia gain matrices.

Parameters
parameterA parameter interface pointer

Definition at line 109 of file Impedance.hpp.

Member Data Documentation

◆ damping_

template<class S >
std::shared_ptr<state_representation::Parameter<Eigen::MatrixXd> > controllers::impedance::Impedance< S >::damping_
protected

damping matrix of the controller associated to velocity

Definition at line 64 of file Impedance.hpp.

◆ dimensions_

template<class S >
const unsigned int controllers::impedance::Impedance< S >::dimensions_
protected

dimensionality of the control space and associated gain matrices

Definition at line 72 of file Impedance.hpp.

◆ feed_forward_force_

template<class S >
std::shared_ptr<state_representation::Parameter<bool> > controllers::impedance::Impedance< S >::feed_forward_force_
protected

flag to decide if force error should be passed on

Definition at line 68 of file Impedance.hpp.

◆ force_limit_

template<class S >
std::shared_ptr<state_representation::Parameter<Eigen::VectorXd> > controllers::impedance::Impedance< S >::force_limit_
protected

vector of force limits for each degree of freedom

Definition at line 70 of file Impedance.hpp.

◆ inertia_

template<class S >
std::shared_ptr<state_representation::Parameter<Eigen::MatrixXd> > controllers::impedance::Impedance< S >::inertia_
protected

inertia matrix of the controller associated to acceleration

Definition at line 66 of file Impedance.hpp.

◆ stiffness_

template<class S >
std::shared_ptr<state_representation::Parameter<Eigen::MatrixXd> > controllers::impedance::Impedance< S >::stiffness_
protected

stiffness matrix of the controller associated to position

Definition at line 62 of file Impedance.hpp.


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