orwell 0.0.0
orwell::RobotModel< dof > Class Template Referenceabstract

base class for a RobotModel to interface different kinematics/dynamics libraries More...

#include <RobotModel.hpp>

Public Types

using Vector = typename RobotState<dof>::Vector
 typedef
 
using Ptr = std::shared_ptr<RobotModel>
 typedef
 

Public Member Functions

virtual void computeCartesianState (const orwell::RobotState< dof > &robot_state)=0
 precompute robot specific quantities for the given RobotState
 
virtual Vector computeForwardDynamics (const Vector &position, const Vector &velocity, const Vector &acceleration, const double &gravity)=0
 interface the computation of the forward dynamics for the used kinematics/dynamics library
 
virtual const Eigen::Matrix< double, 6, dof > & getJacobian () const =0
 access the Jacobian Matrix
 

Detailed Description

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

base class for a RobotModel to interface different kinematics/dynamics libraries

Template Parameters
dofnumber of degrees of freedom of the controlled system

Definition at line 36 of file RobotModel.hpp.

Member Typedef Documentation

◆ Ptr

template<int dof>
using orwell::RobotModel< dof >::Ptr = std::shared_ptr<RobotModel>

typedef

Definition at line 84 of file RobotModel.hpp.

◆ Vector

template<int dof>
using orwell::RobotModel< dof >::Vector = typename RobotState<dof>::Vector

typedef

Definition at line 52 of file RobotModel.hpp.

Member Function Documentation

◆ computeCartesianState()

template<int dof>
virtual void orwell::RobotModel< dof >::computeCartesianState ( const orwell::RobotState< dof > & robot_state)
pure virtual

precompute robot specific quantities for the given RobotState

will be called by Controller::getControlCommand

Parameters
robot_statecurrent RobotState

◆ computeForwardDynamics()

template<int dof>
virtual Vector orwell::RobotModel< dof >::computeForwardDynamics ( const Vector & position,
const Vector & velocity,
const Vector & acceleration,
const double & gravity )
pure virtual

interface the computation of the forward dynamics for the used kinematics/dynamics library

Parameters
positionrobot joint position
velocityrobot joint velocity
accelerationrobot joint acceleration
gravitygravity value
Returns
robot joint torque

◆ getJacobian()

template<int dof>
virtual const Eigen::Matrix< double, 6, dof > & orwell::RobotModel< dof >::getJacobian ( ) const
pure virtual

access the Jacobian Matrix

since the RobotState is not passed to this function, it is expected that it is being computed during the call to computeCartesianState

Returns
Jacobian martix

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