hpp-pinocchio  4.9.1
Wrapping of the kinematic/dynamic chain Pinocchio for HPP.
hpp::pinocchio::AbstractDevice Class Referenceabstract

Abstract class representing a Device. More...

#include <hpp/pinocchio/device-sync.hh>

Inheritance diagram for hpp::pinocchio::AbstractDevice:

Public Member Functions

Access to pinocchio API
ModelConstPtr_t modelPtr () const
 Access to pinocchio model. More...
 
ModelPtr_t modelPtr ()
 Access to pinocchio model. More...
 
const Modelmodel () const
 Access to pinocchio model. More...
 
Modelmodel ()
 Access to pinocchio model. More...
 
GeomModelConstPtr_t geomModelPtr () const
 Access to pinocchio geomModel. More...
 
GeomModelPtr_t geomModelPtr ()
 Access to pinocchio geomModel. More...
 
const GeomModelgeomModel () const
 Access to pinocchio geomModel. More...
 
GeomModelgeomModel ()
 Access to pinocchio geomModel. More...
 
DataConstPtr_t dataPtr () const
 Access to Pinocchio data/. More...
 
DataPtr_t dataPtr ()
 Access to Pinocchio data/. More...
 
const Datadata () const
 Access to Pinocchio data/. More...
 
Datadata ()
 Access to Pinocchio data/. More...
 
GeomDataConstPtr_t geomDataPtr () const
 Access to Pinocchio geomData/. More...
 
GeomDataPtr_t geomDataPtr ()
 Access to Pinocchio geomData/. More...
 
const GeomDatageomData () const
 Access to Pinocchio geomData/. More...
 
GeomDatageomData ()
 Access to Pinocchio geomData/. More...
 
Current state
const Configuration_tcurrentConfiguration () const
 Get current configuration. More...
 
virtual bool currentConfiguration (ConfigurationIn_t configuration)
 
const vector_tcurrentVelocity () const
 Get current velocity. More...
 
bool currentVelocity (vectorIn_t velocity)
 Set current velocity. More...
 
const vector_tcurrentAcceleration () const
 Get current acceleration. More...
 
bool currentAcceleration (vectorIn_t acceleration)
 Set current acceleration. More...
 
Mass and center of mass
const value_typemass () const
 Get mass of robot. More...
 
const vector3_tpositionCenterOfMass () const
 Get position of center of mass. More...
 
const ComJacobian_tjacobianCenterOfMass () const
 Get Jacobian of center of mass with respect to configuration. More...
 
Forward kinematics
virtual void controlComputation (const Computation_t &flag)
 
Computation_t computationFlag () const
 Get computation flag. More...
 
void computeForwardKinematics ()
 Compute forward kinematics. More...
 
void computeFramesForwardKinematics ()
 
void updateGeometryPlacements ()
 Update the geometry placement to the currentConfiguration. More...
 

Protected Member Functions

 AbstractDevice ()
 
 AbstractDevice (const ModelPtr_t &m, const GeomModelPtr_t &gm)
 
virtual DeviceDatad ()=0
 
virtual DeviceData const & d () const =0
 

Protected Attributes

ModelPtr_t model_
 
GeomModelPtr_t geomModel_
 

Detailed Description

Abstract class representing a Device.

Constructor & Destructor Documentation

◆ AbstractDevice() [1/2]

hpp::pinocchio::AbstractDevice::AbstractDevice ( )
protected

◆ AbstractDevice() [2/2]

hpp::pinocchio::AbstractDevice::AbstractDevice ( const ModelPtr_t m,
const GeomModelPtr_t gm 
)
protected

Member Function Documentation

◆ computationFlag()

Computation_t hpp::pinocchio::AbstractDevice::computationFlag ( ) const
inline

Get computation flag.

◆ computeForwardKinematics()

void hpp::pinocchio::AbstractDevice::computeForwardKinematics ( )
inline

Compute forward kinematics.

◆ computeFramesForwardKinematics()

void hpp::pinocchio::AbstractDevice::computeFramesForwardKinematics ( )
inline

Compute frame forward kinematics

Note
call AbstractDevice::computeForwardKinematics.

◆ controlComputation()

virtual void hpp::pinocchio::AbstractDevice::controlComputation ( const Computation_t flag)
virtual

Select computation Optimize computation time by selecting only necessary values in method computeForwardKinematics.

Reimplemented in hpp::pinocchio::Device.

◆ currentAcceleration() [1/2]

const vector_t& hpp::pinocchio::AbstractDevice::currentAcceleration ( ) const
inline

Get current acceleration.

◆ currentAcceleration() [2/2]

