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

Robot with geometric and dynamic pinocchio. More...

#include <hpp/pinocchio/device.hh>

Inheritance diagram for hpp::pinocchio::Device:
Collaboration diagram for hpp::pinocchio::Device:

Classes

struct  JointLinearConstraint
 

Public Types

typedef std::pair< JointPtr_t, JointPtr_tCollisionPair_t
 Collision pairs between bodies. More...
 
typedef std::list< CollisionPair_tCollisionPairs_t
 

Public Member Functions

virtual std::ostream & print (std::ostream &os) const
 Print object in a stream. More...
 
fcl::AABB computeAABB () const
 
void controlComputation (const Computation_t &flag)
 
Set pinocchio models and datas
void setModel (ModelPtr_t modelPtr)
 Set pinocchio model. More...
 
void setGeomModel (GeomModelPtr_t geomModelPtr)
 Set pinocchio geom. More...
 
void setData (DataPtr_t dataPtr)
 Set Pinocchio data corresponding to model. More...
 
void createData ()
 Create Pinocchio data from model. More...
 
void setGeomData (GeomDataPtr_t geomDataPtr)
 Set Pinocchio geomData corresponding to model. More...
 
void createGeomData ()
 Create Pinocchio geomData from model. More...
 
Joints
JointPtr_t rootJoint () const
 Get root joint. More...
 
Frame rootFrame () const
 Get root frame. More...
 
size_type nbJoints () const
 Get number of joints. More...
 
JointPtr_t jointAt (const size_type &i) const
 Access i-th joint. More...
 
JointPtr_t getJointAtConfigRank (const size_type &r) const
 
JointPtr_t getJointAtVelocityRank (const size_type &r) const
 
JointPtr_t getJointByName (const std::string &name) const
 
JointPtr_t getJointByBodyName (const std::string &name) const
 
Frame getFrameByName (const std::string &name) const
 
size_type configSize () const
 
size_type numberDof () const
 
const LiegroupSpacePtr_tconfigSpace () const
 Returns a LiegroupSpace representing the configuration space. More...
 
const LiegroupSpacePtr_tRnxSOnConfigSpace () const
 See Joint::RnxSOnConfigurationSpace. More...
 
Configuration_t neutralConfiguration () const
 Get the neutral configuration. More...
 
void addJointConstraint (JointLinearConstraint constraint)
 Add a joint constraint. More...
 
const std::vector< JointLinearConstraint > & jointConstraints () const
 
Extra configuration space
ExtraConfigSpaceextraConfigSpace ()
 
const ExtraConfigSpaceextraConfigSpace () const
 
virtual void setDimensionExtraConfigSpace (const size_type &dimension)
 Set dimension of extra configuration space. More...
 
Grippers
void addGripper (const GripperPtr_t &gripper)
 Add a gripper to the Device. More...
 
Grippers_tgrippers ()
 Return list of grippers of the Device. More...
 
const Grippers_tgrippers () const
 Return list of grippers of the Device. More...
 
Collision and distance computation
BodyPtr_t obstacles () const
 
size_type nbObjects () const
 Number of objects. More...
 
CollisionObjectPtr_t objectAt (const size_type &i) const
 
bool collisionTest (const bool stopAtFirstCollision=true)
 
void computeDistances ()
 
const DistanceResults_tdistanceResults () const
 Get result of distance computations. More...
 
Multithreading

See DeviceSync for how to enable thread safety.

void numberDeviceData (const size_type &s)
 Set the maximum number of concurrent use of the Device. More...
 
size_type numberDeviceData () const
 Get the number of DeviceData. More...
 
- Public Member Functions inherited from hpp::pinocchio::AbstractDevice
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...
 
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...
 
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...
 
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

 Device (const std::string &name)
 Constructor. More...
 
void init (const DeviceWkPtr_t &weakPtr)
 Initialization. More...
 
void initCopy (const DeviceWkPtr_t &weakPtr, const Device &other)
 Initialization of of a clone device. More...
 
 Device (const Device &device)
 Copy Constructor. More...
 
DeviceDatad ()
 
DeviceData const & d () const
 
void invalidate ()
 
