openrave.org

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

Information about a joint that controls the relationship between two links. More...

#include <kinbody.h>

Inheritance diagram for OpenRAVE::KinBody::Joint:
Inheritance graph
[legend]
Collaboration diagram for OpenRAVE::KinBody::Joint:
Collaboration graph
[legend]

Public Types

typedef Mimic MIMIC RAVE_DEPRECATED
 
typedef KinBody::JointType
JointType 
RAVE_DEPRECATED
 

Public Member Functions

 Joint (KinBodyPtr parent, KinBody::JointType type=KinBody::JointNone)
 
virtual ~Joint ()
 
const std::string & GetName () const
 The unique name of the joint.
 
dReal GetMaxVel (int iaxis=0) const
 
dReal GetMaxAccel (int iaxis=0) const
 
dReal GetMaxTorque (int iaxis=0) const
 
int GetDOFIndex () const
 Get the degree of freedom index in the body's DOF array.
 
int GetJointIndex () const
 Get the joint index into KinBody::GetJoints.
 
KinBodyPtr GetParent () const
 
LinkPtr GetFirstAttached () const
 
LinkPtr GetSecondAttached () const
 
KinBody::JointType GetType () const
 
virtual void GetResolutions (std::vector< dReal > &resolutions, bool bAppend=false) const
 gets all resolutions for the joint axes
 
virtual dReal GetResolution (int iaxis=0) const
 The discretization of the joint used when line-collision checking.
 
virtual void SetResolution (dReal resolution, int iaxis=0)
 
virtual int GetDOF () const
 The degrees of freedom of the joint. Each joint supports a max of 3 degrees of freedom.
 
virtual bool IsCircular (int iaxis) const
 Return true if joint axis has an identification at some of its lower and upper limits.
 
virtual bool IsRevolute (int iaxis) const
 returns true if the axis describes a rotation around an axis.
 
virtual bool IsPrismatic (int iaxis) const
 returns true if the axis describes a translation around an axis.
 
virtual bool IsStatic () const
 Return true if joint can be treated as a static binding (ie all limits are 0)
 
virtual void GetValues (std::vector< dReal > &values, bool bAppend=false) const
 Return all the joint values with the correct offsets applied.
 
virtual dReal GetValue (int axis) const
 Return the value of the specified joint axis only.
 
virtual void GetVelocities (std::vector< dReal > &values, bool bAppend=false) const
 Gets the joint velocities.
 
virtual dReal GetVelocity (int axis) const
 Return the velocity of the specified joint axis only.
 
virtual void AddTorque (const std::vector< dReal > &torques)
 Add effort (force or torque) to the joint.
 
virtual Vector GetAnchor () const
 The anchor of the joint in global coordinates.
 
virtual Vector GetAxis (int axis=0) const
 The axis of the joint in global coordinates.
 
virtual void GetLimits (std::vector< dReal > &vLowerLimit, std::vector< dReal > &vUpperLimit, bool bAppend=false) const
 Get the limits of the joint.
 
virtual std::pair< dReal, dRealGetLimit (int iaxis=0) const
 returns the lower and upper limit of one axis of the joint
 
virtual void SetLimits (const std::vector< dReal > &lower, const std::vector< dReal > &upper)
 
virtual void GetVelocityLimits (std::vector< dReal > &vmax, bool bAppend=false) const
 Returns the max velocities of the joint.
 
virtual void GetVelocityLimits (std::vector< dReal > &vlower, std::vector< dReal > &vupper, bool bAppend=false) const
 
virtual std::pair< dReal, dRealGetVelocityLimit (int iaxis=0) const
 returns the lower and upper velocity limit of one axis of the joint
 
virtual void SetVelocityLimits (const std::vector< dReal > &vmax)
 
virtual void GetAccelerationLimits (std::vector< dReal > &vmax, bool bAppend=false) const
 Returns the max accelerations of the joint.
 
virtual dReal GetAccelerationLimit (int iaxis=0) const
 
virtual void SetAccelerationLimits (const std::vector< dReal > &vmax)
 