bool hpp::pinocchio::AbstractDevice::currentAcceleration ( vectorIn_t  acceleration)

Set current acceleration.

◆ currentConfiguration() [1/2]

const Configuration_t& hpp::pinocchio::AbstractDevice::currentConfiguration ( ) const
inline

Get current configuration.

◆ currentConfiguration() [2/2]

virtual bool hpp::pinocchio::AbstractDevice::currentConfiguration ( ConfigurationIn_t  configuration)
virtual

Set current configuration

Returns
True if the current configuration was modified and false if the current configuration did not change.

◆ currentVelocity() [1/2]

const vector_t& hpp::pinocchio::AbstractDevice::currentVelocity ( ) const
inline

Get current velocity.

◆ currentVelocity() [2/2]

bool hpp::pinocchio::AbstractDevice::currentVelocity ( vectorIn_t  velocity)

Set current velocity.

◆ d() [1/2]

virtual DeviceData& hpp::pinocchio::AbstractDevice::d ( )
protectedpure virtual

◆ d() [2/2]

virtual DeviceData const& hpp::pinocchio::AbstractDevice::d ( ) const
protectedpure virtual

◆ data() [1/2]

const Data& hpp::pinocchio::AbstractDevice::data ( ) const
inline

Access to Pinocchio data/.

◆ data() [2/2]

Data& hpp::pinocchio::AbstractDevice::data ( )
inline

Access to Pinocchio data/.

◆ dataPtr() [1/2]

DataConstPtr_t hpp::pinocchio::AbstractDevice::dataPtr ( ) const
inline

Access to Pinocchio data/.

◆ dataPtr() [2/2]

DataPtr_t hpp::pinocchio::AbstractDevice::dataPtr ( )
inline

Access to Pinocchio data/.

◆ geomData() [1/2]

const GeomData& hpp::pinocchio::AbstractDevice::geomData ( ) const
inline

Access to Pinocchio geomData/.

◆ geomData() [2/2]

GeomData& hpp::pinocchio::AbstractDevice::geomData ( )
inline

Access to Pinocchio geomData/.

◆ geomDataPtr() [1/2]

GeomDataConstPtr_t hpp::pinocchio::AbstractDevice::geomDataPtr ( ) const
inline

Access to Pinocchio geomData/.

◆ geomDataPtr() [2/2]

GeomDataPtr_t hpp::pinocchio::AbstractDevice::geomDataPtr ( )
inline

Access to Pinocchio geomData/.

◆ geomModel() [1/2]

const GeomModel& hpp::pinocchio::AbstractDevice::geomModel ( ) const
inline

Access to pinocchio geomModel.

◆ geomModel() [2/2]

GeomModel& hpp::pinocchio::AbstractDevice::geomModel ( )
inline

Access to pinocchio geomModel.

◆ geomModelPtr() [1/2]

GeomModelConstPtr_t hpp::pinocchio::AbstractDevice::geomModelPtr ( ) const
inline

Access to pinocchio geomModel.

◆ geomModelPtr() [2/2]

GeomModelPtr_t hpp::pinocchio::AbstractDevice::geomModelPtr ( )
inline

Access to pinocchio geomModel.

◆ jacobianCenterOfMass()

const ComJacobian_t& hpp::pinocchio::AbstractDevice::jacobianCenterOfMass ( ) const

Get Jacobian of center of mass with respect to configuration.

◆ mass()

const value_type& hpp::pinocchio::AbstractDevice::mass ( ) const

Get mass of robot.

◆ model() [1/2]

const Model& hpp::pinocchio::AbstractDevice::model ( ) const
inline

Access to pinocchio model.

◆ model() [2/2]

Model& hpp::pinocchio::AbstractDevice::model ( )
inline

Access to pinocchio model.

◆ modelPtr() [1/2]

ModelConstPtr_t hpp::pinocchio::AbstractDevice::modelPtr ( ) const
inline

Access to pinocchio model.

◆ modelPtr() [2/2]

ModelPtr_t hpp::pinocchio::AbstractDevice::modelPtr ( )
inline

Access to pinocchio model.

◆ positionCenterOfMass()

const vector3_t& hpp::pinocchio::AbstractDevice::positionCenterOfMass ( ) const

Get position of center of mass.

◆ updateGeometryPlacements()

void hpp::pinocchio::AbstractDevice::updateGeometryPlacements ( )
inline

Update the geometry placement to the currentConfiguration.

Member Data Documentation

◆ geomModel_

GeomModelPtr_t hpp::pinocchio::AbstractDevice::geomModel_
protected

◆ model_

ModelPtr_t hpp::pinocchio::AbstractDevice::model_
protected

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