Control Libraries 6.3.4
|
A velocity impedance is a normal impedance controller that only uses velocity input and integrates it for position error. More...
#include <VelocityImpedance.hpp>
Public Member Functions | |
VelocityImpedance (unsigned int dimensions=6) | |
Base constructor. More... | |
VelocityImpedance (const std::list< std::shared_ptr< state_representation::ParameterInterface > > ¶meters, unsigned int dimensions=6) | |
Constructor from an initial parameter list. More... | |
S | 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. More... | |
CartesianState | compute_command (const CartesianState &desired_state, const CartesianState &feedback_state) |
JointState | compute_command (const JointState &desired_state, const JointState &feedback_state) |
![]() | |
Impedance (unsigned int dimensions=6) | |
Base constructor. More... | |
Impedance (const std::list< std::shared_ptr< state_representation::ParameterInterface > > ¶meters, unsigned int dimensions=6) | |
Constructor from an initial parameter list. More... | |
S | 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. More... | |
CartesianState | compute_command (const CartesianState &command_state, const CartesianState &feedback_state) |
JointState | compute_command (const JointState &command_state, const JointState &feedback_state) |
![]() | |
IController ()=default | |
Empty constructor. | |
virtual | ~IController ()=default |
Empty destructor. | |
virtual S | compute_command (const S &command_state, const S &feedback_state)=0 |
Compute the command output based on the commanded state and a feedback state To be redefined based on the actual controller implementation. More... | |
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. More... | |
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. More... | |
const robot_model::Model & | get_robot_model () |
Get the robot model associated with the controller. More... | |
void | set_robot_model (const robot_model::Model &robot_model) |
Set the robot model associated with the controller. More... | |
![]() | |
ParameterMap ()=default | |
Empty constructor. | |
ParameterMap (const ParameterInterfaceList ¶meters) | |
Construct the parameter map with an initial list of parameters. More... | |
ParameterMap (const ParameterInterfaceMap ¶meters) | |
Construct the parameter map with an initial map of parameters. More... | |
std::shared_ptr< ParameterInterface > | get_parameter (const std::string &name) const |
Get a parameter by its name. More... | |
ParameterInterfaceMap | get_parameters () const |
Get a map of all the <name, parameter> pairs. More... | |
template<typename T > | |
T | get_parameter_value (const std::string &name) const |
Get a parameter value by its name. More... | |
ParameterInterfaceList | get_parameter_list () const |
Get a list of all the parameters. More... | |
void | set_parameter (const std::shared_ptr< ParameterInterface > ¶meter) |
Set a parameter. More... | |
void | set_parameters (const ParameterInterfaceList ¶meters) |
Set parameters from a list of parameters. More... | |
void | set_parameters (const ParameterInterfaceMap ¶meters) |
Set parameters from a map with <name, parameter> pairs. More... | |
template<typename T > | |
void | set_parameter_value (const std::string &name, const T &value) |
Set a parameter value by its name. More... | |
void | remove_parameter (const std::string &name) |
Remove a parameter from the parameter map. More... | |
Additional Inherited Members | |
![]() | |
void | clamp_force (Eigen::VectorXd &force) |
void | validate_and_set_parameter (const std::shared_ptr< state_representation::ParameterInterface > ¶meter) override |
Validate and set parameters for damping, stiffness and inertia gain matrices. More... | |
Eigen::MatrixXd | gain_matrix_from_parameter (const std::shared_ptr< state_representation::ParameterInterface > ¶meter) |
Convert a parameterized gain to a gain matrix. More... | |
![]() | |
virtual void | validate_and_set_parameter (const std::shared_ptr< ParameterInterface > ¶meter) |
Validate and set a parameter in the map. More... | |
void | assert_parameter_valid (const std::shared_ptr< ParameterInterface > ¶meter) |
Check if a parameter has the expected type, throw an exception otherwise. More... | |
![]() | |
std::shared_ptr< state_representation::Parameter< Eigen::MatrixXd > > | stiffness_ |
stiffness matrix of the controller associated to position More... | |
std::shared_ptr< state_representation::Parameter< Eigen::MatrixXd > > | damping_ |
damping matrix of the controller associated to velocity More... | |
std::shared_ptr< state_representation::Parameter< Eigen::MatrixXd > > | inertia_ |
inertia matrix of the controller associated to acceleration More... | |
std::shared_ptr< state_representation::Parameter< Eigen::VectorXd > > | force_limit_ |
vector of force limits for each degree of freedom More... | |
const unsigned int | dimensions_ |
dimensionality of the control space and associated gain matrices More... | |
![]() | |
std::shared_ptr< robot_model::Model > | robot_model_ |
The robot model associated with the controller. More... | |
![]() | |
ParameterInterfaceMap | parameters_ |
map of parameters by name More... | |
A velocity impedance is a normal impedance controller that only uses velocity input and integrates it for position error.
S | the space of the controller (either CartesianState or JointState) |
Definition at line 15 of file VelocityImpedance.hpp.
|
explicit |
Base constructor.
This initializes all gain matrices to the identity matrix of the corresponding dimensionality.
dimensions | The number of dimensions associated with the controller |
Definition at line 46 of file VelocityImpedance.hpp.
|
explicit |
Constructor from an initial parameter list.
parameters | A parameter list containing initial gain values |
dimensions | The number of dimensions associated with the controller |
Definition at line 52 of file VelocityImpedance.hpp.
CartesianState controllers::impedance::VelocityImpedance< CartesianState >::compute_command | ( | const CartesianState & | desired_state, |
const CartesianState & | feedback_state | ||
) |
Definition at line 22 of file VelocityImpedance.cpp.
JointState controllers::impedance::VelocityImpedance< JointState >::compute_command | ( | const JointState & | desired_state, |
const JointState & | feedback_state | ||
) |
Definition at line 38 of file VelocityImpedance.cpp.
|
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.
desired_state | the desired state to reach |
feedback_state | the real state of the system as read from feedback loop |
Reimplemented from controllers::impedance::Impedance< S >.
Definition at line 16 of file VelocityImpedance.cpp.