virtual void GetTorqueLimits (std::vector< dReal > &vmax, bool bAppend=false) const
 Returns the max torques of the joint.
 
virtual void SetTorqueLimits (const std::vector< dReal > &vmax)
 
virtual void GetWeights (std::vector< dReal > &weights, bool bAppend=false) const
 gets all weights for the joint axes
 
virtual dReal GetWeight (int axis=0) const
 The weight associated with a joint's axis for computing a distance in the robot configuration space.
 
virtual void SetWeights (const std::vector< dReal > &weights)
 
virtual void SubtractValues (std::vector< dReal > &values1, const std::vector< dReal > &values2) const
 Computes the configuration difference values1-values2 and stores it in values1.
 
virtual dReal SubtractValue (dReal value1, dReal value2, int iaxis) const
 Returns the configuration difference value1-value2 for axis i.
 
dReal GetWrapOffset (int iaxis=0) const
 Return internal offset parameter that determines the branch the angle centers on.
 
dReal GetOffset (int iaxis=0) const RAVE_DEPRECATED
 
virtual void SetWrapOffset (dReal offset, int iaxis=0)
 
virtual void serialize (std::ostream &o, int options) const
 
const std::map< std::string,
std::vector< dReal > > & 
GetFloatParameters () const
 return a map of custom float parameters
 
virtual void SetFloatParameters (const std::string &key, const std::vector< dReal > &parameters)
 set custom float parameters
 
const std::map< std::string,
std::vector< int > > & 
GetIntParameters () const
 return a map of custom integer parameters
 
virtual void SetIntParameters (const std::string &key, const std::vector< int > &parameters)
 set custom int parameters
 
virtual void UpdateInfo ()
 Updates several fields in _info depending on the current state of the joint.
 
const KinBody::JointInfoGetInfo () const
 returns the JointInfo structure containing all information.
 
const KinBody::JointInfoUpdateAndGetInfo ()
 Calls UpdateInfo and returns the joint structure.
 
Internal Hierarchy Methods
virtual LinkPtr GetHierarchyParentLink () const
 Return the parent link which the joint measures its angle off from (either GetFirstAttached() or GetSecondAttached())
 
virtual LinkPtr GetHierarchyChildLink () const
 Return the child link whose transformation is computed by this joint's values (either GetFirstAttached() or GetSecondAttached())
 
virtual Vector GetInternalHierarchyAxis (int axis=0) const
 The axis of the joint in local coordinates.
 
virtual Transform GetInternalHierarchyLeftTransform () const
 Left multiply transform given the base body.
 
virtual Transform GetInternalHierarchyRightTransform () const
 Right multiply transform given the base body.
 
Mimic Joint Properties

A mimic joint's angles are automatically determined from other joints based on a general purpose formula. A user does not have control of the the mimic joint values, even if they appear in the DOF list.

virtual int GetMimicJointIndex () const RAVE_DEPRECATED
 
virtual const std::vector< dRealGetMimicCoeffs () const RAVE_DEPRECATED
 
virtual bool IsMimic (int axis=-1) const
 Returns true if a particular axis of the joint is mimiced.
 
virtual std::string GetMimicEquation (int axis=0, int type=0, const std::string &format="") const
 If the joint is mimic, returns the equation to compute its value.
 
virtual void GetMimicDOFIndices (std::vector< int > &vmimicdofs, int axis=0) const
 Returns the set of DOF indices that the computation of a joint axis depends on. Order is arbitrary.
 
virtual void SetMimicEquations (int axis, const std::string &poseq, const std::string &veleq, const std::string &acceleq="")
 Sets the mimic properties of the joint.
 

Static Public Attributes

static const
KinBody::JointType JointNone 
RAVE_DEPRECATED = KinBody::JointNone
 
static const
KinBody::JointType JointHinge 
RAVE_DEPRECATED = KinBody::JointHinge
 
static const
KinBody::JointType
JointRevolute 
RAVE_DEPRECATED = KinBody::JointRevolute
 
static const
KinBody::JointType JointSlider 
RAVE_DEPRECATED = KinBody::JointSlider
 
static const
KinBody::JointType
JointPrismatic 
RAVE_DEPRECATED = KinBody::JointPrismatic
 
static const
KinBody::JointType JointRR 
RAVE_DEPRECATED = KinBody::JointRR
 
static const
KinBody::JointType JointRP 
RAVE_DEPRECATED = KinBody::JointRP
 
static const
KinBody::JointType JointPR 
RAVE_DEPRECATED = KinBody::JointPR
 
static const
KinBody::JointType JointPP 
RAVE_DEPRECATED = KinBody::JointPP
 
static const
KinBody::JointType
JointSpecialBit 
RAVE_DEPRECATED = KinBody::JointSpecialBit
 
static const
KinBody::JointType
JointUniversal 
RAVE_DEPRECATED = KinBody::JointUniversal
 
static const
KinBody::JointType JointHinge2 
RAVE_DEPRECATED = KinBody::JointHinge2
 
static const
KinBody::JointType
JointSpherical 
RAVE_DEPRECATED = KinBody::JointSpherical
 
static const
KinBody::JointType
JointTrajectory 
RAVE_DEPRECATED = KinBody::JointTrajectory
 

Protected Member Functions

virtual void _ComputePartialVelocities (std::vector< std::pair< int, dReal > > &vpartials, int iaxis, std::map< std::pair< Mimic::DOFFormat, int >, dReal > &mapcachedpartials) const
 computes the partial velocities with respect to all dependent DOFs specified by Mimic::_vmimicdofs.
 
virtual void _ComputeInternalInformation (LinkPtr plink0, LinkPtr plink1, const Vector &vanchor, const std::vector< Vector > &vaxes, const std::vector< dReal > &vcurrentvalues)
 Compute internal transformations and specify the attached links of the joint.
 
virtual int _Eval (int axis, uint32_t timederiv, const std::vector< dReal > &vdependentvalues, std::vector< dReal > &voutput)
 evaluates the mimic joint equation using vdependentvalues
 
virtual void _GetVelocities (std::vector< dReal > &values, bool bAppend, const std::pair< Vector, Vector > &linkparentvelocity, const std::pair< Vector, Vector > &linkchildvelocity) const
 compute joint velocities given the parent and child link transformations/velocities
 
virtual dReal _GetVelocity (int axis, const std::pair< Vector, Vector > &linkparentvelocity, const std::pair< Vector, Vector > &linkchildvelocity) const
 Return the velocity of the specified joint axis only.
 

Protected Attributes

JointInfo _info
 
boost::array< MimicPtr, 3 > _vmimic
 the mimic properties of each of the joint axes. It is theoretically possible for a multi-dof joint to have one axes mimiced and the others free. When cloning, is it ok to copy this and assume it is constant?
 
boost::array< int, 3 > _dofbranches
 the branch that identified joints are on. +1 means one loop around the identification. For revolute joints, the actual joint value incremented by 2*pi*branch. Branches are important for maintaining joint ranges greater than 2*pi. For circular joints, the branches can be ignored or not.
 

Detailed Description

Information about a joint that controls the relationship between two links.

Definition at line 710 of file kinbody.h.

Member Typedef Documentation

Deprecated:
12/10/19

Definition at line 714 of file kinbody.h.

Definition at line 715 of file kinbody.h.

Constructor & Destructor Documentation

OpenRAVE::KinBody::Joint::Joint ( KinBodyPtr  parent,
KinBody::JointType  type = KinBody::JointNone 
)

Definition at line 106 of file kinbodyjoint.cpp.

OpenRAVE::KinBody::Joint::~Joint ( )
virtual

Definition at line 121 of file kinbodyjoint.cpp.

Member Function Documentation

void OpenRAVE::KinBody::Joint::_ComputeInternalInformation ( LinkPtr  plink0,
LinkPtr  plink1,
const Vector vanchor,
const std::vector< Vector > &  vaxes,
const std::vector< dReal > &  vcurrentvalues 
)
protectedvirtual

Compute internal transformations and specify the attached links of the joint.

