openrave.org

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
OpenRAVE::RobotBase::Manipulator Class Reference

Defines a chain of joints for an arm and set of joints for a gripper. Simplifies operating with them. More...

#include <robot.h>

Inheritance diagram for OpenRAVE::RobotBase::Manipulator:
Inheritance graph
[legend]
Collaboration diagram for OpenRAVE::RobotBase::Manipulator:
Collaboration graph
[legend]

Public Member Functions

virtual ~Manipulator ()
 
const ManipulatorInfoGetInfo () const
 return a serializable info holding everything to initialize a manipulator
 
virtual Transform GetTransform () const
 Return the transformation of the manipulator frame.
 
virtual std::pair< Vector, VectorGetVelocity () const
 return the linear/angular velocity of the manipulator coordinate system
 
virtual Transform GetEndEffectorTransform () const
 
virtual const std::string & GetName () const
 
virtual RobotBasePtr GetRobot () const
 
virtual bool SetIkSolver (IkSolverBasePtr iksolver)
 Sets the ik solver and initializes it with the current manipulator.
 
virtual IkSolverBasePtr GetIkSolver () const
 Returns the currently set ik solver.
 
virtual LinkPtr GetBase () const
 the base used for the iksolver
 
virtual LinkPtr GetEndEffector () const
 the end effector link (used to define workspace distance)
 
virtual Transform GetLocalToolTransform () const
 Return transform with respect to end effector defining the grasp coordinate system.
 
virtual void SetLocalToolTransform (const Transform &t)
 Sets the local tool transform with respect to the end effector link.
 
virtual void SetName (const std::string &name)
 new name for manipulator
 
virtual Transform GetGraspTransform () const RAVE_DEPRECATED
 
virtual const std::vector< int > & GetGripperIndices () const
 Gripper indices of the joints that the manipulator controls.
 
virtual const std::vector< int > & GetArmIndices () const
 Return the indices of the DOFs of the manipulator, which are used for inverse kinematics.
 
virtual const std::vector
< dReal > & 
GetClosingDirection () const
 return the normal direction to move joints to 'close' the hand
 
virtual void SetLocalToolDirection (const Vector &direction)
 Sets the local tool direction with respect to the end effector link.
 
virtual Vector GetLocalToolDirection () const
 direction of palm/head/manipulator used for approaching. defined inside the manipulator/grasp coordinate system
 
virtual Vector GetDirection () const
 
virtual bool FindIKSolution (const IkParameterization &param, std::vector< dReal > &solution, int filteroptions) const
 Find a close solution to the current robot's joint values.
 
virtual bool FindIKSolution (const IkParameterization &param, const std::vector< dReal > &vFreeParameters, std::vector< dReal > &solution, int filteroptions) const
 
virtual bool FindIKSolution (const IkParameterization &param, int filteroptions, IkReturnPtr ikreturn) const
 
virtual bool FindIKSolution (const IkParameterization &param, const std::vector< dReal > &vFreeParameters, int filteroptions, IkReturnPtr ikreturn) const
 
virtual bool FindIKSolutions (const IkParameterization &param, std::vector< std::vector< dReal > > &solutions, int filteroptions) const
 Find all the IK solutions for the given end effector transform.
 
virtual bool FindIKSolutions (const IkParameterization &param, const std::vector< dReal > &vFreeParameters, std::vector< std::vector< dReal > > &solutions, int filteroptions) const
 
virtual bool FindIKSolutions (const IkParameterization &param, int filteroptions, std::vector< IkReturnPtr > &vikreturns) const
 
virtual bool FindIKSolutions (const IkParameterization &param, const std::vector< dReal > &vFreeParameters, int filteroptions, std::vector< IkReturnPtr > &vikreturns) const
 
virtual IkParameterization GetIkParameterization (IkParameterizationType iktype, bool inworld=true) const
 returns the parameterization of a given IK type for the current manipulator position.
 
virtual IkParameterization GetIkParameterization (const IkParameterization &ikparam, bool inworld=true) const
 returns a full parameterization of a given IK type for the current manipulator position using an existing IkParameterization as the seed.
 
virtual void GetChildJoints (std::vector< JointPtr > &vjoints) const
 Get all child joints of the manipulator starting at the pEndEffector link.
 
virtual void GetChildDOFIndices (std::vector< int > &vdofndices) const
 Get all child DOF indices of the manipulator starting at the pEndEffector link.
 
virtual bool IsChildLink (LinkConstPtr plink) const
 returns true if a link is part of the child links of the manipulator.
 
virtual void GetChildLinks (std::vector< LinkPtr > &vlinks) const
 Get all child links of the manipulator starting at pEndEffector link.
 
virtual void GetIndependentLinks (std::vector< LinkPtr > &vlinks) const
 Get all links that are independent of the arm and gripper joints.
 
virtual bool CheckEndEffectorCollision (const Transform &tEE, CollisionReportPtr report=CollisionReportPtr()) const
 Checks collision with only the gripper given its end-effector transform and the rest of the environment. Ignores disabled links.
 
virtual bool CheckEndEffectorSelfCollision (const Transform &tEE, CollisionReportPtr report=CollisionReportPtr()) const
 Checks self-collision with only the gripper given its end-effector transform with the rest of the robot. Ignores disabled links.
 
virtual bool CheckEndEffectorCollision (const IkParameterization &ikparam, CollisionReportPtr report=CollisionReportPtr()) const
 Checks environment collisions with only the gripper given an IK parameterization of the gripper.
 
virtual bool CheckEndEffectorSelfCollision (const IkParameterization &ikparam, CollisionReportPtr report=CollisionReportPtr()) const
 Checks self-collisions with only the gripper given an IK parameterization of the gripper.
 
virtual bool CheckIndependentCollision (CollisionReportPtr report=CollisionReportPtr()) const
 Checks collision with the environment with all the independent links of the robot. Ignores disabled links.
 
virtual bool IsGrabbing (KinBodyConstPtr body) const
 Checks collision with a target body and all the independent links of the robot. Ignores disabled links.
 
virtual void CalculateJacobian (std::vector< dReal > &jacobian) const
 computes the jacobian of the manipulator arm indices of the current manipulator frame world position.
 
virtual void CalculateJacobian (boost::multi_array< dReal, 2 > &jacobian) const
 calls std::vector version of CalculateJacobian internally, a little inefficient since it copies memory
 
virtual void CalculateRotationJacobian (std::vector< dReal > &jacobian) const
 computes the quaternion jacobian of the manipulator arm indices from the current manipulator frame rotation.
 
virtual void CalculateRotationJacobian (boost::multi_array< dReal, 2 > &jacobian) const
 calls std::vector version of CalculateRotationJacobian internally, a little inefficient since it copies memory
 
virtual void CalculateAngularVelocityJacobian (std::vector< dReal > &jacobian) const
 computes the angule axis jacobian of the manipulator arm indices.
 
virtual void CalculateAngularVelocityJacobian (boost::multi_array< dReal, 2 > &jacobian) const
 calls std::vector version of CalculateAngularVelocityJacobian internally, a little inefficient since it copies memory
 
virtual ConfigurationSpecification GetArmConfigurationSpecification (const std::string &interpolation="") const
 return a copy of the configuration specification of the arm indices
 
virtual void serialize (std::ostream &o, int options) const
 
virtual const std::string & GetStructureHash () const
 Return hash of just the manipulator definition.
 
virtual const std::string & GetKinematicsStructureHash () const
 Return hash of all kinematics information that involves solving the inverse kinematics equations.
 

Protected Member Functions

virtual void _ComputeInternalInformation ()
 compute internal information from user-set info
 

Protected Attributes

ManipulatorInfo _info
 user-set information
 

Detailed Description

Defines a chain of joints for an arm and set of joints for a gripper. Simplifies operating with them.

Definition at line 56 of file robot.h.

