orwell 0.0.0
orwell::JointImpedanceController< dof > Class Template Reference

defines an impedance control law in joint space More...

#include <JointImpedanceController.hpp>

Inheritance diagram for orwell::JointImpedanceController< dof >:
orwell::ReferenceController< Reference, DerivedController >

Public Member Functions

 JointImpedanceController (const sackmesser::Interface::Ptr &interface, const std::string &name)
 loads configuration parameters
 
Eigen::Vector< double, dof > computeCommand ()
 computes the control command for the impedance control law in joint space
 
- 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
 

Additional Inherited Members

- Public Types inherited from orwell::ReferenceController< Reference, DerivedController >
using Ptr = std::shared_ptr<ReferenceController>
 typedef
 

Detailed Description

template<int dof>
class orwell::JointImpedanceController< dof >

defines an impedance control law in joint space

takes a joint position as control reference

Template Parameters
dofnumber of degrees of freedom of the controlled system

Definition at line 35 of file JointImpedanceController.hpp.

Constructor & Destructor Documentation

◆ JointImpedanceController()

template<int dof>
orwell::JointImpedanceController< dof >::JointImpedanceController ( const sackmesser::Interface::Ptr & interface,
const std::string & name )

loads configuration parameters

Parameters
interfaceinterfaces the configuration server
nameparameter namespace

Definition at line 28 of file JointImpedanceController.hxx.

29 : TorqueReferenceController<dof, Eigen::Vector<double, dof>>(interface, name)
30 {
31 config_ = interface->getConfigurations()->load<Configuration>(name);
32 }

Member Function Documentation

◆ computeCommand()

template<int dof>
Eigen::Vector< double, dof > orwell::JointImpedanceController< dof >::computeCommand ( )

computes the control command for the impedance control law in joint space

Returns
joint torque command

Definition at line 57 of file JointImpedanceController.hxx.

58 {
59 Eigen::Vector<double, dof> torque = Eigen::Vector<double, dof>::Zero();
60
61 Eigen::Vector<double, dof> position_error = limit(this->getReference() - this->getRobotState().getPosition());
62
63 torque = config_.stiffness_ * position_error + config_.damping_ * (-this->getRobotState().getVelocity());
64
65 return torque;
66 }
const Reference & getReference() const
provide access to the Reference to derived classes

References orwell::ReferenceController< Reference, DerivedController >::getReference().


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