Called after the joint protected parameters {vAxes, vanchor, and _voffsets} have been initialized. vAxes and vanchor should be in the frame of plink0. Compute the left and right multiplications of the joint transformation and cleans up the attached bodies. After function completes, the following parameters are initialized: _tRight, _tLeft, _tinvRight, _tinvLeft, _attachedbodies. _attachedbodies does not necessarily contain the links in the same order as they were input.

Parameters
plink0the first attaching link, all axes and anchors are defined in its coordinate system
plink1the second attaching link
vanchorthe anchor of the rotation axes
vaxesthe axes in plink0's coordinate system of the joints
vinitialvaluesthe current values of the robot used to set the 0 offset of the robot

Definition at line 566 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::_ComputePartialVelocities ( std::vector< std::pair< int, dReal > > &  vpartials,
int  iaxis,
std::map< std::pair< Mimic::DOFFormat, int >, dReal > &  mapcachedpartials 
) const
protectedvirtual

computes the partial velocities with respect to all dependent DOFs specified by Mimic::_vmimicdofs.

If the joint is not mimic, then just returns its own index

Parameters
[out]vpartialsA list of dofindex/velocity_partial pairs. The final velocity is computed by taking the dot product. The dofindices do not repeat.
[in]iaxisthe axis
[in,out]vcachedpartialsset of cached partials for each degree of freedom

Definition at line 1225 of file kinbodyjoint.cpp.

int OpenRAVE::KinBody::Joint::_Eval ( int  axis,
uint32_t  timederiv,
const std::vector< dReal > &  vdependentvalues,
std::vector< dReal > &  voutput 
)
protectedvirtual

evaluates the mimic joint equation using vdependentvalues

Parameters
[in]axisthe joint axis
[in]timederivthe time derivative to evaluate. 0 is position, 1 is velocity, 2 is acceleration, etc
[in]vdependentvaluesinput values ordered with respect to _vdofformat[iaxis]
[out]voutputthe output values
Returns
an internal error code, 0 if no error

Definition at line 1294 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::_GetVelocities ( std::vector< dReal > &  values,
bool  bAppend,
const std::pair< Vector, Vector > &  linkparentvelocity,
const std::pair< Vector, Vector > &  linkchildvelocity 
) const
protectedvirtual

compute joint velocities given the parent and child link transformations/velocities

Definition at line 467 of file kinbodyjoint.cpp.

dReal OpenRAVE::KinBody::Joint::_GetVelocity ( int  axis,
const std::pair< Vector, Vector > &  linkparentvelocity,
const std::pair< Vector, Vector > &  linkchildvelocity 
) const
protectedvirtual

Return the velocity of the specified joint axis only.

Definition at line 509 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::AddTorque ( const std::vector< dReal > &  torques)
virtual

Add effort (force or torque) to the joint.

Definition at line 988 of file kinbodyjoint.cpp.

dReal OpenRAVE::KinBody::Joint::GetAccelerationLimit ( int  iaxis = 0) const
virtual

Definition at line 860 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::GetAccelerationLimits ( std::vector< dReal > &  vmax,
bool  bAppend = false 
) const
virtual

Returns the max accelerations of the joint.

Parameters
[out]themax acceleration
[in]bAppendif true will append to the end of the vector instead of erasing it

Definition at line 850 of file kinbodyjoint.cpp.

Vector OpenRAVE::KinBody::Joint::GetAnchor ( ) const
virtual

The anchor of the joint in global coordinates.

Definition at line 556 of file kinbodyjoint.cpp.

Vector OpenRAVE::KinBody::Joint::GetAxis ( int  axis = 0) const
virtual

The axis of the joint in global coordinates.

Parameters
[in]axisthe axis to get

Definition at line 561 of file kinbodyjoint.cpp.

int OpenRAVE::KinBody::Joint::GetDOF ( ) const
virtual

The degrees of freedom of the joint. Each joint supports a max of 3 degrees of freedom.

Definition at line 125 of file kinbodyjoint.cpp.

int OpenRAVE::KinBody::Joint::GetDOFIndex ( ) const
inline

Get the degree of freedom index in the body's DOF array.

This does not index in KinBody::GetJoints() directly! In other words, KinBody::GetDOFValues()[GetDOFIndex()] == GetValues()[0]

