hpp::model::HumanoidRobot Class Reference

Humanoid robot. More...

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

Inheritance diagram for hpp::model::HumanoidRobot:
Collaboration diagram for hpp::model::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 ()
 
HumanoidRobotPtr_t clone () const
 Clone as a CkwsDevice. More...
 
- Public Member Functions inherited from hpp::model::Device
const std::string & name () const
 Get name of device. More...
 
virtual std::ostream & print (std::ostream &os) const
 Print object in a stream. More...
 
virtual ~Device ()
 
DevicePtr_t clone () const
 Clone as a CkwsDevice. More...
 
void rootJoint (JointPtr_t joint)
 Set the root of the kinematic chain. More...
 
void rootJointPosition (const Transform3f &position)
 Set position of root joint in world frame. More...
 
JointPtr_t rootJoint () const
 Get root joint. More...
 
void registerJoint (const JointPtr_t &joint)
 Register joint in internal containers. More...
 
const JointVector_tgetJointVector () const
 Get vector of joints. More...
 
JointPtr_t getJointByName (const std::string &name) const
 Get joint by name. More...
 
JointPtr_t getJointByBodyName (const std::string &name) const
 Get joint by body name. More...
 
size_type configSize () const
 Size of configuration vectors Sum of joint dimensions and of extra configuration space dimension. More...
 
size_type numberDof () const
 Size of velocity vectors Sum of joint number of degrees of freedom and of extra configuration space dimension. More...
 
ExtraConfigSpaceextraConfigSpace ()
 Get degrees of freedom to store internal values in configurations. More...
 
const ExtraConfigSpaceextraConfigSpace () const
 Get degrees of freedom to store internal values in configurations. More...
 
void setDimensionExtraConfigSpace (const size_type &dimension)
 Set dimension of extra configuration space. More...
 
const Configuration_tcurrentConfiguration () const
 Get current configuration. More...
 
virtual bool currentConfiguration (ConfigurationIn_t configuration)
 Set current configuration. More...
 
Configuration_t neutralConfiguration () const
 Get the neutral configuration. More...
 
const vector_tcurrentVelocity () const
 Get current velocity. More...
 
void currentVelocity (vectorIn_t velocity)
 Set current velocity. More...
 
const vector_tcurrentAcceleration () const
 Get current acceleration. More...
 
void 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...
 
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...
 
const ObjectVector_tobstacles (Request_t type) const
 Get list of obstacles. More...
 
virtual void addCollisionPairs (const JointPtr_t &joint1, const JointPtr_t &joint2, Request_t type)
 Add collision pairs between objects attached to two joints. More...
 
virtual void removeCollisionPairs (const JointPtr_t &joint1, const JointPtr_t &joint2, Request_t type)
 Remove collision pairs between objects attached to two joints. More...
 
const CollisionPairs_tcollisionPairs (Request_t type) const
 Get list of collision or distance pairs. More...
 
ObjectIterator objectIterator (Request_t type)
 Iterator over inner objects of the device. More...
 
bool collisionTest () const
 Test collision of current configuration. More...
 
void computeDistances ()
 Compute distances between pairs of objects stored in bodies. More...
 
const DistanceResults_tdistanceResults () const
 Get result of distance computations. More...
 
void controlComputation (const Computation_t &flag)
 Select computation Optimize computation time by selecting only necessary values in method computeForwardKinematics. More...
 
Computation_t computationFlag () const
 Get computation flag. More...
 
virtual void computeForwardKinematics ()
 Compute forward kinematics. 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::model::Device
static DevicePtr_t create (std::string name)
 Creation of a new device. More...
 
static DevicePtr_t createCopy (const DevicePtr_t &device)
 Copy of a device. More...
 

Protected Member Functions

 HumanoidRobot (const std::string &name)
 Constructor. More...
 
void init (const HumanoidRobotWkPtr_t &weakPtr)
 Initialization. More...
 
- Protected Member Functions inherited from hpp::model::Device
 Device (const std::string &name)
 Constructor. More...
 
void init (const DeviceWkPtr_t &weakPtr)
 Initialization. More...
 
void updateDistances ()
 Recompute number of distance pairs. More...
 

Additional Inherited Members

- Public Types inherited from hpp::model::Device
enum  Computation_t {
  JOINT_POSITION = 0x0,
  JACOBIAN = 0x1,
  VELOCITY = 0x2,
  ACCELERATION = 0x4,
  COM = 0x8,
  ALL = 0Xffff
}
 Flags to select computation To optimize computation time, computations performed by method computeForwardKinematics can be selected by calling method controlComputation. More...
 
typedef std::pair< JointPtr_t, JointPtr_tCollisionPair_t
 Collision pairs between bodies. More...
 
typedef std::list< CollisionPair_tCollisionPairs_t
 

Detailed Description

Humanoid robot.

Constructor & Destructor Documentation

◆ ~HumanoidRobot()

virtual hpp::model::HumanoidRobot::~HumanoidRobot ( )
virtual

◆ HumanoidRobot()

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

Constructor.

Member Function Documentation

◆ chest() [1/2]

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

Get Joint corresponding to the chest.

◆ chest() [2/2]

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

Set chest joint.

◆ clone()

HumanoidRobotPtr_t hpp::model::HumanoidRobot::clone ( ) const

Clone as a CkwsDevice.

◆ create()

static HumanoidRobotPtr_t hpp::model::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)

Referenced by hpp::model::ObjectFactory::createHumanoidRobot().

◆ gaze()

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

Set gaze parameters.

◆ gazeJoint() [1/2]

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

Get gaze joint.

◆ gazeJoint() [2/2]

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

Set gaze joint.

◆ init()

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

Initialization.

◆ leftAnkle() [1/2]

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

Get Joint corresponding to the left ankle.

◆ leftAnkle() [2/2]

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

Set letf ankle.

◆ leftWrist() [1/2]

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

Get Joint corresponding to the left wrist.

◆ leftWrist() [2/2]

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

Set left wrist.

◆ rightAnkle() [1/2]

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

Get Joint corresponding to the right ankle.

◆ rightAnkle() [2/2]

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

Set right ankle.

◆ rightWrist() [1/2]

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

Get Joint corresponding to the right wrist.

◆ rightWrist() [2/2]

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

Set right wrist.

◆ waist() [1/2]

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

Get Joint corresponding to the waist.

◆ waist() [2/2]

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

Set waist joint.