- Protected Member Functions inherited from hpp::pinocchio::AbstractDevice
 AbstractDevice ()
 
 AbstractDevice (const ModelPtr_t &m, const GeomModelPtr_t &gm)
 

Protected Attributes

DeviceData d_
 
std::string name_
 
Grippers_t grippers_
 
LiegroupSpacePtr_t configSpace_
 
LiegroupSpacePtr_t configSpaceRnxSOn_
 
ExtraConfigSpace extraConfigSpace_
 
std::vector< JointLinearConstraintjointConstraints_
 
DeviceWkPtr_t weakPtr_
 
- Protected Attributes inherited from hpp::pinocchio::AbstractDevice
ModelPtr_t model_
 
GeomModelPtr_t geomModel_
 

Friends

class Joint
 
class Frame
 
class DeviceSync
 
class CollisionObject
 
class CenterOfMassComputation
 

Construction, copy and destruction

virtual ~Device ()
 
virtual DevicePtr_t clone () const
 Clone as a CkwsDevice The pinocchio model is not copied (only copy the pointer). A new Pinocchio "data" is created. As the model is not copied, cloning is a non constant operation. More...
 
DevicePtr_t cloneConst () const
 Clone as a CkwsDevice Both pinocchio objects model and data are copied. TODO: this method is not implemented yet (assert if called) More...
 
const std::string & name () const
 Get name of device. More...
 
static DevicePtr_t create (const std::string &name)
 Creation of a new device. More...
 
static DevicePtr_t createCopy (const DevicePtr_t &device)
 Copy of a device. More...
 
static DevicePtr_t createCopyConst (const DeviceConstPtr_t &device)
 

Detailed Description

Robot with geometric and dynamic pinocchio.

The creation of the device is done by Device::create(const std::string name). This function returns a shared pointer to the newly created object.

See also
Smart pointers documentation: http://www.boost.org/libs/smart_ptr/smart_ptr.htm

Member Typedef Documentation

◆ CollisionPair_t

Collision pairs between bodies.

◆ CollisionPairs_t

Constructor & Destructor Documentation

◆ ~Device()

virtual hpp::pinocchio::Device::~Device ( )
virtual

◆ Device() [1/2]

hpp::pinocchio::Device::Device ( const std::string &  name)
protected

Constructor.

◆ Device() [2/2]

hpp::pinocchio::Device::Device ( const Device device)
protected

Copy Constructor.

Member Function Documentation

◆ addGripper()

void hpp::pinocchio::Device::addGripper ( const GripperPtr_t gripper)
inline

Add a gripper to the Device.

◆ addJointConstraint()

void hpp::pinocchio::Device::addJointConstraint ( JointLinearConstraint  constraint)

Add a joint constraint.

◆ clone()

virtual DevicePtr_t hpp::pinocchio::Device::clone ( ) const
inlinevirtual

Clone as a CkwsDevice The pinocchio model is not copied (only copy the pointer). A new Pinocchio "data" is created. As the model is not copied, cloning is a non constant operation.

See also
cloneConst

Reimplemented in hpp::pinocchio::HumanoidRobot.

◆ cloneConst()

DevicePtr_t hpp::pinocchio::Device::cloneConst ( ) const
inline

Clone as a CkwsDevice Both pinocchio objects model and data are copied. TODO: this method is not implemented yet (assert if called)

◆ collisionTest()

bool hpp::pinocchio::Device::collisionTest ( const bool  stopAtFirstCollision = true)

Test collision of current configuration

Parameters
stopAtFirstCollisionact as named
Warning
Users should call computeForwardKinematics first.

◆ computeAABB()

fcl::AABB hpp::pinocchio::Device::computeAABB ( ) const

Compute an aligned bounding around the robot. The bounding box is computed as follows:

  • for each direct children of the universe joint:
    • compute a bounding box of its center (using the bounds in translation)
    • compute the maximal distance between the its center and each bodies attach its subtree.
    • sum the two.
  • sum all the BB obtained.

◆ computeDistances()

void hpp::pinocchio::Device::computeDistances ( )

Compute distances between pairs of objects stored in bodies

Warning
Users should call computeForwardKinematics first.

◆ configSize()

size_type hpp::pinocchio::Device::configSize ( ) const

