RobWorkProject  23.9.11-
Public Types | Public Member Functions | Protected Member Functions | List of all members
Joint Class Referenceabstract

A Joint is a Frame with assignable values for position, velocity limits and acceleration limits. More...

#include <Joint.hpp>

Inherits Frame.

Inherited by DependentJoint, PrismaticJoint, PrismaticSphericalJoint, PrismaticUniversalJoint, RevoluteJoint, SphericalJoint, UniversalJoint, and VirtualJoint.

Public Types

typedef rw::core::Ptr< JointPtr
 smart pointer type to this class
 
- Public Types inherited from Frame
typedef rw::core::Ptr< FramePtr
 Smart pointer type for a Frame object.
 
typedef rw::core::Ptr< const FrameCPtr
 Smart pointer type for a constant Frame object.
 
typedef rw::common::ConcatVectorIterator< Frameiterator
 Forward iterator for frames.
 
typedef rw::common::ConstConcatVectorIterator< Frameconst_iterator
 Forward iterator for const frames.
 
typedef rw::core::iter_pair< iteratoriterator_pair
 Pair of iterators.
 
typedef rw::core::iter_pair< const_iteratorconst_iterator_pair
 Pair of const iterators.
 

Public Member Functions

virtual ~Joint ()
 Virtual destructor.
 
void setBounds (const std::pair< const rw::math::Q, const rw::math::Q > &bounds)
 Sets joint bounds. More...
 
void setBounds (const rw::math::Q &lower, const rw::math::Q &upper)
 Sets joint bounds. More...
 
const std::pair< rw::math::Q, rw::math::Q > & getBounds () const
 Gets joint bounds. More...
 
void setMaxVelocity (const rw::math::Q &maxVelocity)
 Sets max velocity of joint. More...
 
const rw::math::QgetMaxVelocity () const
 Gets max velocity of joint. More...
 
void setMaxAcceleration (const rw::math::Q &maxAcceleration)
 Sets max acceleration of joint. More...
 
const rw::math::QgetMaxAcceleration () const
 Gets max acceleration of joint. More...
 
virtual void getJacobian (size_t row, size_t col, const rw::math::Transform3D<> &joint, const rw::math::Transform3D<> &tcp, const rw::kinematics::State &state, rw::math::Jacobian &jacobian) const =0
 Finds the Jacobian of the joints and adds it in jacobian. More...
 
virtual rw::math::Transform3D getFixedTransform () const =0
 get the fixed transform from parent to this joint More...
 
virtual void setFixedTransform (const rw::math::Transform3D<> &t3d)=0
 change the transform from parent to joint base. More...
 
virtual rw::math::Transform3D getJointTransform (const rw::kinematics::State &state) const =0
 get the isolated joint transformation which is purely dependent on q. More...
 
void setActive (bool isActive)
 set the active state of the joint More...
 
bool isActive () const
 a joint is active if its motorized/controlled in some fasion. passive or non-active joints are typically used in parrallel robots. More...
 
virtual void setJointMapping (rw::math::Function1Diff<>::Ptr function)=0
 set the function to be used in transforming from the state q to the actual q needed. More...
 
virtual void removeJointMapping ()=0
 removes mapping of joint values
 
- Public Member Functions inherited from Frame
virtual ~Frame ()
 Destructor for the frame.
 
void multiplyTransform (const rw::math::Transform3D<> &parent, const rw::kinematics::State &state, rw::math::Transform3D<> &result) const
 Post-multiply the transform of the frame to the parent transform. More...
 
rw::math::Transform3D getTransform (const rw::kinematics::State &state) const
 The transform of the frame relative to its parent. More...
 
const rw::core::PropertyMapgetPropertyMap () const
 Miscellaneous properties of the frame. More...
 
rw::core::PropertyMapgetPropertyMap ()
 Miscellaneous properties of the frame. More...
 
int getDOF () const
 The number of degrees of freedom (dof) of the frame. More...
 
const rw::kinematics::FramegetParent () const
 The parent of the frame or NULL if the frame is a DAF.
 
rw::kinematics::FramegetParent ()
 The parent of the frame or NULL if the frame is a DAF.
 
rw::kinematics::FramegetParent (const rw::kinematics::State &state)
 Returns the parent of the frame. More...
 
const rw::kinematics::FramegetParent (const rw::kinematics::State &state) const
 Returns the parent of the frame. More...
 
const rw::kinematics::FramegetDafParent (const rw::kinematics::State &state) const
 The dynamically attached parent or NULL if the frame is not a DAF.
 
rw::kinematics::FramegetDafParent (const rw::kinematics::State &state)
 The dynamically attached parent or NULL if the frame is not a DAF. More...
 
