Robowflex
v0.1
Making MoveIt Easy
|
A real vector joint of n dimensions. More...
#include <joints.h>
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 | |
StateSpace * | space_ |
State space this joint is for. More... | |
ompl::RNG & | rng_ |
Random number generator. More... | |
std::vector< std::size_t > | indices_ |
Indices this joint corresponds to. More... | |
std::vector< std::string > | dofs_ |
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... | |
RnJoint::RnJoint | ( | StateSpace * | space, |
dart::dynamics::Joint * | joint, | ||
double | low, | ||
double | high | ||
) |
Constructor.
[in] | space | State space. |
[in] | joint | 1-DoF joint to control. |
[in] | low | Lower bound. |
[in] | high | Upper bound. |
Definition at line 12 of file rnjoint.cpp.
RnJoint::RnJoint | ( | StateSpace * | space, |
dart::dynamics::Joint * | joint, | ||
unsigned int | n, | ||
unsigned int | start, | ||
Eigen::VectorXd | low, | ||
Eigen::VectorXd | high | ||
) |
Constructor.
[in] | space | State space. |
[in] | joint | n-DoF joint to control. |
[in] | n | Number of DoF. |
[in] | start | Which DoF to start controlling. |
[in] | low | Lower bound. |
[in] | high | Upper bound. |
Definition at line 22 of file rnjoint.cpp.
|
overridevirtual |
Compute the distance between two joint configurations.
Implements robowflex::darts::Joint.
Definition at line 37 of file rnjoint.cpp.
|
overridevirtual |
Enforce bounds on a joint configuration.
[in,out] | a | Joint configuration to modify. |
Implements robowflex::darts::Joint.
Definition at line 56 of file rnjoint.cpp.
|
overridevirtual |
Get the maximum extent of this joint (maximum distance).
Implements robowflex::darts::Joint.
Definition at line 43 of file rnjoint.cpp.
|
overridevirtual |
Interpolate to a new configuration c which is t from a to b.
[in] | a | Joint configuration a. |
[in] | b | Joint configuration b. |
[in] | t | Amount to interpolate. |
[out] | c | Interpolated configuration. |
Implements robowflex::darts::Joint.
Definition at line 48 of file rnjoint.cpp.
|
overridevirtual |
Sample a configuration for this joint.
[out] | a | Joint configuration to sample. |
Implements robowflex::darts::Joint.
Definition at line 77 of file rnjoint.cpp.
|
overridevirtual |
Sample a configuration for this joint near another configuration near.
[out] | a | Joint configuration to sample. |
[in] | near | Joint configuration to sample near. |
[in] | r | Distance from near to sample within. |
Implements robowflex::darts::Joint.
Definition at line 83 of file rnjoint.cpp.
|
overridevirtual |
Check if a joint configuration satisfies bounds.
[in,out] | a | Joint configuration to check. |
Implements robowflex::darts::Joint.
Definition at line 65 of file rnjoint.cpp.
|
overridevirtual |
Set the lower limits of a joint.
[in] | v | Lower limits of the joint. |
Reimplemented from robowflex::darts::Joint.
Definition at line 104 of file rnjoint.cpp.
|
overridevirtual |
Set the upper limits of a joint.
[in] | v | Upper limits of the joint. |
Reimplemented from robowflex::darts::Joint.
Definition at line 93 of file rnjoint.cpp.
|
private |
|
private |