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

Humanoid robot. More...

#include <hpp/pinocchio/humanoid-robot.hh>

Inheritance diagram for hpp::pinocchio::HumanoidRobot:
Collaboration diagram for hpp::pinocchio::HumanoidRobot:

Public Member Functions

JointPtr_t waist () const
 Get Joint corresponding to the waist. More...
 
void waist (const JointPtr_t &joint)
 Set waist joint. More...
 
JointPtr_t chest () const
 Get Joint corresponding to the chest. More...
 
void chest (const JointPtr_t &joint)
 Set chest joint. More...
 
JointPtr_t leftWrist () const
 Get Joint corresponding to the left wrist. More...
 
void leftWrist (const JointPtr_t &joint)
 Set left wrist. More...
 
JointPtr_t rightWrist () const
 Get Joint corresponding to the right wrist. More...
 
void rightWrist (const JointPtr_t &joint)
 Set right wrist. More...
 
JointPtr_t leftAnkle () const
 Get Joint corresponding to the left ankle. More...
 
void leftAnkle (const JointPtr_t &joint)
 Set letf ankle. More...
 
JointPtr_t rightAnkle () const
 Get Joint corresponding to the right ankle. More...
 
void rightAnkle (const JointPtr_t &joint)
 Set right ankle. More...
 
JointPtr_t gazeJoint () const
 Get gaze joint. More...
 
void gazeJoint (const JointPtr_t &joint)
 Set gaze joint. More...
 
void gaze (const vector3_t &origin, const vector3_t &dir)
 Set gaze parameters. More...
 
Construction, copy and destruction
virtual ~HumanoidRobot ()
 
virtual DevicePtr_t clone () const
 Clone as a HumanoidRobot. More...
 
- Public Member Functions inherited from hpp::pinocchio::Device
virtual std::ostream & print (std::ostream &os) const
 Print object in a stream. More...
 
fcl::AABB computeAABB () const
 
void controlComputation (const Computation_t &flag)
 
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...
 
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
 
ExtraConfigSpaceextraConfigSpace ()
 
const ExtraConfigSpaceextraConfigSpace () const
 
virtual void setDimensionExtraConfigSpace (const size_type &dimension)
 Set dimension of extra configuration space. More...
 
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...
 
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...
 
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...
 
virtual ~Device ()
 
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...
 
- 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...
 

Static Public Member Functions

static HumanoidRobotPtr_t create (const std::string &name)
 Creation of a new device. More...
 
- Static Public Member Functions inherited from hpp::pinocchio::Device
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)
 

Protected Member Functions

 HumanoidRobot (const std::string &name)
 Constructor. More...
 
 HumanoidRobot (const HumanoidRobot &other)
 
void init (const HumanoidRobotWkPtr_t &weakPtr)
 Initialization. More...
 
void initCopy (const HumanoidRobotWkPtr_t &weakPtr, const HumanoidRobot &other)
 
- Protected Member Functions inherited from hpp::pinocchio::Device
 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)
 

Additional Inherited Members

- Public Types inherited from hpp::pinocchio::Device
typedef std::pair< JointPtr_t, JointPtr_tCollisionPair_t
 Collision pairs between bodies. More...
 
typedef std::list< CollisionPair_tCollisionPairs_t
 
- Protected Attributes inherited from hpp::pinocchio::Device
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_
 

Detailed Description

Humanoid robot.

Constructor & Destructor Documentation

◆ ~HumanoidRobot()

virtual hpp::pinocchio::HumanoidRobot::~HumanoidRobot ( )
virtual

◆ HumanoidRobot() [1/2]

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

Constructor.

◆ HumanoidRobot() [2/2]

hpp::pinocchio::HumanoidRobot::HumanoidRobot ( const HumanoidRobot other)
protected

Member Function Documentation

◆ chest() [1/2]

JointPtr_t hpp::pinocchio::HumanoidRobot::chest ( ) const

Get Joint corresponding to the chest.

◆ chest() [2/2]

void hpp::pinocchio::HumanoidRobot::chest ( const JointPtr_t joint)

Set chest joint.

◆ clone()

virtual DevicePtr_t hpp::pinocchio::HumanoidRobot::clone ( ) const
virtual

Clone as a HumanoidRobot.

Reimplemented from hpp::pinocchio::Device.

◆ create()

static HumanoidRobotPtr_t hpp::pinocchio::HumanoidRobot::create ( const std::string &  name)
static

Creation of a new device.

Returns
a shared pointer to the new device
Parameters
nameName of the device (is passed to CkkpDeviceComponent)

◆ gaze()

void hpp::pinocchio::HumanoidRobot::gaze ( const vector3_t origin,
const vector3_t dir 
)
inline

Set gaze parameters.

◆ gazeJoint() [1/2]

JointPtr_t hpp::pinocchio::HumanoidRobot::gazeJoint ( ) const

Get gaze joint.

◆ gazeJoint() [2/2]

void hpp::pinocchio::HumanoidRobot::gazeJoint ( const JointPtr_t joint)

Set gaze joint.

◆ init()

void hpp::pinocchio::HumanoidRobot::init ( const HumanoidRobotWkPtr_t &  weakPtr)
protected

Initialization.

◆ initCopy()

void hpp::pinocchio::HumanoidRobot::initCopy ( const HumanoidRobotWkPtr_t &  weakPtr,
const HumanoidRobot other 
)
protected

◆ leftAnkle() [1/2]

JointPtr_t hpp::pinocchio::HumanoidRobot::leftAnkle ( ) const

Get Joint corresponding to the left ankle.

◆ leftAnkle() [2/2]

void hpp::pinocchio::HumanoidRobot::leftAnkle ( const JointPtr_t joint)

Set letf ankle.

◆ leftWrist() [1/2]

JointPtr_t hpp::pinocchio::HumanoidRobot::leftWrist ( ) const

Get Joint corresponding to the left wrist.

◆ leftWrist() [2/2]

void hpp::pinocchio::HumanoidRobot::leftWrist ( const JointPtr_t joint)

Set left wrist.

◆ rightAnkle() [1/2]

JointPtr_t hpp::pinocchio::HumanoidRobot::rightAnkle ( ) const

Get Joint corresponding to the right ankle.

◆ rightAnkle() [2/2]

void hpp::pinocchio::HumanoidRobot::rightAnkle ( const JointPtr_t joint)

Set right ankle.

◆ rightWrist() [1/2]

JointPtr_t hpp::pinocchio::HumanoidRobot::rightWrist ( ) const

Get Joint corresponding to the right wrist.

◆ rightWrist() [2/2]

void hpp::pinocchio::HumanoidRobot::rightWrist ( const JointPtr_t joint)

Set right wrist.

◆ waist() [1/2]

JointPtr_t hpp::pinocchio::HumanoidRobot::waist ( ) const

Get Joint corresponding to the waist.

◆ waist() [2/2]

void hpp::pinocchio::HumanoidRobot::waist ( const JointPtr_t joint)

Set waist joint.


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