|
Robowflex
v0.1
Making MoveIt Easy
|
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 | |
| 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... | |
Abstract controllable joint for robowflex::darts::StateSpace.
| Joint::Joint | ( | StateSpace * | space, |
| unsigned int | skelIndex, | ||
| unsigned int | jointIndex, | ||
| unsigned int | sizeInSpace, | ||
| unsigned int | startIndex, | ||
| unsigned int | numDof | ||
| ) |
Constructor.
| [in] | space | State space this joint will be in. |
| [in] | skelIndex | Index of the skeleton this joint is in. |
| [in] | jointIndex | Index of joint in skeleton. |
| [in] | sizeInSpace | Number of DoFs in the state space. |
| [in] | startIndex | Starting index in a configuration vector. |
| [in] | numDof | Number of DoFs this joint has in the skeleton. |
Definition at line 15 of file joint.cpp.
| Joint::Joint | ( | StateSpace * | space, |
| dart::dynamics::Joint * | joint, | ||
| unsigned int | sizeInSpace, | ||
| unsigned int | startIndex = 0, |
||
| unsigned int | numDof = 0 |
||
| ) |
Constructor.
| [in] | space | State space this joint will be in. |
| [in] | joint | Joint in skeleton. |
| [in] | sizeInSpace | Number of DoFs in the state space. |
| [in] | startIndex | Starting index in a configuration vector. |
| [in] | numDof | Number of DoFs this joint has in the skeleton. |
Definition at line 43 of file joint.cpp.
|
pure virtual |
Compute the distance between two joint configurations.
Implemented in robowflex::darts::SO3Joint, robowflex::darts::SO2Joint, and robowflex::darts::RnJoint.
|
pure virtual |
Enforce bounds on a joint configuration.
| [in,out] | a | Joint configuration to modify. |
Implemented in robowflex::darts::SO3Joint, robowflex::darts::SO2Joint, and robowflex::darts::RnJoint.
| std::size_t Joint::getDimension | ( | ) | const |
| const std::vector< std::string > & Joint::getDofs | ( | ) | const |
| const std::vector< std::size_t > & Joint::getIndices | ( | ) | const |
| dart::dynamics::Joint * Joint::getJoint | ( | WorldPtr | world | ) | const |
| std::size_t Joint::getJointIndex | ( | ) | const |
Get the index of the joint in the skeleton.
|
virtual |
Get the state of the joint in world.
Reimplemented in robowflex::darts::SO3Joint.
|
virtual |
Get the lower limits of a joint.
Definition at line 122 of file joint.cpp.
|
pure virtual |
Get the maximum extent of this joint (maximum distance).
Implemented in robowflex::darts::SO3Joint, robowflex::darts::SO2Joint, and robowflex::darts::RnJoint.
| std::size_t Joint::getSkeletonIndex | ( | ) | const |
Get the index of the skeleton for this joint in the world.
| Eigen::Ref< Eigen::VectorXd > Joint::getSpaceVars | ( | Eigen::Ref< Eigen::VectorXd > | a | ) |
Gets the joint configuration (subvector of variables for this joint) from a configuration.
| [in] | a | Configuration of the full space. |
| 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.
| [in] | a | Configuration of the full space. |
|
virtual |
Get the upper limits of a joint.
Definition at line 117 of file joint.cpp.
|
pure virtual |
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. |
Implemented in robowflex::darts::SO3Joint, robowflex::darts::SO2Joint, and robowflex::darts::RnJoint.
|
pure virtual |
Sample a configuration for this joint.
| [out] | a | Joint configuration to sample. |
Implemented in robowflex::darts::SO3Joint, robowflex::darts::SO2Joint, and robowflex::darts::RnJoint.
|
pure virtual |
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. |
Implemented in robowflex::darts::SO3Joint, robowflex::darts::SO2Joint, and robowflex::darts::RnJoint.
|
pure virtual |
Check if a joint configuration satisfies bounds.
| [in,out] | a | Joint configuration to check. |
Implemented in robowflex::darts::SO3Joint, robowflex::darts::SO2Joint, and robowflex::darts::RnJoint.
|
virtual |
Set the state of the joint in world.
Reimplemented in robowflex::darts::SO3Joint.
|
virtual |
Set the lower limits of a joint.
| [in] | v | Lower limits of the joint. |
Reimplemented in robowflex::darts::RnJoint.
|
virtual |
Set the upper limits of a joint.
| [in] | v | Upper limits of the joint. |
Reimplemented in robowflex::darts::RnJoint.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |