hpp-pinocchio
4.9.1
Wrapping of the kinematic/dynamic chain Pinocchio for HPP.
|
Robot with geometric and dynamic pinocchio. More...
#include <hpp/pinocchio/device.hh>
Classes | |
struct | JointLinearConstraint |
Public Types | |
typedef std::pair< JointPtr_t, JointPtr_t > | CollisionPair_t |
Collision pairs between bodies. More... | |
typedef std::list< CollisionPair_t > | CollisionPairs_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_t & | configSpace () const |
Returns a LiegroupSpace representing the configuration space. More... | |
const 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 |
Extra configuration space | |
ExtraConfigSpace & | extraConfigSpace () |
const ExtraConfigSpace & | extraConfigSpace () 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_t & | grippers () |
Return list of grippers of the Device. More... | |
const Grippers_t & | grippers () 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_t & | distanceResults () 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 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) |
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 () |
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... | |
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) | |
Protected Attributes | |
DeviceData | d_ |
std::string | name_ |
Grippers_t | grippers_ |
LiegroupSpacePtr_t | configSpace_ |
LiegroupSpacePtr_t | configSpaceRnxSOn_ |
ExtraConfigSpace | extraConfigSpace_ |
std::vector< JointLinearConstraint > | jointConstraints_ |
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) |
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.
typedef std::pair<JointPtr_t, JointPtr_t> hpp::pinocchio::Device::CollisionPair_t |
Collision pairs between bodies.
typedef std::list<CollisionPair_t> hpp::pinocchio::Device::CollisionPairs_t |
|
virtual |
|
protected |
Constructor.
|
protected |
Copy Constructor.
|
inline |
Add a gripper to the Device.
void hpp::pinocchio::Device::addJointConstraint | ( | JointLinearConstraint | constraint | ) |
Add a joint constraint.
|
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.
Reimplemented in hpp::pinocchio::HumanoidRobot.
|
inline |
Clone as a CkwsDevice Both pinocchio objects model and data are copied. TODO: this method is not implemented yet (assert if called)
bool hpp::pinocchio::Device::collisionTest | ( | const bool | stopAtFirstCollision = true | ) |
Test collision of current configuration
stopAtFirstCollision | act as named |
fcl::AABB hpp::pinocchio::Device::computeAABB | ( | ) | const |
Compute an aligned bounding around the robot. The bounding box is computed as follows:
void hpp::pinocchio::Device::computeDistances | ( | ) |
Compute distances between pairs of objects stored in bodies
size_type hpp::pinocchio::Device::configSize | ( | ) | const |
Size of configuration vectors Sum of joint dimensions and of extra configuration space dimension
|
inline |
Returns a LiegroupSpace representing the configuration space.
|
virtual |
Select computation Optimize computation time by selecting only necessary values in method computeForwardKinematics.
Reimplemented from hpp::pinocchio::AbstractDevice.
|
static |
Creation of a new device.
name | Name of the device |
|
static |
Copy of a device.
device | Device to be copied. The pinocchio model is not copied (only copy the pointer). A new Pinocchio "data" is created. |
|
static |
void hpp::pinocchio::Device::createData | ( | ) |
Create Pinocchio data from model.
void hpp::pinocchio::Device::createGeomData | ( | ) |
Create Pinocchio geomData from model.
|
inlineprotectedvirtual |
Implements hpp::pinocchio::AbstractDevice.
|
inlineprotectedvirtual |
Implements hpp::pinocchio::AbstractDevice.
const DistanceResults_t& hpp::pinocchio::Device::distanceResults | ( | ) | const |
Get result of distance computations.
|
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.
|
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.
Frame hpp::pinocchio::Device::getFrameByName | ( | const std::string & | name | ) | const |
Get frame by name
name | name of the frame. |
runtime_error | if device has no frame with this name |
JointPtr_t hpp::pinocchio::Device::getJointAtConfigRank | ( | const size_type & | r | ) | const |
Get the joint at configuration rank r
JointPtr_t hpp::pinocchio::Device::getJointAtVelocityRank | ( | const size_type & | r | ) | const |
Get the joint at velocity rank r
JointPtr_t hpp::pinocchio::Device::getJointByBodyName | ( | const std::string & | name | ) | const |
Get joint by body name
runtime_error | if device has no body with this name |
JointPtr_t hpp::pinocchio::Device::getJointByName | ( | const std::string & | name | ) | const |
Get joint by name
name | name of the joint. |
runtime_error | if device has no joint with this name |
|
inline |
Return list of grippers of the Device.
|
inline |
Return list of grippers of the Device.
|
protected |
Initialization.
|
protected |
Initialization of of a clone device.
|
inlineprotected |
JointPtr_t hpp::pinocchio::Device::jointAt | ( | const size_type & | i | ) | const |
Access i-th joint.
|
inline |
|
inline |
Get name of device.
size_type hpp::pinocchio::Device::nbJoints | ( | ) | const |
Get number of joints.
size_type hpp::pinocchio::Device::nbObjects | ( | ) | const |
Number of objects.
Configuration_t hpp::pinocchio::Device::neutralConfiguration | ( | ) | const |
Get the neutral configuration.
void hpp::pinocchio::Device::numberDeviceData | ( | const size_type & | s | ) |
Set the maximum number of concurrent use of the Device.
size_type hpp::pinocchio::Device::numberDeviceData | ( | ) | const |
Get the number of DeviceData.
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
CollisionObjectPtr_t hpp::pinocchio::Device::objectAt | ( | const size_type & | i | ) | const |
Access the i-th object.
BodyPtr_t hpp::pinocchio::Device::obstacles | ( | ) | const |
Get the static obstacles It corresponds to the geometries attached to the universe in pinocchio.
|
virtual |
Print object in a stream.
|
inline |
Frame hpp::pinocchio::Device::rootFrame | ( | ) | const |
Get root frame.
JointPtr_t hpp::pinocchio::Device::rootJoint | ( | ) | const |
Get root joint.
|
inline |
Set Pinocchio data corresponding to model.
|
inlinevirtual |
Set dimension of extra configuration space.
|
inline |
Set Pinocchio geomData corresponding to model.
|
inline |
Set pinocchio geom.
|
inline |
Set pinocchio model.
|
friend |
|
friend |
|
friend |
|
friend |
|
friend |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |