Robot with geometric and dynamic model. More...
#include <hpp/model/device.hh>
Public Types | |
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_t > | CollisionPair_t |
Collision pairs between bodies. | |
typedef std::list < CollisionPair_t > | CollisionPairs_t |
Public Member Functions | |
const std::string & | name () const |
Get name of device. | |
virtual std::ostream & | print (std::ostream &os) const |
Print object in a stream. | |
Construction, copy and destruction | |
virtual | ~Device () |
DevicePtr_t | clone () const |
Clone as a CkwsDevice. | |
Joints | |
void | rootJoint (JointPtr_t joint) |
Set the root of the kinematic chain. | |
void | rootJointPosition (const Transform3f &position) |
Set position of root joint in world frame. | |
JointPtr_t | rootJoint () const |
Get root joint. | |
void | registerJoint (const JointPtr_t &joint) |
Register joint in internal containers. | |
const JointVector_t & | getJointVector () const |
Get vector of joints. | |
JointPtr_t | getJointByName (const std::string &name) const |
Get joint by name. | |
JointPtr_t | getJointByBodyName (const std::string &name) const |
Get joint by body name. | |
size_type | configSize () const |
Size of configuration vectors Sum of joint dimensions and of extra configuration space dimension. | |
size_type | numberDof () const |
Size of velocity vectors Sum of joint number of degrees of freedom and of extra configuration space dimension. | |
Extra configuration space | |
ExtraConfigSpace & | extraConfigSpace () |
Get degrees of freedom to store internal values in configurations. | |
const ExtraConfigSpace & | extraConfigSpace () const |
Get degrees of freedom to store internal values in configurations. | |
void | setDimensionExtraConfigSpace (const size_type &dimension) |
Set dimension of extra configuration space. | |
Current state | |
const Configuration_t & | currentConfiguration () const |
Get current configuration. | |
virtual bool | currentConfiguration (ConfigurationIn_t configuration) |
Set current configuration. | |
Configuration_t | neutralConfiguration () const |
Get the neutral configuration. | |
const vector_t & | currentVelocity () const |
Get current velocity. | |
void | currentVelocity (vectorIn_t velocity) |
Set current velocity. | |
const vector_t & | currentAcceleration () const |
Get current acceleration. | |
void | currentAcceleration (vectorIn_t acceleration) |
Set current acceleration. | |
Mass and center of mass | |
const value_type & | mass () const |
Get mass of robot. | |
const vector3_t & | positionCenterOfMass () const |
Get position of center of mass. | |
const ComJacobian_t & | jacobianCenterOfMass () const |
Get Jacobian of center of mass with respect to configuration. | |
void | addGripper (const GripperPtr_t &gripper) |
Add a gripper to the Device. | |
Grippers_t & | grippers () |
Return list of grippers of the Device. | |
const Grippers_t & | grippers () const |
Return list of grippers of the Device. | |
Collision and distance computation | |
const ObjectVector_t & | obstacles (Request_t type) const |
Get list of obstacles. | |
virtual void | addCollisionPairs (const JointPtr_t &joint1, const JointPtr_t &joint2, Request_t type) |
Add collision pairs between objects attached to two joints. | |
virtual void | removeCollisionPairs (const JointPtr_t &joint1, const JointPtr_t &joint2, Request_t type) |
Remove collision pairs between objects attached to two joints. | |
const CollisionPairs_t & | collisionPairs (Request_t type) const |
Get list of collision or distance pairs. | |
ObjectIterator | objectIterator (Request_t type) |
Iterator over inner objects of the device. | |
bool | collisionTest () const |
Test collision of current configuration. | |
void | computeDistances () |
Compute distances between pairs of objects stored in bodies. | |
const DistanceResults_t & | distanceResults () const |
Get result of distance computations. | |
Forward kinematics | |
void | controlComputation (const Computation_t &flag) |
Select computation Optimize computation time by selecting only necessary values in method computeForwardKinematics. | |
Computation_t | computationFlag () const |
Get computation flag. | |
virtual void | computeForwardKinematics () |
Compute forward kinematics. | |
Static Public Member Functions | |
static DevicePtr_t | create (std::string name) |
Creation of a new device. | |
static DevicePtr_t | createCopy (const DevicePtr_t &device) |
Copy of a device. | |
Protected Member Functions | |
Device (const std::string &name) | |
Constructor. | |
void | init (const DeviceWkPtr_t &weakPtr) |
Initialization. | |
void | updateDistances () |
Recompute number of distance pairs. | |
Friends | |
class | Body |
class | Joint |
Robot with geometric and dynamic model.
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::model::Device::CollisionPair_t |
Collision pairs between bodies.
typedef std::list<CollisionPair_t> hpp::model::Device::CollisionPairs_t |
virtual hpp::model::Device::~Device | ( | ) | [virtual] |
hpp::model::Device::Device | ( | const std::string & | name | ) | [protected] |
Constructor.
virtual void hpp::model::Device::addCollisionPairs | ( | const JointPtr_t & | joint1, |
const JointPtr_t & | joint2, | ||
Request_t | type | ||
) | [virtual] |
Add collision pairs between objects attached to two joints.
joint1 | first joint |
joint2 | second joint |
type | collision or distance. |
Define collision pair between each object of joint 1 body and each object of joint2 body.
void hpp::model::Device::addGripper | ( | const GripperPtr_t & | gripper | ) | [inline] |
Add a gripper to the Device.
DevicePtr_t hpp::model::Device::clone | ( | ) | const |
Clone as a CkwsDevice.
Reimplemented in hpp::model::HumanoidRobot.
const CollisionPairs_t& hpp::model::Device::collisionPairs | ( | Request_t | type | ) | const |
Get list of collision or distance pairs.
type | collision or distance. |
bool hpp::model::Device::collisionTest | ( | ) | const |
Test collision of current configuration.
Computation_t hpp::model::Device::computationFlag | ( | ) | const [inline] |
Get computation flag.
void hpp::model::Device::computeDistances | ( | ) |
Compute distances between pairs of objects stored in bodies.
virtual void hpp::model::Device::computeForwardKinematics | ( | ) | [virtual] |
Compute forward kinematics.
size_type hpp::model::Device::configSize | ( | ) | const |
Size of configuration vectors Sum of joint dimensions and of extra configuration space dimension.
void hpp::model::Device::controlComputation | ( | const Computation_t & | flag | ) | [inline] |
Select computation Optimize computation time by selecting only necessary values in method computeForwardKinematics.
static DevicePtr_t hpp::model::Device::create | ( | std::string | name | ) | [static] |
Creation of a new device.
name | Name of the device (is passed to CkkpDeviceComponent) |
Referenced by hpp::model::ObjectFactory::createRobot().
static DevicePtr_t hpp::model::Device::createCopy | ( | const DevicePtr_t & | device | ) | [static] |
const vector_t& hpp::model::Device::currentAcceleration | ( | ) | const [inline] |
Get current acceleration.
void hpp::model::Device::currentAcceleration | ( | vectorIn_t | acceleration | ) | [inline] |
Set current acceleration.
const Configuration_t& hpp::model::Device::currentConfiguration | ( | ) | const [inline] |
Get current configuration.
virtual bool hpp::model::Device::currentConfiguration | ( | ConfigurationIn_t | configuration | ) | [inline, virtual] |
Set current configuration.
const vector_t& hpp::model::Device::currentVelocity | ( | ) | const [inline] |
Get current velocity.
void hpp::model::Device::currentVelocity | ( | vectorIn_t | velocity | ) | [inline] |
Set current velocity.
const DistanceResults_t& hpp::model::Device::distanceResults | ( | ) | const [inline] |
Get result of distance computations.
ExtraConfigSpace& hpp::model::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.
const ExtraConfigSpace& hpp::model::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.
JointPtr_t hpp::model::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::model::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 |
const JointVector_t& hpp::model::Device::getJointVector | ( | ) | const |
Get vector of joints.
Grippers_t& hpp::model::Device::grippers | ( | ) | [inline] |
Return list of grippers of the Device.
const Grippers_t& hpp::model::Device::grippers | ( | ) | const [inline] |
Return list of grippers of the Device.
void hpp::model::Device::init | ( | const DeviceWkPtr_t & | weakPtr | ) | [protected] |
Initialization.
const ComJacobian_t& hpp::model::Device::jacobianCenterOfMass | ( | ) | const [inline] |
Get Jacobian of center of mass with respect to configuration.
const value_type& hpp::model::Device::mass | ( | ) | const [inline] |
Get mass of robot.
const std::string& hpp::model::Device::name | ( | ) | const [inline] |
Get name of device.
Get the neutral configuration.
size_type hpp::model::Device::numberDof | ( | ) | const |
Size of velocity vectors Sum of joint number of degrees of freedom and of extra configuration space dimension.
Iterator over inner objects of the device.
type | Collision or distance |
const ObjectVector_t& hpp::model::Device::obstacles | ( | Request_t | type | ) | const |
Get list of obstacles.
type | collision or distance. |
const vector3_t& hpp::model::Device::positionCenterOfMass | ( | ) | const [inline] |
Get position of center of mass.
virtual std::ostream& hpp::model::Device::print | ( | std::ostream & | os | ) | const [virtual] |
Print object in a stream.
void hpp::model::Device::registerJoint | ( | const JointPtr_t & | joint | ) |
Register joint in internal containers.
virtual void hpp::model::Device::removeCollisionPairs | ( | const JointPtr_t & | joint1, |
const JointPtr_t & | joint2, | ||
Request_t | type | ||
) | [virtual] |
Remove collision pairs between objects attached to two joints.
joint1 | first joint |
joint2 | second joint |
type | collision or distance. |
remove collision between each object of joint 1 body and each object of joint2 body
void hpp::model::Device::rootJoint | ( | JointPtr_t | joint | ) |
Set the root of the kinematic chain.
JointPtr_t hpp::model::Device::rootJoint | ( | ) | const |
Get root joint.
void hpp::model::Device::rootJointPosition | ( | const Transform3f & | position | ) |
Set position of root joint in world frame.
void hpp::model::Device::setDimensionExtraConfigSpace | ( | const size_type & | dimension | ) | [inline] |
Set dimension of extra configuration space.
void hpp::model::Device::updateDistances | ( | ) | [protected] |
Recompute number of distance pairs.
friend class Body [friend] |
friend class Joint [friend] |