Humanoid robot. More...
#include <hpp/pinocchio/humanoid-robot.hh>
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 |
| Compute an aligned bounding around the robot. More... | |
| void | controlComputation (const Computation_t &flag) |
| Select computation Optimize computation time by selecting only necessary values in method computeForwardKinematics. More... | |
| 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 |
| Get the joint at configuration rank r. More... | |
| JointPtr_t | getJointAtVelocityRank (const size_type &r) const |
| Get the joint at velocity rank r. 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... | |
| Frame | getFrameByName (const std::string &name) const |
| Get frame by 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... | |
| const LiegroupSpacePtr_t & | configSpace () const |
| Returns a LiegroupSpace representing the configuration space. More... | |
| LiegroupSpacePtr_t | RnxSOnConfigSpace () 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 |
| ExtraConfigSpace & | extraConfigSpace () |
| Get degrees of freedom to store internal values in configurations. More... | |
| const ExtraConfigSpace & | extraConfigSpace () const |
| Get degrees of freedom to store internal values in configurations. More... | |
| 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_t & | grippers () |
| Return list of grippers of the Device. More... | |
| const Grippers_t & | grippers () const |
| Return list of grippers of the Device. More... | |
| BodyPtr_t | obstacles () const |
| Get the static obstacles It corresponds to the geometries attached to the universe in pinocchio. More... | |
| size_type | nbObjects () const |
| Number of objects. More... | |
| CollisionObjectPtr_t | objectAt (const size_type &i) const |
| Access the i-th object. More... | |
| bool | collisionTest (const bool stopAtFirstCollision=true) |
| Test collision of current configuration. More... | |
| void | computeDistances () |
| Compute distances between pairs of objects stored in bodies. More... | |
| const DistanceResults_t & | distanceResults () 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. 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 Model & | model () const |
| Access to pinocchio model. More... | |
| Model & | model () |
| Access to pinocchio model. More... | |
| GeomModelConstPtr_t | geomModelPtr () const |
| Access to pinocchio geomModel. More... | |
| GeomModelPtr_t | geomModelPtr () |
| Access to pinocchio geomModel. More... | |
| const GeomModel & | geomModel () const |
| Access to pinocchio geomModel. More... | |
| GeomModel & | geomModel () |
| Access to pinocchio geomModel. More... | |
| DataConstPtr_t | dataPtr () const |
| Access to Pinocchio data/. More... | |
| DataPtr_t | dataPtr () |
| Access to Pinocchio data/. More... | |
| const Data & | data () const |
| Access to Pinocchio data/. More... | |
| Data & | data () |
| Access to Pinocchio data/. More... | |
| GeomDataConstPtr_t | geomDataPtr () const |
| Access to Pinocchio geomData/. More... | |
| GeomDataPtr_t | geomDataPtr () |
| Access to Pinocchio geomData/. More... | |
| const GeomData & | geomData () const |
| Access to Pinocchio geomData/. More... | |
| GeomData & | geomData () |
| Access to Pinocchio geomData/. More... | |
| const Configuration_t & | currentConfiguration () const |
| Get current configuration. More... | |
| virtual bool | currentConfiguration (ConfigurationIn_t configuration) |
| Set current configuration. More... | |
| const vector_t & | currentVelocity () const |
| Get current velocity. More... | |
| bool | currentVelocity (vectorIn_t velocity) |
| Set current velocity. More... | |
| const vector_t & | currentAcceleration () const |
| Get current acceleration. More... | |
| bool | currentAcceleration (vectorIn_t acceleration) |
| Set current acceleration. More... | |
| const value_type & | mass () const |
| Get mass of robot. More... | |
| const vector3_t & | positionCenterOfMass () const |
| Get position of center of mass. More... | |
| const ComJacobian_t & | jacobianCenterOfMass () 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 () |
| Compute frame forward kinematics. More... | |
| 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... | |
| DeviceData & | d () |
| 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_t > | CollisionPair_t |
| Collision pairs between bodies. More... | |
| typedef std::list< CollisionPair_t > | CollisionPairs_t |
Protected Attributes inherited from hpp::pinocchio::Device | |
| DeviceData | d_ |
| std::string | name_ |
| Grippers_t | grippers_ |
| LiegroupSpacePtr_t | configSpace_ |
| ExtraConfigSpace | extraConfigSpace_ |
| std::vector< JointLinearConstraint > | jointConstraints_ |
| DeviceWkPtr_t | weakPtr_ |
Protected Attributes inherited from hpp::pinocchio::AbstractDevice | |
| ModelPtr_t | model_ |
| GeomModelPtr_t | geomModel_ |
Humanoid robot.
|
virtual |
|
protected |
Constructor.
|
protected |
| JointPtr_t hpp::pinocchio::HumanoidRobot::chest | ( | ) | const |
Get Joint corresponding to the chest.
| void hpp::pinocchio::HumanoidRobot::chest | ( | const JointPtr_t & | joint | ) |
Set chest joint.
|
virtual |
Clone as a HumanoidRobot.
Reimplemented from hpp::pinocchio::Device.
|
static |
Creation of a new device.
| name | Name of the device (is passed to CkkpDeviceComponent) |
Set gaze parameters.
| JointPtr_t hpp::pinocchio::HumanoidRobot::gazeJoint | ( | ) | const |
Get gaze joint.
| void hpp::pinocchio::HumanoidRobot::gazeJoint | ( | const JointPtr_t & | joint | ) |
Set gaze joint.
|
protected |
Initialization.
|
protected |
| JointPtr_t hpp::pinocchio::HumanoidRobot::leftAnkle | ( | ) | const |
Get Joint corresponding to the left ankle.
| void hpp::pinocchio::HumanoidRobot::leftAnkle | ( | const JointPtr_t & | joint | ) |
Set letf ankle.
| JointPtr_t hpp::pinocchio::HumanoidRobot::leftWrist | ( | ) | const |
Get Joint corresponding to the left wrist.
| void hpp::pinocchio::HumanoidRobot::leftWrist | ( | const JointPtr_t & | joint | ) |
Set left wrist.
| JointPtr_t hpp::pinocchio::HumanoidRobot::rightAnkle | ( | ) | const |
Get Joint corresponding to the right ankle.
| void hpp::pinocchio::HumanoidRobot::rightAnkle | ( | const JointPtr_t & | joint | ) |
Set right ankle.
| JointPtr_t hpp::pinocchio::HumanoidRobot::rightWrist | ( | ) | const |
Get Joint corresponding to the right wrist.
| void hpp::pinocchio::HumanoidRobot::rightWrist | ( | const JointPtr_t & | joint | ) |
Set right wrist.
| JointPtr_t hpp::pinocchio::HumanoidRobot::waist | ( | ) | const |
Get Joint corresponding to the waist.
| void hpp::pinocchio::HumanoidRobot::waist | ( | const JointPtr_t & | joint | ) |
Set waist joint.