Size of configuration vectors Sum of joint dimensions and of extra configuration space dimension

◆ configSpace()

const LiegroupSpacePtr_t& hpp::pinocchio::Device::configSpace ( ) const
inline

Returns a LiegroupSpace representing the configuration space.

◆ controlComputation()

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

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

Reimplemented from hpp::pinocchio::AbstractDevice.

◆ create()

static DevicePtr_t hpp::pinocchio::Device::create ( const std::string &  name)
static

Creation of a new device.

Returns
a shared pointer to the new device
Parameters
nameName of the device

◆ createCopy()

static DevicePtr_t hpp::pinocchio::Device::createCopy ( const DevicePtr_t device)
static

Copy of a device.

Returns
A shared pointer to new device.
Parameters
deviceDevice to be copied. The pinocchio model is not copied (only copy the pointer). A new Pinocchio "data" is created.

◆ createCopyConst()

static DevicePtr_t hpp::pinocchio::Device::createCopyConst ( const DeviceConstPtr_t device)
static

◆ createData()

void hpp::pinocchio::Device::createData ( )

Create Pinocchio data from model.

◆ createGeomData()

void hpp::pinocchio::Device::createGeomData ( )

Create Pinocchio geomData from model.

◆ d() [1/2]

DeviceData& hpp::pinocchio::Device::d ( )
inlineprotectedvirtual

◆ d() [2/2]

DeviceData const& hpp::pinocchio::Device::d ( ) const
inlineprotectedvirtual

◆ distanceResults()

const DistanceResults_t& hpp::pinocchio::Device::distanceResults ( ) const

Get result of distance computations.

◆ extraConfigSpace() [1/2]

ExtraConfigSpace& hpp::pinocchio::Device::extraConfigSpace ( )
inline

Get degrees of freedom to store internal values in configurations

In some applications, it is useful to store extra variables with the configuration vector. For instance, when planning motions in state space using roadmap based methods, the velocity of the robot is stored in the nodes of the roadmap.

◆ extraConfigSpace() [2/2]

const ExtraConfigSpace& hpp::pinocchio::Device::extraConfigSpace ( ) const
inline

Get degrees of freedom to store internal values in configurations

In some applications, it is useful to store extra variables with the configuration vector. For instance, when planning motions in state space using roadmap based methods, the velocity of the robot is stored in the nodes of the roadmap.

◆ getFrameByName()

Frame hpp::pinocchio::Device::getFrameByName ( const std::string &  name) const

Get frame by name

Parameters
namename of the frame.
Exceptions
runtime_errorif device has no frame with this name

◆ getJointAtConfigRank()

JointPtr_t hpp::pinocchio::Device::getJointAtConfigRank ( const size_type r) const

Get the joint at configuration rank r

Returns
joint j such that j->rankInConfiguration () <= r < j->rankInConfiguration () + j->configSize ()

◆ getJointAtVelocityRank()

JointPtr_t hpp::pinocchio::Device::getJointAtVelocityRank ( const size_type r) const

Get the joint at velocity rank r

Returns
joint j such that j->rankInVelocity () <= r < j->rankInVelocity () + j->numberDof ()

◆ getJointByBodyName()

JointPtr_t hpp::pinocchio::Device::getJointByBodyName ( const std::string &  name) const

Get joint by body name

Exceptions
runtime_errorif device has no body with this name

◆ getJointByName()

JointPtr_t hpp::pinocchio::Device::getJointByName ( const std::string &  name) const

Get joint by name

Parameters
namename of the joint.
Exceptions
runtime_errorif device has no joint with this name

◆ grippers() [1/2]

Grippers_t& hpp::pinocchio::Device::grippers ( )
inline

Return list of grippers of the Device.

◆ grippers() [2/2]

const Grippers_t& hpp::pinocchio::Device::grippers ( ) const
inline

Return list of grippers of the Device.

◆ init()

void hpp::pinocchio::Device::init ( const DeviceWkPtr_t &  weakPtr)
protected

Initialization.

◆ initCopy()

void hpp::pinocchio::Device::initCopy ( const DeviceWkPtr_t &  weakPtr,
const Device other 
)
protected

Initialization of of a clone device.

◆ invalidate()

void hpp::pinocchio::Device::invalidate ( )
inlineprotected

◆ jointAt()

JointPtr_t hpp::pinocchio::Device::jointAt ( const size_type i) const

Access i-th joint.

◆ jointConstraints()

const std::vector<JointLinearConstraint>& hpp::pinocchio::Device::jointConstraints ( ) const
inline

◆ name()

const std::string& hpp::pinocchio::Device::name ( ) const
inline

Get name of device.

◆ nbJoints()

size_type hpp::pinocchio::Device::nbJoints ( ) const

Get number of joints.

◆ nbObjects()

size_type hpp::pinocchio::Device::nbObjects ( ) const

Number of objects.

◆ neutralConfiguration()

Configuration_t hpp::pinocchio::Device::neutralConfiguration ( ) const

Get the neutral configuration.

◆ numberDeviceData() [1/2]

void hpp::pinocchio::Device::numberDeviceData ( const size_type s)

Set the maximum number of concurrent use of the Device.

◆ numberDeviceData() [2/2]

size_type hpp::pinocchio::Device::numberDeviceData ( ) const

Get the number of DeviceData.

◆ numberDof()

size_type hpp::pinocchio::Device::numberDof ( ) const

Size of velocity vectors Sum of joint number of degrees of freedom and of extra configuration space dimension

◆ objectAt()

CollisionObjectPtr_t hpp::pinocchio::Device::objectAt ( const size_type i) const

Access the i-th object.

See also
Device::nbObjects() const

◆ obstacles()

BodyPtr_t hpp::pinocchio::Device::obstacles ( ) const

Get the static obstacles It corresponds to the geometries attached to the universe in pinocchio.

◆ print()

virtual std::ostream& hpp::pinocchio::Device::print ( std::ostream &  os) const
virtual

Print object in a stream.

◆ RnxSOnConfigSpace()

const LiegroupSpacePtr_t& hpp::pinocchio::Device::RnxSOnConfigSpace ( ) const
inline

◆ rootFrame()

Frame hpp::pinocchio::Device::rootFrame ( ) const

Get root frame.

◆ rootJoint()

JointPtr_t hpp::pinocchio::Device::rootJoint ( ) const

Get root joint.

◆ setData()

void hpp::pinocchio::Device::setData ( DataPtr_t  dataPtr)
inline

Set Pinocchio data corresponding to model.

◆ setDimensionExtraConfigSpace()

virtual void hpp::pinocchio::Device::setDimensionExtraConfigSpace ( const size_type dimension)
inlinevirtual

Set dimension of extra configuration space.

◆ setGeomData()

void hpp::pinocchio::Device::setGeomData ( GeomDataPtr_t  geomDataPtr)
inline

Set Pinocchio geomData corresponding to model.

◆ setGeomModel()

void hpp::pinocchio::Device::setGeomModel ( GeomModelPtr_t  geomModelPtr)
inline

Set pinocchio geom.

◆ setModel()

void hpp::pinocchio::Device::setModel ( ModelPtr_t  modelPtr)
inline

Set pinocchio model.

Friends And Related Function Documentation

◆ CenterOfMassComputation

friend class CenterOfMassComputation
friend

◆ CollisionObject

friend class CollisionObject
friend

◆ DeviceSync

friend class DeviceSync
friend

◆ Frame

friend class Frame
friend

◆ Joint

friend class Joint
friend

Member Data Documentation

◆ configSpace_

LiegroupSpacePtr_t hpp::pinocchio::Device::configSpace_
protected

◆ configSpaceRnxSOn_

LiegroupSpacePtr_t hpp::pinocchio::Device::configSpaceRnxSOn_
protected

◆ d_

DeviceData hpp::pinocchio::Device::d_
protected

◆ extraConfigSpace_

ExtraConfigSpace hpp::pinocchio::Device::extraConfigSpace_
protected

◆ grippers_

Grippers_t hpp::pinocchio::Device::grippers_
protected

◆ jointConstraints_

std::vector<JointLinearConstraint> hpp::pinocchio::Device::jointConstraints_
protected

◆ name_

std::string hpp::pinocchio::Device::name_
protected

◆ weakPtr_

DeviceWkPtr_t hpp::pinocchio::Device::weakPtr_
protected

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