Robowflex  v0.1
Making MoveIt Easy
robowflex::darts::RnJoint Class Reference

A real vector joint of n dimensions. More...

#include <joints.h>

+ Inheritance diagram for robowflex::darts::RnJoint:

Public Member Functions

void setUpperLimits (const Eigen::Ref< const Eigen::VectorXd > &v) override
 Set the upper limits of a joint. More...
 
void setLowerLimits (const Eigen::Ref< const Eigen::VectorXd > &v) override
 Set the lower limits of a joint. More...
 
double distance (const Eigen::Ref< const Eigen::VectorXd > &a, const Eigen::Ref< const Eigen::VectorXd > &b) const override
 Compute the distance between two joint configurations. More...
 
double getMaximumExtent () const override
 Get the maximum extent of this joint (maximum distance). More...
 
void interpolate (const Eigen::Ref< const Eigen::VectorXd > &a, const Eigen::Ref< const Eigen::VectorXd > &b, double t, Eigen::Ref< Eigen::VectorXd > c) const override
 Interpolate to a new configuration c which is t from a to b. More...
 
void enforceBounds (Eigen::Ref< Eigen::VectorXd > a) const override
 Enforce bounds on a joint configuration. More...
 
bool satisfiesBounds (const Eigen::Ref< const Eigen::VectorXd > &a) const override
 Check if a joint configuration satisfies bounds. More...
 
void sample (Eigen::Ref< Eigen::VectorXd > a) const override
 Sample a configuration for this joint. More...
 
void sampleNear (Eigen::Ref< Eigen::VectorXd > a, const Eigen::Ref< const Eigen::VectorXd > &near, double r) const override
 Sample a configuration for this joint near another configuration near. More...
 
Constructors.
 RnJoint (StateSpace *space, dart::dynamics::Joint *joint, double low, double high)
 Constructor. More...
 
 RnJoint (StateSpace *space, dart::dynamics::Joint *joint, unsigned int n, unsigned int start, Eigen::VectorXd low, Eigen::VectorXd high)
 Constructor. More...
 
- Public Member Functions inherited from robowflex::darts::Joint
 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...
 
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...
 
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 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...
 

Private Attributes

Eigen::VectorXd low_
 Lower bounds. More...
 
Eigen::VectorXd high_
 Upper bounds. More...
 

Additional Inherited Members

- Protected Attributes inherited from robowflex::darts::Joint
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

A real vector joint of n dimensions.

Definition at line 223 of file joints.h.

Constructor & Destructor Documentation

◆ RnJoint() [1/2]

RnJoint::RnJoint ( StateSpace space,
dart::dynamics::Joint *  joint,
double  low,
double  high 
)

Constructor.

Parameters
[in]spaceState space.
[in]joint1-DoF joint to control.
[in]lowLower bound.
[in]highUpper bound.

RnJoint

Definition at line 12 of file rnjoint.cpp.

15  : RnJoint(space, joint, //
16  1, 0, //
17  Eigen::VectorXd::Constant(1, low), //
18  Eigen::VectorXd::Constant(1, high))
19 {
20 }
RnJoint(StateSpace *space, dart::dynamics::Joint *joint, double low, double high)
Constructor.
Definition: rnjoint.cpp:12

◆ RnJoint() [2/2]

RnJoint::RnJoint ( StateSpace space,
dart::dynamics::Joint *  joint,
unsigned int  n,
unsigned int  start,
Eigen::VectorXd  low,
Eigen::VectorXd  high 
)

Constructor.

Parameters
[in]spaceState space.
[in]jointn-DoF joint to control.
[in]nNumber of DoF.
[in]startWhich DoF to start controlling.
[in]lowLower bound.
[in]highUpper bound.

Definition at line 22 of file rnjoint.cpp.

26  : Joint(space, joint, n, start, n), low_(low), high_(high)
27 {
28  if (low_.size() != numDof_ or high_.size() != numDof_)
29  {
30  }
31 
32  for (unsigned int i = 0; i < numDof_; ++i)
33  space_->addDimension(low[i], high[i]);
34 }
StateSpace * space_
State space this joint is for.
Definition: joints.h:205
unsigned int numDof_
Number of DoF this joint controls.
Definition: joints.h:218
Joint(StateSpace *space, unsigned int skelIndex, unsigned int jointIndex, unsigned int sizeInSpace, unsigned int startIndex, unsigned int numDof)
Constructor.
Definition: joint.cpp:15
Eigen::VectorXd high_
Upper bounds.
Definition: joints.h:279
Eigen::VectorXd low_
Lower bounds.
Definition: joints.h:278

Member Function Documentation

◆ distance()

double RnJoint::distance ( const Eigen::Ref< const Eigen::VectorXd > &  a,
const Eigen::Ref< const Eigen::VectorXd > &  b 
) const
overridevirtual

Compute the distance between two joint configurations.

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

Implements robowflex::darts::Joint.

Definition at line 37 of file rnjoint.cpp.

39 {
40  return (a - b).lpNorm<1>();
41 }

◆ enforceBounds()

void RnJoint::enforceBounds ( Eigen::Ref< Eigen::VectorXd >  a) const
overridevirtual

Enforce bounds on a joint configuration.

Parameters
[in,out]aJoint configuration to modify.

Implements robowflex::darts::Joint.

Definition at line 56 of file rnjoint.cpp.

57 {
58  for (unsigned int i = 0; i < numDof_; ++i)
59  {
60  double &v = a[i];
61  v = (v < low_[i]) ? low_[i] : ((v > high_[i]) ? high_[i] : v);
62  }
63 }

◆ getMaximumExtent()

double RnJoint::getMaximumExtent ( ) const
overridevirtual

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

Returns
The maximum extent.

Implements robowflex::darts::Joint.

Definition at line 43 of file rnjoint.cpp.

44 {
45  return distance(low_, high_);
46 }
double distance(const Eigen::Ref< const Eigen::VectorXd > &a, const Eigen::Ref< const Eigen::VectorXd > &b) const override
Compute the distance between two joint configurations.
Definition: rnjoint.cpp:37

◆ interpolate()

void RnJoint::interpolate ( const Eigen::Ref< const Eigen::VectorXd > &  a,
const Eigen::Ref< const Eigen::VectorXd > &  b,
double  t,
Eigen::Ref< Eigen::VectorXd >  c 
) const
overridevirtual

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.

Implements robowflex::darts::Joint.

Definition at line 48 of file rnjoint.cpp.

52 {
53  c = a + t * (b - a);
54 }

◆ sample()

void RnJoint::sample ( Eigen::Ref< Eigen::VectorXd >  a) const
overridevirtual

Sample a configuration for this joint.

Parameters
[out]aJoint configuration to sample.

Implements robowflex::darts::Joint.

Definition at line 77 of file rnjoint.cpp.

78 {
79  for (unsigned int i = 0; i < numDof_; ++i)
80  a[i] = rng_.uniformReal(low_[i], high_[i]);
81 }
ompl::RNG & rng_
Random number generator.
Definition: joints.h:206

◆ sampleNear()

void RnJoint::sampleNear ( Eigen::Ref< Eigen::VectorXd >  a,
const Eigen::Ref< const Eigen::VectorXd > &  near,
double  r 
) const
overridevirtual

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.

Implements robowflex::darts::Joint.

Definition at line 83 of file rnjoint.cpp.

86 {
87  for (unsigned int i = 0; i < numDof_; ++i)
88  a[i] = rng_.uniformReal(near[i] - r, near[i] + r);
89 
90  enforceBounds(a);
91 }
void enforceBounds(Eigen::Ref< Eigen::VectorXd > a) const override
Enforce bounds on a joint configuration.
Definition: rnjoint.cpp:56

◆ satisfiesBounds()

bool RnJoint::satisfiesBounds ( const Eigen::Ref< const Eigen::VectorXd > &  a) const
overridevirtual

Check if a joint configuration satisfies bounds.

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

Implements robowflex::darts::Joint.

Definition at line 65 of file rnjoint.cpp.

66 {
67  for (unsigned int i = 0; i < numDof_; ++i)
68  {
69  const double &v = a[i];
70  if ((v < low_[i]) or (v > high_[i]))
71  return false;
72  }
73 
74  return true;
75 }

◆ setLowerLimits()

void RnJoint::setLowerLimits ( const Eigen::Ref< const Eigen::VectorXd > &  v)
overridevirtual

Set the lower limits of a joint.

Parameters
[in]vLower limits of the joint.

Reimplemented from robowflex::darts::Joint.

Definition at line 104 of file rnjoint.cpp.

105 {
106  if (v.size() != low_.size())
107  throw std::runtime_error("Incorrect size for limits!");
108 
109  low_ = v;
110 
111  for (std::size_t i = 0; i < sizeInSpace_; ++i)
112  space_->bounds_.setLow(startInSpace_ + i, low_[i]);
113 }
unsigned int startInSpace_
Start index in space configuration.
Definition: joints.h:214
unsigned int sizeInSpace_
Size of joint in space configuration.
Definition: joints.h:215

◆ setUpperLimits()

void RnJoint::setUpperLimits ( const Eigen::Ref< const Eigen::VectorXd > &  v)
overridevirtual

Set the upper limits of a joint.

Parameters
[in]vUpper limits of the joint.

Reimplemented from robowflex::darts::Joint.

Definition at line 93 of file rnjoint.cpp.

94 {
95  if (v.size() != high_.size())
96  throw std::runtime_error("Incorrect size for limits!");
97 
98  high_ = v;
99 
100  for (std::size_t i = 0; i < sizeInSpace_; ++i)
101  space_->bounds_.setHigh(startInSpace_ + i, high_[i]);
102 }

Member Data Documentation

◆ high_

Eigen::VectorXd robowflex::darts::RnJoint::high_
private

Upper bounds.

Definition at line 279 of file joints.h.

◆ low_

Eigen::VectorXd robowflex::darts::RnJoint::low_
private

Lower bounds.

Definition at line 278 of file joints.h.


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