Constructor & Destructor Documentation

virtual OpenRAVE::RobotBase::Manipulator::~Manipulator ( )
virtual

Member Function Documentation

virtual void OpenRAVE::RobotBase::Manipulator::_ComputeInternalInformation ( )
protectedvirtual

compute internal information from user-set info

virtual void OpenRAVE::RobotBase::Manipulator::CalculateAngularVelocityJacobian ( std::vector< dReal > &  jacobian) const
virtual

computes the angule axis jacobian of the manipulator arm indices.

virtual void OpenRAVE::RobotBase::Manipulator::CalculateAngularVelocityJacobian ( boost::multi_array< dReal, 2 > &  jacobian) const
virtual

calls std::vector version of CalculateAngularVelocityJacobian internally, a little inefficient since it copies memory

virtual void OpenRAVE::RobotBase::Manipulator::CalculateJacobian ( std::vector< dReal > &  jacobian) const
virtual

computes the jacobian of the manipulator arm indices of the current manipulator frame world position.

The manipulator frame is computed from Manipulator::GetTransform()

virtual void OpenRAVE::RobotBase::Manipulator::CalculateJacobian ( boost::multi_array< dReal, 2 > &  jacobian) const
virtual

calls std::vector version of CalculateJacobian internally, a little inefficient since it copies memory

virtual void OpenRAVE::RobotBase::Manipulator::CalculateRotationJacobian ( std::vector< dReal > &  jacobian) const
virtual

computes the quaternion jacobian of the manipulator arm indices from the current manipulator frame rotation.

virtual void OpenRAVE::RobotBase::Manipulator::CalculateRotationJacobian ( boost::multi_array< dReal, 2 > &  jacobian) const
virtual

calls std::vector version of CalculateRotationJacobian internally, a little inefficient since it copies memory

virtual bool OpenRAVE::RobotBase::Manipulator::CheckEndEffectorCollision ( const Transform tEE,
CollisionReportPtr  report = CollisionReportPtr() 
) const
virtual

Checks collision with only the gripper given its end-effector transform and the rest of the environment. Ignores disabled links.

Parameters
tEEthe end effector transform
[out]report[optional] collision report
Returns
true if a collision occurred
virtual bool OpenRAVE::RobotBase::Manipulator::CheckEndEffectorCollision ( const IkParameterization ikparam,
CollisionReportPtr  report = CollisionReportPtr() 
) const
virtual

Checks environment collisions with only the gripper given an IK parameterization of the gripper.

        Some IkParameterizations can fully determine the gripper 6DOF location. If the type is Transform6D or the manipulator arm DOF <= IkParameterization DOF, then this would be possible. In the latter case, an ik solver is required to support the ik parameterization.
        \param ikparam the ik parameterization determining the gripper transform
        \param[out] report [optional] collision report
        \return true if a collision occurred

/

Exceptions
openrave_exceptionif the gripper location cannot be fully determined from the passed in ik parameterization.
virtual bool OpenRAVE::RobotBase::Manipulator::CheckEndEffectorSelfCollision ( const Transform tEE,
CollisionReportPtr  report = CollisionReportPtr() 
) const
virtual

Checks self-collision with only the gripper given its end-effector transform with the rest of the robot. Ignores disabled links.

Parameters
tEEthe end effector transform
[out]report[optional] collision report
Returns
true if a collision occurred
virtual bool OpenRAVE::RobotBase::Manipulator::CheckEndEffectorSelfCollision ( const IkParameterization ikparam,
CollisionReportPtr  report = CollisionReportPtr() 
) const
virtual

Checks self-collisions with only the gripper given an IK parameterization of the gripper.

        Some IkParameterizations can fully determine the gripper 6DOF location. If the type is Transform6D or the manipulator arm DOF <= IkParameterization DOF, then this would be possible. In the latter case, an ik solver is required to support the ik parameterization.
        \param ikparam the ik parameterization determining the gripper transform
        \param[out] report [optional] collision report
        \return true if a collision occurred

