Control Libraries 6.3.4
|
Abstract class to define a controller in a desired state type, such as joint or Cartesian spaces. More...
#include <IController.hpp>
Public Member Functions | |
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... | |
Protected Attributes | |
std::shared_ptr< robot_model::Model > | robot_model_ |
The robot model associated with the controller. More... | |
![]() | |
ParameterInterfaceMap | parameters_ |
map of parameters by name More... | |
Additional Inherited Members | |
![]() | |
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... | |
Abstract class to define a controller in a desired state type, such as joint or Cartesian spaces.
S | The state type of the controller |
Definition at line 26 of file IController.hpp.
|
pure virtual |
Compute the command output based on the commanded state and a feedback state To be redefined based on the actual controller implementation.
command_state | The input state to the controller |
feedback_state | The current state of the system given as feedback |
Implemented in controllers::impedance::Dissipative< S >, controllers::impedance::Impedance< S >, controllers::impedance::VelocityImpedance< S >, controllers::impedance::Dissipative< state_representation::CartesianState >, controllers::impedance::Impedance< state_representation::CartesianState >, controllers::impedance::CompliantTwist, and controllers::impedance::VelocityImpedance< state_representation::CartesianState >.
JointState IController::compute_command | ( | const S & | command_state, |
const S & | feedback_state, | ||
const state_representation::Jacobian & | jacobian | ||
) |
Compute the command output in joint space.
command_state | The input state to the controller |
feedback_state | The current state of the system given as feedback |
jacobian | The Jacobian matrix relating Cartesian forces to joint space |
Definition at line 10 of file IController.cpp.
JointState IController::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.
This method requires the controller to have an associated robot model to compute the Jacobian.
command_state | The input state to the controller |
feedback_state | The current state of the system given as feedback |
joint_positions | The current joint positions, which are required for computing the Jacobian |
frame | The name of the robot frame at which to compute the Jacobian |
Definition at line 16 of file IController.cpp.
const robot_model::Model & IController::get_robot_model |
Get the robot model associated with the controller.
Definition at line 89 of file IController.hpp.
void IController::set_robot_model | ( | const robot_model::Model & | robot_model | ) |
Set the robot model associated with the controller.
robot_model | The robot model |
Definition at line 97 of file IController.hpp.
|
protected |
The robot model associated with the controller.
Definition at line 85 of file IController.hpp.