Robowflex  v0.1
Making MoveIt Easy
robowflex::darts::Joint Class Referenceabstract

Abstract controllable joint for robowflex::darts::StateSpace. More...

#include <joints.h>

+ Inheritance diagram for robowflex::darts::Joint:

Public Member Functions

Constructors.
 Joint (StateSpace *space, unsigned int skelIndex, unsigned int jointIndex, unsigned int sizeInSpace, unsigned int startIndex, unsigned int numDof)
 Constructor. More...
 
 Joint (StateSpace *space, dart::dynamics::Joint *joint, unsigned int sizeInSpace, unsigned int startIndex=0, unsigned int numDof=0)
 Constructor. More...
 
Configuration access.
Eigen::Ref< Eigen::VectorXd > getSpaceVars (Eigen::Ref< Eigen::VectorXd > a)
 Gets the joint configuration (subvector of variables for this joint) from a configuration. More...
 
Eigen::Ref< const Eigen::VectorXd > getSpaceVarsConst (const Eigen::Ref< const Eigen::VectorXd > &a)
 Gets the subvector of variables for this joint from a configuration. More...
 
const std::vector< std::size_t > & getIndices () const
 Get the indices in the skeleton for this joint. More...
 
const std::vector< std::string > & getDofs () const
 Get the names of the DoF in the skeleton for this joint. More...
 
std::size_t getSkeletonIndex () const
 Get the index of the skeleton for this joint in the world. More...
 
std::size_t getJointIndex () const
 Get the index of the joint in the skeleton. More...
 
std::size_t getDimension () const
 Get the dimension of this joint. More...
 
Joint operations.
virtual void setUpperLimits (const Eigen::Ref< const Eigen::VectorXd > &v)
 Set the upper limits of a joint. More...
 
virtual void setLowerLimits (const Eigen::Ref< const Eigen::VectorXd > &v)
 Set the lower limits of a joint. More...
 
virtual Eigen::VectorXd getUpperLimits () const
 Get the upper limits of a joint. More...
 
virtual Eigen::VectorXd getLowerLimits () const
 Get the lower limits of a joint. More...
 
virtual double distance (const Eigen::Ref< const Eigen::VectorXd > &a, const Eigen::Ref< const Eigen::VectorXd > &b) const =0
 Compute the distance between two joint configurations. More...
 
virtual double getMaximumExtent () const =0
 Get the maximum extent of this joint (maximum distance). More...
 
virtual void interpolate (const Eigen::Ref< const Eigen::VectorXd > &a, const Eigen::Ref< const Eigen::VectorXd > &b, double t, Eigen::Ref< Eigen::VectorXd > c) const =0
 Interpolate to a new configuration c which is t from a to b. More...
 
virtual void enforceBounds (Eigen::Ref< Eigen::VectorXd > a) const =0
 Enforce bounds on a joint configuration. More...
 
virtual bool satisfiesBounds (const Eigen::Ref< const Eigen::VectorXd > &a) const =0
 Check if a joint configuration satisfies bounds. More...
 
virtual void sample (Eigen::Ref< Eigen::VectorXd > a) const =0
 Sample a configuration for this joint. More...
 
virtual void sampleNear (Eigen::Ref< Eigen::VectorXd > a, const Eigen::Ref< const Eigen::VectorXd > &near, double r) const =0
 Sample a configuration for this joint near another configuration near. More...
 
World modification.
virtual void setJointState (WorldPtr world, const Eigen::Ref< const Eigen::VectorXd > &a) const
 Set the state of the joint in world. More...
 
virtual void getJointState (WorldPtr world, Eigen::Ref< Eigen::VectorXd > a) const
 Get the state of the joint in world. More...
 
dart::dynamics::Joint * getJoint (WorldPtr world) const
 Get the Dart joint from a world. More...
 

Protected Attributes

StateSpacespace_
 State space this joint is for. More...
 
ompl::RNG & rng_
 Random number generator. More...
 
std::vector< std::size_tindices_
 Indices this joint corresponds to. More...
 
std::vector< std::stringdofs_
 Controlled DoF names. More...
 
unsigned int skelIndex_
 Index of skeleton. More...
 
unsigned int jointIndex_
 Index of joint. More...
 
unsigned int startInSpace_
 Start index in space configuration. More...
 
unsigned int sizeInSpace_
 Size of joint in space configuration. More...
 
unsigned int startIndex_
 Start index in joint. More...
 
unsigned int numDof_
 Number of DoF this joint controls. More...
 

Detailed Description

Abstract controllable joint for robowflex::darts::StateSpace.

Definition at line 37 of file joints.h.

Constructor & Destructor Documentation

