orwell 0.0.0
orwell::AdmittanceController< dof, Reference > Class Template Referenceabstract

base class for an admittance controller derived from TorqueController More...

#include <AdmittanceController.hpp>

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

Public Member Functions

 AdmittanceController (const sackmesser::Interface::Ptr &interface, const std::string &name)
 loads configuration parameters
 
RobotState< dof >::Vector computeCommand ()
 computes the joint torque using forward dynamics
 
- 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

virtual RobotState< dof >::Vector computeDesiredJointAcceleration ()=0
 admittance control law
 

Additional Inherited Members

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

Detailed Description

template<int dof, class Reference>
class orwell::AdmittanceController< dof, Reference >

base class for an admittance controller derived from TorqueController

Template Parameters
dofnumber of degrees of freedom of the controlled system
Referencereference target

Definition at line 35 of file AdmittanceController.hpp.

Constructor & Destructor Documentation

◆ AdmittanceController()

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

loads configuration parameters

Parameters
interfaceinterfaces the configuration server
nameparameter namespace

Definition at line 30 of file AdmittanceController.hxx.

31 : TorqueReferenceController<dof, Reference>(interface, name)
32 {}

Member Function Documentation

◆ computeCommand()

template<int dof, class Reference >
RobotState< dof >::Vector orwell::AdmittanceController< dof, Reference >::computeCommand ( )

computes the joint torque using forward dynamics

Returns
joint torque command

Definition at line 38 of file AdmittanceController.hxx.

39 {
40 const typename RobotState<dof>::Vector &position = this->getRobotState().getPosition();
41 const typename RobotState<dof>::Vector &velocity = this->getRobotState().getVelocity();
43
44 return this->getRobotModel()->computeForwardDynamics(position, velocity, acceleration, 0.0);
45 }
virtual RobotState< dof >::Vector computeDesiredJointAcceleration()=0
admittance control law
Eigen::Vector< double, dof > Vector
typedef

◆ computeDesiredJointAcceleration()

template<int dof, class Reference >
virtual RobotState< dof >::Vector orwell::AdmittanceController< dof, Reference >::computeDesiredJointAcceleration ( )
protectedpure virtual

admittance control law

Returns
desired joint acceleration

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