Definition at line 752 of file kinbody.h.

LinkPtr OpenRAVE::KinBody::Joint::GetFirstAttached ( ) const
inline

Definition at line 765 of file kinbody.h.

const std::map<std::string, std::vector<dReal> >& OpenRAVE::KinBody::Joint::GetFloatParameters ( ) const
inline

return a map of custom float parameters

Definition at line 1003 of file kinbody.h.

KinBody::LinkPtr OpenRAVE::KinBody::Joint::GetHierarchyChildLink ( ) const
virtual

Return the child link whose transformation is computed by this joint's values (either GetFirstAttached() or GetSecondAttached())

Definition at line 752 of file kinbodyjoint.cpp.

KinBody::LinkPtr OpenRAVE::KinBody::Joint::GetHierarchyParentLink ( ) const
virtual

Return the parent link which the joint measures its angle off from (either GetFirstAttached() or GetSecondAttached())

Definition at line 747 of file kinbodyjoint.cpp.

const KinBody::JointInfo& OpenRAVE::KinBody::Joint::GetInfo ( ) const
inline

returns the JointInfo structure containing all information.

Some values in this structure like _vcurrentvalues need to be updated, so make sure to call UpdateInfo() right before this function is called.

Definition at line 1028 of file kinbody.h.

Vector OpenRAVE::KinBody::Joint::GetInternalHierarchyAxis ( int  axis = 0) const
virtual

The axis of the joint in local coordinates.

Definition at line 757 of file kinbodyjoint.cpp.

Transform OpenRAVE::KinBody::Joint::GetInternalHierarchyLeftTransform ( ) const
virtual

Left multiply transform given the base body.

Definition at line 762 of file kinbodyjoint.cpp.

Transform OpenRAVE::KinBody::Joint::GetInternalHierarchyRightTransform ( ) const
virtual

Right multiply transform given the base body.

Definition at line 768 of file kinbodyjoint.cpp.

const std::map<std::string, std::vector<int> >& OpenRAVE::KinBody::Joint::GetIntParameters ( ) const
inline

return a map of custom integer parameters

Definition at line 1013 of file kinbody.h.

int OpenRAVE::KinBody::Joint::GetJointIndex ( ) const
inline

Get the joint index into KinBody::GetJoints.

Definition at line 757 of file kinbody.h.

std::pair< dReal, dReal > OpenRAVE::KinBody::Joint::GetLimit ( int  iaxis = 0) const
virtual

returns the lower and upper limit of one axis of the joint

Definition at line 786 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::GetLimits ( std::vector< dReal > &  vLowerLimit,
std::vector< dReal > &  vUpperLimit,
bool  bAppend = false 
) const
virtual

Get the limits of the joint.

Parameters
[out]vLowerLimitthe lower limits
[out]vUpperLimitthe upper limits
[in]bAppendif true will append to the end of the vector instead of erasing it

Definition at line 774 of file kinbodyjoint.cpp.

dReal OpenRAVE::KinBody::Joint::GetMaxAccel ( int  iaxis = 0) const
inline

Definition at line 742 of file kinbody.h.

dReal OpenRAVE::KinBody::Joint::GetMaxTorque ( int  iaxis = 0) const
inline

Definition at line 745 of file kinbody.h.

dReal OpenRAVE::KinBody::Joint::GetMaxVel ( int  iaxis = 0) const
inline

Definition at line 739 of file kinbody.h.

const std::vector< dReal > OpenRAVE::KinBody::Joint::GetMimicCoeffs ( ) const
virtual
Deprecated:
(11/1/1)

Definition at line 1003 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::GetMimicDOFIndices ( std::vector< int > &  vmimicdofs,
int  axis = 0 
) const
virtual

Returns the set of DOF indices that the computation of a joint axis depends on. Order is arbitrary.

If the mimic joint uses the values of other mimic joints, then the dependent DOFs of that joint are also copied over. Therefore, the dof indices returned can be more than the actual variables used in the equation.

Exceptions
openrave_exceptionThrows an exception if the axis is not mimic.