/

Exceptions
openrave_exceptionif the gripper location cannot be fully determined from the passed in ik parameterization.
virtual bool OpenRAVE::RobotBase::Manipulator::CheckIndependentCollision ( CollisionReportPtr  report = CollisionReportPtr()) const
virtual

Checks collision with the environment with all the independent links of the robot. Ignores disabled links.

Parameters
[out]report[optional] collision report
Returns
true if a collision occurred
virtual bool OpenRAVE::RobotBase::Manipulator::FindIKSolution ( const IkParameterization param,
std::vector< dReal > &  solution,
int  filteroptions 
) const
virtual

Find a close solution to the current robot's joint values.

The function is a wrapper around the IkSolver interface. Note that the solution returned is not guaranteed to be the closest solution. In order to compute that, will have to compute all the ik solutions using FindIKSolutions.

Parameters
paramThe transformation of the end-effector in the global coord system
solutionWill be of size GetArmIndices().size() and contain the best solution
[in]filteroptionsA bitmask of IkFilterOptions values controlling what is checked for each ik solution.
virtual bool OpenRAVE::RobotBase::Manipulator::FindIKSolution ( const IkParameterization param,
const std::vector< dReal > &  vFreeParameters,
std::vector< dReal > &  solution,
int  filteroptions 
) const
virtual
virtual bool OpenRAVE::RobotBase::Manipulator::FindIKSolution ( const IkParameterization param,
int  filteroptions,
IkReturnPtr  ikreturn 
) const
virtual
virtual bool OpenRAVE::RobotBase::Manipulator::FindIKSolution ( const IkParameterization param,
const std::vector< dReal > &  vFreeParameters,
int  filteroptions,
IkReturnPtr  ikreturn 
) const
virtual
virtual bool OpenRAVE::RobotBase::Manipulator::FindIKSolutions ( const IkParameterization param,
std::vector< std::vector< dReal > > &  solutions,
int  filteroptions 
) const
virtual

Find all the IK solutions for the given end effector transform.

Parameters
paramThe transformation of the end-effector in the global coord system
solutionsAn array of all solutions, each element in solutions is of size GetArmIndices().size()
[in]filteroptionsA bitmask of IkFilterOptions values controlling what is checked for each ik solution.
virtual bool OpenRAVE::RobotBase::Manipulator::FindIKSolutions ( const IkParameterization param,
const std::vector< dReal > &  vFreeParameters,
std::vector< std::vector< dReal > > &  solutions,
int  filteroptions 
) const
virtual
virtual bool OpenRAVE::RobotBase::Manipulator::FindIKSolutions ( const IkParameterization param,
int  filteroptions,
std::vector< IkReturnPtr > &  vikreturns 
) const
virtual
virtual bool OpenRAVE::RobotBase::Manipulator::FindIKSolutions ( const IkParameterization param,
const std::vector< dReal > &  vFreeParameters,
int  filteroptions,
std::vector< IkReturnPtr > &  vikreturns 
) const
virtual
virtual ConfigurationSpecification OpenRAVE::RobotBase::Manipulator::GetArmConfigurationSpecification ( const std::string &  interpolation = "") const
virtual

return a copy of the configuration specification of the arm indices

Note that the return type is by-value, so should not be used in iteration

virtual const std::vector<int>& OpenRAVE::RobotBase::Manipulator::GetArmIndices ( ) const
inlinevirtual

Return the indices of the DOFs of the manipulator, which are used for inverse kinematics.

Usually the DOF indices of the chain from pBase to pEndEffector

Definition at line 140 of file robot.h.

virtual LinkPtr OpenRAVE::RobotBase::Manipulator::GetBase ( ) const
inlinevirtual

the base used for the iksolver

Definition at line 103 of file robot.h.

virtual void OpenRAVE::RobotBase::Manipulator::GetChildDOFIndices ( std::vector< int > &  vdofndices) const
virtual

Get all child DOF indices of the manipulator starting at the pEndEffector link.