◆ Joint() [1/2]

Joint::Joint ( StateSpace space,
unsigned int  skelIndex,
unsigned int  jointIndex,
unsigned int  sizeInSpace,
unsigned int  startIndex,
unsigned int  numDof 
)

Constructor.

Parameters
[in]spaceState space this joint will be in.
[in]skelIndexIndex of the skeleton this joint is in.
[in]jointIndexIndex of joint in skeleton.
[in]sizeInSpaceNumber of DoFs in the state space.
[in]startIndexStarting index in a configuration vector.
[in]numDofNumber of DoFs this joint has in the skeleton.

Joint

Definition at line 15 of file joint.cpp.

21  : space_(space)
22  , rng_(space->rng_)
23  , skelIndex_(skelIndex)
24  , jointIndex_(jointIndex)
25  , startInSpace_(space_->getDimension())
26  , sizeInSpace_(sizeInSpace)
27  , startIndex_(startIndex)
28  , numDof_(numDof)
29 {
30  auto *joint = getJoint(space_->getWorld());
31  for (unsigned int i = 0; i < numDof_; ++i)
32  {
33  unsigned int j = startIndex_ + i;
34  if (j >= joint->getNumDofs())
35  throw std::runtime_error("Invalid joint");
36 
37  auto *dof = joint->getDof(j);
38  indices_.emplace_back(dof->getIndexInSkeleton());
39  dofs_.emplace_back(dof->getName());
40  }
41 }
unsigned int skelIndex_
Index of skeleton.
Definition: joints.h:211
unsigned int jointIndex_
Index of joint.
Definition: joints.h:212
unsigned int startIndex_
Start index in joint.
Definition: joints.h:217
StateSpace * space_
State space this joint is for.
Definition: joints.h:205
std::vector< std::size_t > indices_
Indices this joint corresponds to.
Definition: joints.h:208
unsigned int numDof_
Number of DoF this joint controls.
Definition: joints.h:218
unsigned int startInSpace_
Start index in space configuration.
Definition: joints.h:214
dart::dynamics::Joint * getJoint(WorldPtr world) const
Get the Dart joint from a world.
Definition: joint.cpp:54
unsigned int sizeInSpace_
Size of joint in space configuration.
Definition: joints.h:215
std::vector< std::string > dofs_
Controlled DoF names.
Definition: joints.h:209
ompl::RNG & rng_
Random number generator.
Definition: joints.h:206
WorldPtr getWorld()
Get underlying world.
Definition: space.cpp:373
ompl::RNG rng_
Random number generator.
Definition: space.h:266
T emplace_back(T... args)

◆ Joint() [2/2]

Joint::Joint ( StateSpace space,
dart::dynamics::Joint *  joint,
unsigned int  sizeInSpace,
unsigned int  startIndex = 0,
unsigned int  numDof = 0 
)

Constructor.

Parameters
[in]spaceState space this joint will be in.
[in]jointJoint in skeleton.
[in]sizeInSpaceNumber of DoFs in the state space.
[in]startIndexStarting index in a configuration vector.
[in]numDofNumber of DoFs this joint has in the skeleton.

Definition at line 43 of file joint.cpp.

45  : Joint(space, //
46  space->getWorld()->getSkeletonIndex(joint->getSkeleton()), //
47  joint->getJointIndexInSkeleton(), //
48  sizeInSpace, //
49  startIndex, //
50  (numDof) ? numDof : joint->getNumDofs())
51 {
52 }
Joint(StateSpace *space, unsigned int skelIndex, unsigned int jointIndex, unsigned int sizeInSpace, unsigned int startIndex, unsigned int numDof)
Constructor.
Definition: joint.cpp:15

Member Function Documentation

◆ distance()

virtual double robowflex::darts::Joint::distance ( const Eigen::Ref< const Eigen::VectorXd > &  a,
const Eigen::Ref< const Eigen::VectorXd > &  b 
) const
pure virtual

Compute the distance between two joint configurations.

Parameters
[in]aJoint configuration a.
[in]bJoint configuration b.
Returns
Distance between configurations.

Implemented in robowflex::darts::SO3Joint, robowflex::darts::SO2Joint, and robowflex::darts::RnJoint.

◆ enforceBounds()

virtual void robowflex::darts::Joint::enforceBounds ( Eigen::Ref< Eigen::VectorXd >  a) const
pure virtual

Enforce bounds on a joint configuration.

Parameters
[in,out]aJoint configuration to modify.

Implemented in robowflex::darts::SO3Joint, robowflex::darts::SO2Joint, and robowflex::darts::RnJoint.

◆ getDimension()