const_iterator_pair getChildren () const
 Iterator pair for the fixed children of the frame.
 
iterator_pair getChildren ()
 Iterator pair for the fixed children of the frame. More...
 
const_iterator_pair getChildren (const rw::kinematics::State &state) const
 Iterator pair for all children of the frame.
 
iterator_pair getChildren (const rw::kinematics::State &state)
 Iterator pair for all children of the frame.
 
std::vector< Frame::PtrgetChildrenList (const rw::kinematics::State &state)
 get a list of all frame children More...
 
const_iterator_pair getDafChildren (const rw::kinematics::State &state) const
 Iterator pair for the dynamically attached children of the frame.
 
iterator_pair getDafChildren (const rw::kinematics::State &state)
 Iterator pair for the dynamically attached children of the frame. More...
 
void attachTo (const Ptr &parent, rw::kinematics::State &state)
 Move a frame within the tree. More...
 
bool isDAF ()
 Test if this frame is a Dynamically Attachable Frame. More...
 
rw::math::Transform3D wTf (const rw::kinematics::State &state) const
 Get the transform relative to world. More...
 
rw::math::Transform3D fTf (const CPtr &to, const rw::kinematics::State &state) const
 Get the transform of other frame relative to this frame. More...
 
bool operator== (const Frame &rhs)
 Compares the Frame to see if they are the same Checks the statedata, parent frame and chld frame. More...
 
bool operator!= (const Frame &rhs)
 Check if not equal. More...
 
- Public Member Functions inherited from StateData
virtual ~StateData ()
 destructor
 
int getID () const
 An integer ID for the StateData. More...
 
const std::string & getName () const
 The name of the state data. More...
 
int size () const
 The number of doubles allocated by this StateData in each State object. More...
 
const double * getData (const rw::kinematics::State &state) const
 An array of length size() containing the values for the state data. More...
 
double * getData (rw::kinematics::State &state)
 An array of length size() containing the values for the state data. More...
 
void setData (rw::kinematics::State &state, const double *vals) const
 Assign for state data the size() of values of the array vals. More...
 
void setData (rw::kinematics::State &state, const std::vector< double > &vals) const
 Assign for state data the size() of values of the array vals. More...
 
void setData (rw::kinematics::State &state, const double &val) const
 Assign for state data the size() of values of the array vals. More...
 
bool hasCache () const
 Check is state data includes a cache. More...
 
rw::core::Ptr< rw::kinematics::StateCachegetCache (const rw::kinematics::State &state) const
 Get the cache. More...
 
rw::core::Ptr< rw::kinematics::StateCachegetCache (rw::kinematics::State &state)
 Get the cache. . More...
 
rw::core::Ptr< rw::kinematics::StateCachegetDefaultCache ()
 Get default cache. More...
 
void setCache (rw::core::Ptr< rw::kinematics::StateCache > cache, rw::kinematics::State &state)
 Set the cache values. More...
 
class rw::kinematics::StateStructuregetStateStructure ()
 Get the state structure. More...
 
bool operator== (const StateData &rhs)
 Compares the state data to see if they are the same Checks the ID, name and which statetrucure they belong to. More...
 
bool operator!= (const StateData &rhs)
 Check if not equal. More...
 
 StateData (int size, const std::string &name)
 A state with size number of doubles in the State vector. More...
 
 StateData (int size, const std::string &name, rw::core::Ptr< rw::kinematics::StateCache > cache)
 A state with size number of doubles in the State vector. More...
 

Protected Member Functions

 Joint (const std::string &name, size_t dof)
 Default constructor for the joint interface. More...
 
 Joint (const std::string &name, size_t dof, size_t stateSize)
 constructor - with the possiblity of adding additional states than the dofs. More...
 
- Protected Member Functions inherited from Frame
 Frame (int dof, const std::string &name)
 A frame with dof number of degrees of freedom. More...
 
virtual void doMultiplyTransform (const rw::math::Transform3D<> &parent, const rw::kinematics::State &state, rw::math::Transform3D<> &result) const =0
 Subclass implementation of the getTransform() method.
 
virtual rw::math::Transform3D doGetTransform (const rw::kinematics::State &state) const =0
 

Detailed Description

A Joint is a Frame with assignable values for position, velocity limits and acceleration limits.

Constructor & Destructor Documentation

◆ Joint() [1/2]

Joint ( const std::string &  name,
size_t  dof 
)
protected

Default constructor for the joint interface.

Parameters
name[in] The name of the frame.
dof[in] the degrees of freedom of this joint

◆ Joint() [2/2]

Joint ( const std::string &  name,
size_t  dof,
size_t  stateSize 
)
protected

constructor - with the possiblity of adding additional states than the dofs.

Parameters
name[in] The name of the joint frame.
dof[in] degree of freedom of the joint
stateSize[in] additional doubles to allocate space for in the state

Member Function Documentation

◆ getBounds()

const std::pair<rw::math::Q, rw::math::Q>& getBounds ( ) const
inline

Gets joint bounds.

Returns
the lower and upper bound of this joint

◆ getFixedTransform()

virtual rw::math::Transform3D getFixedTransform ( ) const
pure virtual

get the fixed transform from parent to this joint

Notice that this does not include the actual rotation of the joint (its state) only its fixed transform.

Returns
fixed part of transform from paretn to joint

Implemented in VirtualJoint, UniversalJoint, SphericalJoint, RevoluteJoint, PrismaticUniversalJoint, PrismaticSphericalJoint, PrismaticJoint, DependentRevoluteJoint, and DependentPrismaticJoint.

◆ getJacobian()

virtual void getJacobian ( size_t  row,
size_t  col,
const rw::math::Transform3D<> &  joint,
const rw::math::Transform3D<> &  tcp,
const rw::kinematics::State state,
rw::math::Jacobian jacobian 
) const
pure virtual

Finds the Jacobian of the joints and adds it in jacobian.

Calculates the Jacobian contribution to the device Jacobian when controlling a frame tcp and given a current joint pose joint.

The values are stored from row row to row+5 and column col to col+(joint.getDOF()-1).

Parameters
row[in] Row where values should be stored
col[in] Column where values should be stored
joint[in] Transform of the joint
tcp[in] Transformation of the point to control
state
jacobian[in] Jacobian to which to add the results.

Implemented in VirtualJoint, RevoluteJoint, PrismaticJoint, DependentRevoluteJoint, and DependentPrismaticJoint.

◆ getJointTransform()

virtual rw::math::Transform3D getJointTransform ( const rw::kinematics::State state) const
pure virtual

get the isolated joint transformation which is purely dependent on q.

Parameters
state[in] the state from which to extract q
Returns
the joint transformation

Implemented in VirtualJoint, UniversalJoint, SphericalJoint, RevoluteJoint, PrismaticUniversalJoint, PrismaticSphericalJoint, PrismaticJoint, DependentRevoluteJoint, and DependentPrismaticJoint.

◆ getMaxAcceleration()

const rw::math::Q& getMaxAcceleration ( ) const
inline

Gets max acceleration of joint.

Returns
the maximum acceleration of the joint

◆ getMaxVelocity()

const rw::math::Q& getMaxVelocity ( ) const
inline

Gets max velocity of joint.

Returns
the maximum velocity of the joint

◆ isActive()

bool isActive ( ) const
inline

a joint is active if its motorized/controlled in some fasion. passive or non-active joints are typically used in parrallel robots.

Returns

◆ setActive()

void setActive ( bool  isActive)
inline

set the active state of the joint

Parameters
isActive[in] true to enable control/motorization of joint, false otherwise

◆ setBounds() [1/2]

void setBounds ( const rw::math::Q lower,
const rw::math::Q upper 
)
inline

Sets joint bounds.

Parameters
lower[in] the lower of this joint
upper[in] the upper of this joint

◆ setBounds() [2/2]

void setBounds ( const std::pair< const rw::math::Q, const rw::math::Q > &  bounds)
inline

Sets joint bounds.

Parameters
bounds[in] the lower and upper bounds of this joint

◆ setFixedTransform()

virtual void setFixedTransform ( const rw::math::Transform3D<> &  t3d)
pure virtual

change the transform from parent to joint base.

Parameters
t3d[in] the new transform.

Implemented in VirtualJoint, UniversalJoint, SphericalJoint, RevoluteJoint, PrismaticUniversalJoint, PrismaticSphericalJoint, PrismaticJoint, DependentRevoluteJoint, and DependentPrismaticJoint.

◆ setJointMapping()

virtual void setJointMapping ( rw::math::Function1Diff<>::Ptr  function)
pure virtual

set the function to be used in transforming from the state q to the actual q needed.

This function can be used e.g. by a calibration.

Parameters
function[in] function with first order derivative.

Implemented in VirtualJoint, UniversalJoint, SphericalJoint, RevoluteJoint, PrismaticUniversalJoint, PrismaticSphericalJoint, PrismaticJoint, DependentRevoluteJoint, and DependentPrismaticJoint.

◆ setMaxAcceleration()

void setMaxAcceleration ( const rw::math::Q maxAcceleration)
inline

Sets max acceleration of joint.

Parameters
maxAcceleration[in] the new maximum acceleration of the joint

◆ setMaxVelocity()

void setMaxVelocity ( const rw::math::Q maxVelocity)
inline

Sets max velocity of joint.

Parameters
maxVelocity[in] the new maximum velocity of the joint

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