virtual void OpenRAVE::RobotBase::Manipulator::GetChildJoints ( std::vector< JointPtr > &  vjoints) const
virtual

Get all child joints of the manipulator starting at the pEndEffector link.

virtual void OpenRAVE::RobotBase::Manipulator::GetChildLinks ( std::vector< LinkPtr > &  vlinks) const
virtual

Get all child links of the manipulator starting at pEndEffector link.

The child links do not include the arm links.

virtual const std::vector<dReal>& OpenRAVE::RobotBase::Manipulator::GetClosingDirection ( ) const
inlinevirtual

return the normal direction to move joints to 'close' the hand

Definition at line 145 of file robot.h.

virtual Vector OpenRAVE::RobotBase::Manipulator::GetDirection ( ) const
inlinevirtual
Deprecated:
(11/10/15) use GetLocalToolDirection

Definition at line 160 of file robot.h.

virtual LinkPtr OpenRAVE::RobotBase::Manipulator::GetEndEffector ( ) const
inlinevirtual

the end effector link (used to define workspace distance)

Definition at line 108 of file robot.h.

virtual Transform OpenRAVE::RobotBase::Manipulator::GetEndEffectorTransform ( ) const
inlinevirtual

Definition at line 81 of file robot.h.

virtual Transform OpenRAVE::RobotBase::Manipulator::GetGraspTransform ( ) const
inlinevirtual
Deprecated:
(11/10/15) use GetLocalToolTransform

Definition at line 128 of file robot.h.

virtual const std::vector<int>& OpenRAVE::RobotBase::Manipulator::GetGripperIndices ( ) const
inlinevirtual

Gripper indices of the joints that the manipulator controls.

Definition at line 133 of file robot.h.

virtual IkParameterization OpenRAVE::RobotBase::Manipulator::GetIkParameterization ( IkParameterizationType  iktype,
bool  inworld = true 
) const
virtual

returns the parameterization of a given IK type for the current manipulator position.

Ideally pluging the returned ik parameterization into FindIkSolution should return the a manipulator configuration such that a new call to GetIkParameterization returns the same values. In other words:

ikparam = manip->GetIkParameterization(iktype);
... move robot
std::vector<dReal> sol;
if( FindIKSolution(ikparam,sol, filteroptions) ) {
manip->GetRobot()->SetActiveDOFs(manip->GetArmIndices());
manip->GetRobot()->SetActiveDOFValues(sol);
BOOST_ASSERT( dist(manip->GetIkParameterization(iktype), ikparam) <= epsilon );
}
Parameters
iktypethe type of parameterization to request
inworldif true will return the parameterization in the world coordinate system, otherwise in the base link (GetBase()) coordinate system
virtual IkParameterization OpenRAVE::RobotBase::Manipulator::GetIkParameterization ( const IkParameterization ikparam,
bool  inworld = true 
) const
virtual

returns a full parameterization of a given IK type for the current manipulator position using an existing IkParameterization as the seed.

Custom data is copied to the new parameterization. Furthermore, some IK types like Lookat3D and TranslationLocalGlobal6D set constraints in the global coordinate system of the manipulator. Because these values are not stored in manipulator itself, they have to be passed in through an existing IkParameterization. Ideally pluging the returned ik parameterization into FindIkSolution should return the a manipulator configuration such that a new call to GetIkParameterization returns the same values.

Parameters
ikparamThe parameterization to use as seed.
inworldif true will return the parameterization in the world coordinate system, otherwise in the base link (GetBase()) coordinate system
virtual IkSolverBasePtr OpenRAVE::RobotBase::Manipulator::GetIkSolver ( ) const
virtual

Returns the currently set ik solver.

virtual void OpenRAVE::RobotBase::Manipulator::GetIndependentLinks ( std::vector< LinkPtr > &  vlinks) const
virtual

Get all links that are independent of the arm and gripper joints.

In other words, returns all links not on the path from the base to the end effector and not children of the end effector. The base and all links rigidly attached to it are also returned.