std::size_t Joint::getDimension ( ) const

Get the dimension of this joint.

Returns
The dimension of the joint.

Definition at line 90 of file joint.cpp.

91 {
92  return numDof_;
93 }

◆ getDofs()

const std::vector< std::string > & Joint::getDofs ( ) const

Get the names of the DoF in the skeleton for this joint.

Returns
Names of joint DoFs.

Definition at line 75 of file joint.cpp.

76 {
77  return dofs_;
78 }

◆ getIndices()

const std::vector< std::size_t > & Joint::getIndices ( ) const

Get the indices in the skeleton for this joint.

Returns
Indices of joint DoFs.

Definition at line 70 of file joint.cpp.

71 {
72  return indices_;
73 }

◆ getJoint()

dart::dynamics::Joint * Joint::getJoint ( WorldPtr  world) const

Get the Dart joint from a world.

Parameters
[in]worldWorld to get joint from.
Returns
Joint.

Definition at line 54 of file joint.cpp.

55 {
56  const auto &sim = world->getSimConst();
57  return sim->getSkeleton(skelIndex_)->getJoint(jointIndex_);
58 }

◆ getJointIndex()

std::size_t Joint::getJointIndex ( ) const

Get the index of the joint in the skeleton.

Returns
Joint index.

Definition at line 85 of file joint.cpp.

86 {
87  return jointIndex_;
88 }

◆ getJointState()

void Joint::getJointState ( WorldPtr  world,
Eigen::Ref< Eigen::VectorXd >  a 
) const
virtual

Get the state of the joint in world.

Parameters
[in]worldWorld to get joint state from.
[out]aJoint configuration to set.

Reimplemented in robowflex::darts::SO3Joint.

Definition at line 101 of file joint.cpp.

102 {
103  auto *joint = getJoint(std::move(world));
104  a = joint->getSkeleton()->getPositions(indices_);
105 }
T move(T... args)

◆ getLowerLimits()

Eigen::VectorXd Joint::getLowerLimits ( ) const
virtual

Get the lower limits of a joint.

Returns
The lower limits of the joint.

Definition at line 122 of file joint.cpp.

123 {
124  return space_->getLowerBound().segment(startInSpace_, sizeInSpace_);
125 }
Eigen::VectorXd getLowerBound() const
Get a vector of the lower joint bounds for the space.
Definition: space.cpp:474

◆ getMaximumExtent()

virtual double robowflex::darts::Joint::getMaximumExtent ( ) const
pure virtual

Get the maximum extent of this joint (maximum distance).

Returns
The maximum extent.

Implemented in robowflex::darts::SO3Joint, robowflex::darts::SO2Joint, and robowflex::darts::RnJoint.

◆ getSkeletonIndex()

std::size_t Joint::getSkeletonIndex ( ) const

Get the index of the skeleton for this joint in the world.

Returns
Skeleton index.

Definition at line 80 of file joint.cpp.

81 {
82  return skelIndex_;
83 }

◆ getSpaceVars()

Eigen::Ref< Eigen::VectorXd > Joint::getSpaceVars ( Eigen::Ref< Eigen::VectorXd >  a)

Gets the joint configuration (subvector of variables for this joint) from a configuration.

Parameters
[in]aConfiguration of the full space.
Returns
A vector of variables for this joint.

Definition at line 60 of file joint.cpp.

61 {
62  return a.segment(startInSpace_, sizeInSpace_);
63 }

◆ getSpaceVarsConst()

Eigen::Ref< const Eigen::VectorXd > Joint::getSpaceVarsConst ( const Eigen::Ref< const Eigen::VectorXd > &  a)

Gets the subvector of variables for this joint from a configuration.

Parameters
[in]aConfiguration of the full space.
Returns
A vector of variables for this joint.

Definition at line 65 of file joint.cpp.

66 {
67  return a.segment(startInSpace_, sizeInSpace_);
68 }

◆ getUpperLimits()

Eigen::VectorXd Joint::getUpperLimits ( ) const
virtual

Get the upper limits of a joint.

Returns
The upper limits of the joint.

Definition at line 117 of file joint.cpp.

118 {
119  return space_->getUpperBound().segment(startInSpace_, sizeInSpace_);
120 }
Eigen::VectorXd getUpperBound() const
Get a vector of the upper joint bounds for the space.
Definition: space.cpp:480

◆ interpolate()

virtual void robowflex::darts::Joint::interpolate ( const Eigen::Ref< const Eigen::VectorXd > &  a,
const Eigen::Ref< const Eigen::VectorXd > &  b,
double  t,
Eigen::Ref< Eigen::VectorXd >  c 
) const
pure virtual

Interpolate to a new configuration c which is t from a to b.

Parameters
[in]aJoint configuration a.
[in]bJoint configuration b.
[in]tAmount to interpolate.
[out]cInterpolated configuration.

Implemented in robowflex::darts::SO3Joint, robowflex::darts::SO2Joint, and robowflex::darts::RnJoint.

◆ sample()

virtual void robowflex::darts::Joint::sample ( Eigen::Ref< Eigen::VectorXd >  a) const
pure virtual

Sample a configuration for this joint.

Parameters
[out]aJoint configuration to sample.

Implemented in robowflex::darts::SO3Joint, robowflex::darts::SO2Joint, and robowflex::darts::RnJoint.

◆ sampleNear()

virtual void robowflex::darts::Joint::sampleNear ( Eigen::Ref< Eigen::VectorXd >  a,
const Eigen::Ref< const Eigen::VectorXd > &  near,
double  r 
) const
pure virtual

Sample a configuration for this joint near another configuration near.

Parameters
[out]aJoint configuration to sample.
[in]nearJoint configuration to sample near.
[in]rDistance from near to sample within.

Implemented in robowflex::darts::SO3Joint, robowflex::darts::SO2Joint, and robowflex::darts::RnJoint.

◆ satisfiesBounds()

virtual bool robowflex::darts::Joint::satisfiesBounds ( const Eigen::Ref< const Eigen::VectorXd > &  a) const
pure virtual

Check if a joint configuration satisfies bounds.

Parameters
[in,out]aJoint configuration to check.
Returns
True if configuration satisfies bounds, false otherwise.

Implemented in robowflex::darts::SO3Joint, robowflex::darts::SO2Joint, and robowflex::darts::RnJoint.

◆ setJointState()

void Joint::setJointState ( WorldPtr  world,
const Eigen::Ref< const Eigen::VectorXd > &  a 
) const
virtual

Set the state of the joint in world.

Parameters
[out]worldWorld to set joint state in.
[in]aJoint configuration to set.

Reimplemented in robowflex::darts::SO3Joint.

Definition at line 95 of file joint.cpp.

96 {
97  auto *joint = getJoint(std::move(world));
98  joint->getSkeleton()->setPositions(indices_, a);
99 }

◆ setLowerLimits()

void Joint::setLowerLimits ( const Eigen::Ref< const Eigen::VectorXd > &  v)
virtual

Set the lower limits of a joint.

Parameters
[in]vLower limits of the joint.

Reimplemented in robowflex::darts::RnJoint.

Definition at line 112 of file joint.cpp.

113 {
114  throw std::runtime_error("Cannot set bounds on this joint!");
115 }

◆ setUpperLimits()

void Joint::setUpperLimits ( const Eigen::Ref< const Eigen::VectorXd > &  v)
virtual

Set the upper limits of a joint.

Parameters
[in]vUpper limits of the joint.

Reimplemented in robowflex::darts::RnJoint.

Definition at line 107 of file joint.cpp.

108 {
109  throw std::runtime_error("Cannot set bounds on this joint!");
110 }

Member Data Documentation

◆ dofs_

std::vector<std::string> robowflex::darts::Joint::dofs_
protected

Controlled DoF names.

Definition at line 209 of file joints.h.

◆ indices_

std::vector<std::size_t> robowflex::darts::Joint::indices_
protected

Indices this joint corresponds to.

Definition at line 208 of file joints.h.

◆ jointIndex_

unsigned int robowflex::darts::Joint::jointIndex_
protected

Index of joint.

Definition at line 212 of file joints.h.

◆ numDof_

unsigned int robowflex::darts::Joint::numDof_
protected

Number of DoF this joint controls.

Definition at line 218 of file joints.h.

◆ rng_

ompl::RNG& robowflex::darts::Joint::rng_
protected

Random number generator.

Definition at line 206 of file joints.h.

◆ sizeInSpace_

unsigned int robowflex::darts::Joint::sizeInSpace_
protected

Size of joint in space configuration.

Definition at line 215 of file joints.h.

◆ skelIndex_

unsigned int robowflex::darts::Joint::skelIndex_
protected

Index of skeleton.

Definition at line 211 of file joints.h.

◆ space_

StateSpace* robowflex::darts::Joint::space_
protected

State space this joint is for.

Definition at line 205 of file joints.h.

◆ startIndex_

unsigned int robowflex::darts::Joint::startIndex_
protected

Start index in joint.

Definition at line 217 of file joints.h.

◆ startInSpace_

unsigned int robowflex::darts::Joint::startInSpace_
protected

Start index in space configuration.

Definition at line 214 of file joints.h.


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