22#include <orwell/torque/TorqueController.hpp>
34 template <
int dof,
class Reference>
71#include <orwell/torque/AdmittanceController.hxx>
base class for an admittance controller derived from TorqueController
RobotState< dof >::Vector computeCommand()
computes the joint torque using forward dynamics
virtual RobotState< dof >::Vector computeDesiredJointAcceleration()=0
admittance control law
AdmittanceController(const sackmesser::Interface::Ptr &interface, const std::string &name)
loads configuration parameters
base implementation of a Controller tracking a given Reference
Eigen::Vector< double, dof > Vector
typedef