const ManipulatorInfo& OpenRAVE::RobotBase::Manipulator::GetInfo ( ) const
inline

return a serializable info holding everything to initialize a manipulator

Definition at line 68 of file robot.h.

virtual const std::string& OpenRAVE::RobotBase::Manipulator::GetKinematicsStructureHash ( ) const
virtual

Return hash of all kinematics information that involves solving the inverse kinematics equations.

This includes joint axes, joint positions, and final grasp transform. Hash is used to cache the solvers.

virtual Vector OpenRAVE::RobotBase::Manipulator::GetLocalToolDirection ( ) const
inlinevirtual

direction of palm/head/manipulator used for approaching. defined inside the manipulator/grasp coordinate system

Definition at line 155 of file robot.h.

virtual Transform OpenRAVE::RobotBase::Manipulator::GetLocalToolTransform ( ) const
inlinevirtual

Return transform with respect to end effector defining the grasp coordinate system.

Definition at line 113 of file robot.h.

virtual const std::string& OpenRAVE::RobotBase::Manipulator::GetName ( ) const
inlinevirtual

Definition at line 85 of file robot.h.

virtual RobotBasePtr OpenRAVE::RobotBase::Manipulator::GetRobot ( ) const
inlinevirtual

Definition at line 88 of file robot.h.

virtual const std::string& OpenRAVE::RobotBase::Manipulator::GetStructureHash ( ) const
virtual

Return hash of just the manipulator definition.

virtual Transform OpenRAVE::RobotBase::Manipulator::GetTransform ( ) const
virtual

Return the transformation of the manipulator frame.

The manipulator frame is defined by the the end effector link position * GetLocalToolTransform() All inverse kinematics and jacobian queries are specifying this frame.

virtual std::pair<Vector,Vector> OpenRAVE::RobotBase::Manipulator::GetVelocity ( ) const
virtual

return the linear/angular velocity of the manipulator coordinate system

virtual bool OpenRAVE::RobotBase::Manipulator::IsChildLink ( LinkConstPtr  plink) const
virtual

returns true if a link is part of the child links of the manipulator.

The child links do not include the arm links.

virtual bool OpenRAVE::RobotBase::Manipulator::IsGrabbing ( KinBodyConstPtr  body) const
virtual

Checks collision with a target body and all the independent links of the robot. Ignores disabled links.

Parameters
[in]thebody to check the independent links with
[out]report[optional] collision report
Returns
true if a collision occurredreturn true if the body is being grabbed by any link on this manipulator
virtual void OpenRAVE::RobotBase::Manipulator::serialize ( std::ostream &  o,
int  options 
) const
virtual
virtual bool OpenRAVE::RobotBase::Manipulator::SetIkSolver ( IkSolverBasePtr  iksolver)
virtual

Sets the ik solver and initializes it with the current manipulator.

Due to complications with translation,rotation,direction,and ray ik, the ik solver should take into account the grasp transform (_info._tLocalTool) internally. The actual ik primitives are transformed into the base frame only.

virtual void OpenRAVE::RobotBase::Manipulator::SetLocalToolDirection ( const Vector direction)
virtual

Sets the local tool direction with respect to the end effector link.

Because this call will change manipulator hash, it resets the loaded IK and sends the Prop_RobotManipulatorTool message.

virtual void OpenRAVE::RobotBase::Manipulator::SetLocalToolTransform ( const Transform t)
virtual

Sets the local tool transform with respect to the end effector link.

Because this call will change manipulator hash, it resets the loaded IK and sends the Prop_RobotManipulatorTool message.

virtual void OpenRAVE::RobotBase::Manipulator::SetName ( const std::string &  name)
virtual

new name for manipulator

Exceptions
openrave_exceptionif name is already used in another manipulator

Member Data Documentation

ManipulatorInfo OpenRAVE::RobotBase::Manipulator::_info
protected

user-set information

Definition at line 330 of file robot.h.


The documentation for this class was generated from the following file: