|
orwell 0.0.0
|
base class for an impedance controller derived from TorqueController More...
#include <CartesianImpedanceController.hpp>
Public Member Functions | |
| CartesianImpedanceController (const sackmesser::Interface::Ptr &interface, const std::string &name) | |
| loads configuration parameters | |
| RobotState< dof >::Vector | computeCommand () |
| implements the impedance control law | |
Public Member Functions inherited from orwell::ReferenceController< Reference, DerivedController > | |
| ReferenceController (const sackmesser::Interface::Ptr &interface, const std::string &name) | |
| void | setReference (const Reference &reference) |
| set Reference | |
| const Reference & | getReference () const |
| provide access to the Reference to derived classes | |
Protected Member Functions | |
| void | setPositionError (const Eigen::Vector< double, 6 > &position_error) |
| set the value of position_error_ | |
| void | setVelocityError (const Eigen::Vector< double, 6 > &velocity_error) |
| set the value of velocity_error_ | |
| void | setAccelerationError (const Eigen::Vector< double, 6 > &acceleration_error) |
| set the value of acceleration_error_ | |
| Eigen::Vector< double, 6 > | limitWrench (const Eigen::Vector< double, 6 > &wrench) |
| limit the end-effector wrench to the given wrench_limit_ | |
| virtual void | computeStateError ()=0 |
| computes the state error for the impedance control law | |
Additional Inherited Members | |
Public Types inherited from orwell::ReferenceController< Reference, DerivedController > | |
| using | Ptr = std::shared_ptr<ReferenceController> |
| typedef | |
base class for an impedance controller derived from TorqueController
| dof | number of degrees of freedom of the controlled system |
| Reference | reference target |
Definition at line 35 of file CartesianImpedanceController.hpp.
| orwell::CartesianImpedanceController< dof, Reference >::CartesianImpedanceController | ( | const sackmesser::Interface::Ptr & | interface, |
| const std::string & | name ) |
loads configuration parameters
| interface | interfaces the configuration server |
| name | parameter namespace |
Definition at line 30 of file CartesianImpedanceController.hxx.
| RobotState< dof >::Vector orwell::CartesianImpedanceController< dof, Reference >::computeCommand | ( | ) |
implements the impedance control law
derived classes should call setPositionError, setVelocityError and setAccelerationError during computeStateError
Definition at line 66 of file CartesianImpedanceController.hxx.
References orwell::CartesianImpedanceController< dof, Reference >::computeStateError(), and orwell::CartesianImpedanceController< dof, Reference >::limitWrench().
|
protectedpure virtual |
computes the state error for the impedance control law
derived classes should call setPositionError, setVelocityError, setAccelerationError
Referenced by orwell::CartesianImpedanceController< dof, Reference >::computeCommand().
|
protected |
limit the end-effector wrench to the given wrench_limit_
| wrench | wrench computed by getDesiredWrench |
Definition at line 100 of file CartesianImpedanceController.hxx.
Referenced by orwell::CartesianImpedanceController< dof, Reference >::computeCommand().
|
protected |
set the value of acceleration_error_
derived classes should call this function during computeStateError
| acceleration_error | the acceleration error for the impedance control law |
Definition at line 94 of file CartesianImpedanceController.hxx.
|
protected |
set the value of position_error_
derived classes should call this function during computeStateError
| position_error | the position error for the impedance control law |
Definition at line 82 of file CartesianImpedanceController.hxx.
|
protected |
set the value of velocity_error_
derived classes should call this function during computeStateError
| velocity_error | the velocity error for the impedance control law |
Definition at line 88 of file CartesianImpedanceController.hxx.