Definition of a robot gripper. More...
#include <hpp/model/gripper.hh>
Public Member Functions | |
const JointPtr_t & | joint () const |
Get joint that grip. | |
void | joint (const JointPtr_t &joint) |
Set joint that grip. | |
const Transform3f & | objectPositionInJoint () const |
Get handle position in the the Grippering joint. | |
const std::string & | name () const |
get name | |
void | name (const std::string &n) |
Set name. | |
void | addDisabledCollision (const JointPtr_t &joint) |
add joint to disabled collision vector | |
void | removeDisabledCollision (JointPtr_t &joint) |
remove joint of disabled collision vector | |
const JointVector_t & | getDisabledCollisions () const |
void | removeAllDisabledCollisions () |
GripperPtr_t | clone () const |
virtual std::ostream & | print (std::ostream &os) const |
Static Public Member Functions | |
static GripperPtr_t | create (const std::string &name, const JointPtr_t &joint, const Transform3f &objectPositionInJoint, const JointVector_t disabledCollisions) |
Return a shared pointer to new instance. | |
Protected Member Functions | |
Gripper (const std::string &name, const JointPtr_t &joint, const Transform3f &objectPositionInJoint, const JointVector_t disabledCollisions) | |
Constructor. | |
void | init (GripperWkPtr_t weakPtr) |
Definition of a robot gripper.
This class represent a robot gripper as a frame attached to the joint of the robot that holds the gripper.
To graps a box-shaped object with small lengths along x and y, the gripper frame should coincide with the object frame.
hpp::model::Gripper::Gripper | ( | const std::string & | name, |
const JointPtr_t & | joint, | ||
const Transform3f & | objectPositionInJoint, | ||
const JointVector_t | disabledCollisions | ||
) | [inline, protected] |
Constructor.
joint | joint of the robot that holds the handle, |
objectPositionInJoint | handle position in the the grasping joint. |
disabledCollisions | vector of joints that will be in collision with the object, so collisions detection will be disabled for those joints and the handles. |
void hpp::model::Gripper::addDisabledCollision | ( | const JointPtr_t & | joint | ) | [inline] |
add joint to disabled collision vector
GripperPtr_t hpp::model::Gripper::clone | ( | ) | const |
static GripperPtr_t hpp::model::Gripper::create | ( | const std::string & | name, |
const JointPtr_t & | joint, | ||
const Transform3f & | objectPositionInJoint, | ||
const JointVector_t | disabledCollisions | ||
) | [inline, static] |
Return a shared pointer to new instance.
joint | joint of the robot that will hold handles, |
objectPositionInJoint | object position in the the grasping joint. |
disabledCollisions | vector of joints that will be in collision with the object, so collisions detection will be disabled for those joints and the handles. |
References init().
const JointVector_t& hpp::model::Gripper::getDisabledCollisions | ( | ) | const [inline] |
void hpp::model::Gripper::init | ( | GripperWkPtr_t | weakPtr | ) | [inline, protected] |
Referenced by create().
const JointPtr_t& hpp::model::Gripper::joint | ( | ) | const [inline] |
Get joint that grip.
void hpp::model::Gripper::joint | ( | const JointPtr_t & | joint | ) | [inline] |
Set joint that grip.
const std::string& hpp::model::Gripper::name | ( | ) | const [inline] |
get name
void hpp::model::Gripper::name | ( | const std::string & | n | ) | [inline] |
Set name.
const Transform3f& hpp::model::Gripper::objectPositionInJoint | ( | ) | const [inline] |
Get handle position in the the Grippering joint.
virtual std::ostream& hpp::model::Gripper::print | ( | std::ostream & | os | ) | const [virtual] |
void hpp::model::Gripper::removeAllDisabledCollisions | ( | ) | [inline] |
void hpp::model::Gripper::removeDisabledCollision | ( | JointPtr_t & | joint | ) | [inline] |
remove joint of disabled collision vector