1#include "controllers/impedance/CompliantTwist.hpp"
3#include "state_representation/exceptions/InvalidParameterException.hpp"
5namespace controllers::impedance {
10 double linear_principle_damping,
double linear_orthogonal_damping,
double angular_stiffness,
double angular_damping
11) : linear_principle_damping_(
12 std::make_shared<
Parameter<double>>(
"linear_principle_damping", linear_principle_damping)),
13 linear_orthogonal_damping_(
14 std::make_shared<
Parameter<double>>(
"linear_orthogonal_damping", linear_orthogonal_damping)),
15 angular_stiffness_(std::make_shared<
Parameter<double>>(
"angular_stiffness", angular_stiffness)),
16 angular_damping_(std::make_shared<
Parameter<double>>(
"angular_damping", angular_damping)),
17 dissipative_ctrl_(ComputationalSpaceType::LINEAR),
18 velocity_impedance_ctrl_(6) {
29 const std::list<std::shared_ptr<state_representation::ParameterInterface>>& parameters
46 Eigen::VectorXd damping(6);
47 damping << linear_principle_damping, linear_orthogonal_damping, linear_orthogonal_damping, 0, 0, 0;
63 Eigen::MatrixXd k(6, 6), d(6, 6);
64 k.diagonal() << 0, 0, 0, angular_stiffness, angular_stiffness, angular_stiffness;
65 d.diagonal() << 0, 0, 0, angular_damping, angular_damping, angular_damping;
80 const std::shared_ptr<state_representation::ParameterInterface>& parameter
82 if (parameter->get_parameter_type() != ParameterType::DOUBLE) {
84 "Parameter " + parameter->get_name() +
" must be a double");
86 double value = std::static_pointer_cast<Parameter<double>>(parameter)->get_value();
87 if (parameter->get_name() ==
"linear_principle_damping") {
89 }
else if (parameter->get_name() ==
"linear_orthogonal_damping") {
91 }
else if (parameter->get_name() ==
"angular_stiffness") {
93 }
else if (parameter->get_name() ==
"angular_damping") {
97 "No parameter with name '" + parameter->get_name() +
"' found"
A concrete controller class specifically for controlling 6 degree of freedom Cartesian twist with a c...
std::shared_ptr< state_representation::Parameter< double > > angular_stiffness_
stiffness of angular displacement
void set_linear_orthogonal_damping(double linear_orthogonal_damping)
Setter of the linear orthogonal damping.
void set_linear_principle_damping(double linear_principle_damping)
Setter of the linear principle damping.
Dissipative< state_representation::CartesianState > dissipative_ctrl_
controller for linear space
std::shared_ptr< state_representation::Parameter< double > > angular_damping_
damping of angular velocity error
void set_angular_stiffness(double angular_stiffness)
Setter of the angular stiffness.
std::shared_ptr< state_representation::Parameter< double > > linear_principle_damping_
damping along principle eigenvector of linear velocity error
VelocityImpedance< state_representation::CartesianState > velocity_impedance_ctrl_
controller for angular space
void set_linear_gains(double linear_principle_damping, double linear_orthogonal_damping)
Setter of the linear damping values.
CompliantTwist(const std::list< std::shared_ptr< state_representation::ParameterInterface > > ¶meters)
Constructor from an initial parameter list.
void set_angular_gains(double angular_stiffness, double angular_damping)
Setter of the angular damping.
state_representation::CartesianState compute_command(const state_representation::CartesianState &desired_state, const state_representation::CartesianState &feedback_state) override
Compute the force (task space) or torque (joint space) command based on the input state of the system...
std::shared_ptr< state_representation::Parameter< double > > linear_orthogonal_damping_
damping along secondary eigenvectors of linear velocity error
void set_angular_damping(double angular_damping)
Setter of the angular damping.
void validate_and_set_parameter(const std::shared_ptr< state_representation::ParameterInterface > ¶meter) override
Validate and set parameters for controller gains.
S compute_command(const S &command_state, const S &feedback_state) override
Compute the force (task space) or torque (joint space) command based on the input state of the system...
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...
Class to represent a state in Cartesian space.
Class to define twist in cartesian space as 3D linear and angular velocity vectors.
void set_parameters(const ParameterInterfaceList ¶meters)
Set parameters from a list of parameters.
ParameterInterfaceMap parameters_
map of parameters by name
void set_parameter_value(const std::string &name, const T &value)
Set a parameter value by its name.
Core state variables and objects.