Definition at line 1072 of file kinbodyjoint.cpp.

std::string OpenRAVE::KinBody::Joint::GetMimicEquation ( int  axis = 0,
int  type = 0,
const std::string &  format = "" 
) const
virtual

If the joint is mimic, returns the equation to compute its value.

Parameters
[in]axisthe axis index
[in]type0 for position, 1 for velocity, 2 for acceleration.
[in]formatthe format the equations are returned in. If empty or "fparser", equation in fparser format. Also supports: "mathml".

MathML:

Set 'format' to "mathml". The joint variables are specified with <csymbol>. If a targetted joint has more than one degree of freedom, then axis is suffixed with _%d. If 'type' is 1 or 2, the partial derivatives are outputted as consecutive <math></math> tags in the same order as Mimic::_vdofformat

Definition at line 1023 of file kinbodyjoint.cpp.

int OpenRAVE::KinBody::Joint::GetMimicJointIndex ( ) const
virtual
Deprecated:
(11/1/1)

Definition at line 993 of file kinbodyjoint.cpp.

const std::string& OpenRAVE::KinBody::Joint::GetName ( ) const
inline

The unique name of the joint.

Definition at line 735 of file kinbody.h.

dReal OpenRAVE::KinBody::Joint::GetOffset ( int  iaxis = 0) const
inline

Definition at line 922 of file kinbody.h.

KinBodyPtr OpenRAVE::KinBody::Joint::GetParent ( ) const
inline

Definition at line 761 of file kinbody.h.

dReal OpenRAVE::KinBody::Joint::GetResolution ( int  iaxis = 0) const
virtual

The discretization of the joint used when line-collision checking.

The resolutions are set as large as possible such that the joint will not go through obstacles of determined size.

Definition at line 931 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::GetResolutions ( std::vector< dReal > &  resolutions,
bool  bAppend = false 
) const
virtual

gets all resolutions for the joint axes

Parameters
[in]bAppendif true will append to the end of the vector instead of erasing it

Definition at line 921 of file kinbodyjoint.cpp.

LinkPtr OpenRAVE::KinBody::Joint::GetSecondAttached ( ) const
inline

Definition at line 768 of file kinbody.h.

void OpenRAVE::KinBody::Joint::GetTorqueLimits ( std::vector< dReal > &  vmax,
bool  bAppend = false 
) const
virtual

Returns the max torques of the joint.

Parameters
[out]themax torque
[in]bAppendif true will append to the end of the vector instead of erasing it

Definition at line 873 of file kinbodyjoint.cpp.

KinBody::JointType OpenRAVE::KinBody::Joint::GetType ( ) const
inline

Definition at line 772 of file kinbody.h.

dReal OpenRAVE::KinBody::Joint::GetValue ( int  axis) const
virtual

Return the value of the specified joint axis only.

Definition at line 292 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::GetValues ( std::vector< dReal > &  values,
bool  bAppend = false 
) const
virtual

Return all the joint values with the correct offsets applied.

Parameters
bAppendif true will append to the end of the vector instead of erasing it
Returns
degrees of freedom of the joint (even if pValues is NULL)

Definition at line 194 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::GetVelocities ( std::vector< dReal > &  values,
bool  bAppend = false 
) const
virtual

Gets the joint velocities.

Parameters
bAppendif true will append to the end of the vector instead of erasing it
Returns
the degrees of freedom of the joint (even if pValues is NULL)

Definition at line 448 of file kinbodyjoint.cpp.

dReal OpenRAVE::KinBody::Joint::GetVelocity ( int  axis) const
virtual

Return the velocity of the specified joint axis only.

Definition at line 461 of file kinbodyjoint.cpp.

std::pair< dReal, dReal > OpenRAVE::KinBody::Joint::GetVelocityLimit ( int  iaxis = 0) const
virtual

returns the lower and upper velocity limit of one axis of the joint

Definition at line 837 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::GetVelocityLimits ( std::vector< dReal > &  vmax,
bool  bAppend = false 
) const
virtual

Returns the max velocities of the joint.

Parameters
[out]themax velocity
[in]bAppendif true will append to the end of the vector instead of erasing it

