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

Abstract class to define a controller in a desired state type, such as joint or Cartesian spaces. More...

#include <IController.hpp>

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

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.
 
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 Attributes

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
 

Additional Inherited Members

- 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.
 

Detailed Description

template<class S>
class controllers::IController< S >

Abstract class to define a controller in a desired state type, such as joint or Cartesian spaces.

Template Parameters
SThe state type of the controller

Definition at line 26 of file IController.hpp.

Member Function Documentation

◆ compute_command() [1/3]

template<class S >
virtual S controllers::IController< S >::compute_command ( const S &  command_state,
const S &  feedback_state 
)
pure virtual

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

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 >.

◆ compute_command() [2/3]

template<class S >
JointState IController::compute_command ( const S &  command_state,
const S &  feedback_state,
const state_representation::Jacobian jacobian 
)

Compute the command output in joint space.

Parameters
command_stateThe input state to the controller
feedback_stateThe current state of the system given as feedback
jacobianThe Jacobian matrix relating Cartesian forces to joint space
Returns
The output command in joint space

Definition at line 10 of file IController.cpp.

◆ compute_command() [3/3]

template<class S >
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.

Parameters
command_stateThe input state to the controller
feedback_stateThe current state of the system given as feedback
joint_positionsThe current joint positions, which are required for computing the Jacobian
frameThe name of the robot frame at which to compute the Jacobian
Returns
The output command in joint space

Definition at line 16 of file IController.cpp.

◆ get_robot_model()

template<class S >
const robot_model::Model & IController::get_robot_model ( )

Get the robot model associated with the controller.

Returns
The robot model

Definition at line 89 of file IController.hpp.

◆ set_robot_model()

template<class S >
void IController::set_robot_model ( const robot_model::Model robot_model)

Set the robot model associated with the controller.

Parameters
robot_modelThe robot model

Definition at line 97 of file IController.hpp.

Member Data Documentation

◆ robot_model_

template<class S >
std::shared_ptr<robot_model::Model> controllers::IController< S >::robot_model_
protected

The robot model associated with the controller.

Definition at line 85 of file IController.hpp.


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