Definition at line 827 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::GetVelocityLimits ( std::vector< dReal > &  vlower,
std::vector< dReal > &  vupper,
bool  bAppend = false 
) const
virtual

Definition at line 815 of file kinbodyjoint.cpp.

dReal OpenRAVE::KinBody::Joint::GetWeight ( int  axis = 0) const
virtual

The weight associated with a joint's axis for computing a distance in the robot configuration space.

Definition at line 952 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::GetWeights ( std::vector< dReal > &  weights,
bool  bAppend = false 
) const
virtual

gets all weights for the joint axes

Parameters
[in]bAppendif true will append to the end of the vector instead of erasing it

Definition at line 942 of file kinbodyjoint.cpp.

dReal OpenRAVE::KinBody::Joint::GetWrapOffset ( int  iaxis = 0) const
inline

Return internal offset parameter that determines the branch the angle centers on.

Wrap offsets are needed for rotation joints since the range is limited to 2*pi. This allows the wrap offset to be set so the joint can function in [-pi+offset,pi+offset]..

Parameters
iaxisthe axis to get the offset from

Definition at line 918 of file kinbody.h.

bool OpenRAVE::KinBody::Joint::IsCircular ( int  iaxis) const
virtual

Return true if joint axis has an identification at some of its lower and upper limits.

An identification of the lower and upper limits means that once the joint reaches its upper limits, it is also at its lower limit. The most common identification on revolute joints at -pi and pi. 'circularity' means the joint does not stop at limits. Although currently not developed, it could be possible to support identification for joints that are not revolute.

Definition at line 140 of file kinbodyjoint.cpp.

bool OpenRAVE::KinBody::Joint::IsMimic ( int  axis = -1) const
virtual

Returns true if a particular axis of the joint is mimiced.

Parameters
axisthe axis to query. When -1 returns true if any of the axes have mimic joints

Definition at line 1010 of file kinbodyjoint.cpp.

bool OpenRAVE::KinBody::Joint::IsPrismatic ( int  iaxis) const
virtual

returns true if the axis describes a translation around an axis.

Parameters
iaxisthe axis of the joint to return the results for

Definition at line 153 of file kinbodyjoint.cpp.

bool OpenRAVE::KinBody::Joint::IsRevolute ( int  iaxis) const
virtual

returns true if the axis describes a rotation around an axis.

Parameters
iaxisthe axis of the joint to return the results for

Definition at line 145 of file kinbodyjoint.cpp.

bool OpenRAVE::KinBody::Joint::IsStatic ( ) const
virtual

Return true if joint can be treated as a static binding (ie all limits are 0)

Definition at line 161 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::serialize ( std::ostream &  o,
int  options 
) const
virtual

Definition at line 1376 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::SetAccelerationLimits ( const std::vector< dReal > &  vmax)
virtual
See Also
GetAccelerationLimits

Definition at line 865 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::SetFloatParameters ( const std::string &  key,
const std::vector< dReal > &  parameters 
)
virtual

set custom float parameters

Parameters
parametersif empty, then removes the parameter

Definition at line 1348 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::SetIntParameters ( const std::string &  key,
const std::vector< int > &  parameters 
)
virtual

set custom int parameters

Parameters
parametersif empty, then removes the parameter

Definition at line 1359 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::SetLimits ( const std::vector< dReal > &  lower,
const std::vector< dReal > &  upper 
)
virtual
See Also
GetLimits

Definition at line 791 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::SetMimicEquations ( int  axis,
const std::string &  poseq,
const std::string &  veleq,
const std::string &  acceleq = "" 
)
virtual

Sets the mimic properties of the joint.

The equations can use the joint names directly in the equation, which represent the position of the joint. Any non-mimic joint part of KinBody::GetJoints() can be used in the computation of the values. If a joint has more than one degree of freedom, then suffix it '_' and the axis index. For example universaljoint_0 * 10 + sin(universaljoint_1).

See http://warp.povusers.org/FunctionParser/fparser.html for a full description of the equation formats.

The velocity and acceleration equations are specified in terms of partial derivatives, which means one expression needs to be specified per degree of freedom of used. In order to separate the expressions use "|name ...". The name should immediately follow '|'. For example:

|universaljoint_0 10 |universaljoint_1 10*cos(universaljoint_1)

If there is only one variable used in the position equation, then the equation can be specified directly without using "{}".

Parameters
[in]axisthe axis to set the properties for.
[in]poseqEquation for joint's position. If it is empty, the mimic properties are turned off for this joint.
[in]veleqFirst-order partial derivatives of poseq with respect to all used DOFs. Only the variables used in poseq are allowed to be used. If poseq is not empty, this is required.
[in]acceleqSecond-order partial derivatives of poseq with respect to all used DOFs. Only the variables used in poseq are allowed to be used. Optional.
Exceptions
openrave_exceptionThrows an exception if the mimic equation is invalid in any way.

Definition at line 1084 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::SetResolution ( dReal  resolution,
int  iaxis = 0 
)
virtual

Definition at line 936 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::SetTorqueLimits ( const std::vector< dReal > &  vmax)
virtual
See Also
GetTorqueLimits

Definition at line 883 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::SetVelocityLimits ( const std::vector< dReal > &  vmax)
virtual
See Also
GetVelocityLimits

Definition at line 842 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::SetWeights ( const std::vector< dReal > &  weights)
virtual
See Also
GetWeight

Definition at line 957 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::SetWrapOffset ( dReal  offset,
int  iaxis = 0 
)
virtual
See Also
GetWrapOffset

Definition at line 891 of file kinbodyjoint.cpp.

dReal OpenRAVE::KinBody::Joint::SubtractValue ( dReal  value1,
dReal  value2,
int  iaxis 
) const
virtual

Returns the configuration difference value1-value2 for axis i.

Takes into account joint limits and wrapping of circular joints.

Definition at line 978 of file kinbodyjoint.cpp.

void OpenRAVE::KinBody::Joint::SubtractValues ( std::vector< dReal > &  values1,
const std::vector< dReal > &  values2 
) const
virtual

Computes the configuration difference values1-values2 and stores it in values1.

Takes into account joint limits and wrapping of circular joints.

Definition at line 966 of file kinbodyjoint.cpp.

const KinBody::JointInfo& OpenRAVE::KinBody::Joint::UpdateAndGetInfo ( )
inline

Calls UpdateInfo and returns the joint structure.

Definition at line 1033 of file kinbody.h.

void OpenRAVE::KinBody::Joint::UpdateInfo ( )
virtual

Updates several fields in _info depending on the current state of the joint.

Definition at line 1370 of file kinbodyjoint.cpp.

Member Data Documentation

boost::array<int,3> OpenRAVE::KinBody::Joint::_dofbranches
protected

the branch that identified joints are on. +1 means one loop around the identification. For revolute joints, the actual joint value incremented by 2*pi*branch. Branches are important for maintaining joint ranges greater than 2*pi. For circular joints, the branches can be ignored or not.

Definition at line 1080 of file kinbody.h.

JointInfo OpenRAVE::KinBody::Joint::_info
protected

Definition at line 1039 of file kinbody.h.

boost::array< MimicPtr,3> OpenRAVE::KinBody::Joint::_vmimic
protected

the mimic properties of each of the joint axes. It is theoretically possible for a multi-dof joint to have one axes mimiced and the others free. When cloning, is it ok to copy this and assume it is constant?

Definition at line 1041 of file kinbody.h.

Definition at line 716 of file kinbody.h.

Definition at line 717 of file kinbody.h.

Definition at line 718 of file kinbody.h.

Definition at line 719 of file kinbody.h.

Definition at line 720 of file kinbody.h.

Definition at line 721 of file kinbody.h.

Definition at line 722 of file kinbody.h.

Definition at line 723 of file kinbody.h.

Definition at line 724 of file kinbody.h.

Definition at line 725 of file kinbody.h.

Definition at line 726 of file kinbody.h.

Definition at line 727 of file kinbody.h.

Definition at line 728 of file kinbody.h.

Definition at line 729 of file kinbody.h.


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