|
Robowflex
v0.1
Making MoveIt Easy
|
The specification of a TSR. More...
#include <tsr.h>
Public Member Functions | |
Constructors | |
| Specification ()=default | |
| Default constructor. More... | |
| Specification (const std::string &structure, const std::string &target_frame, const Eigen::Ref< const Eigen::Vector3d > &position, const Eigen::Quaterniond &rotation) | |
| Constructor for basic pose TSR constrained in world frame. More... | |
| void | setTarget (const std::string &structure, const std::string &frame) |
| Setting TSR Frame. More... | |
| void | setBase (const std::string &structure, const std::string &frame) |
| Set the base frame. More... | |
| void | setFrame (const std::string &structure, const std::string &target, const std::string &base=magic::ROOT_FRAME) |
| Set the base and target frame. More... | |
| void | addSuffix (const std::string &suffix) |
| Add a suffix to the structures for the target and base frame. More... | |
| void | setPosition (const Eigen::Ref< const Eigen::Vector3d > &position) |
| Setting TSR Pose. More... | |
| void | setPosition (double x, double y, double z) |
| Set the position of the TSR. More... | |
| void | setRotation (const Eigen::Quaterniond &orientation) |
| Set the rotation of the TSR. More... | |
| void | setRotation (double w, double x, double y, double z) |
| Set the rotation of the TSR as a quaternion. More... | |
| void | setRotation (double x, double y, double z) |
| Set the rotation of the TSR as XYZ Euler angles. More... | |
| void | setPose (const RobotPose &other) |
| Set the pose of the TSR. More... | |
| void | setPose (const Eigen::Ref< const Eigen::Vector3d > &position, const Eigen::Quaterniond &rotation) |
| Set the pose of the TSR. More... | |
| void | setPose (double xp, double yp, double zp, double wr, double xr, double yr, double zr) |
| Set the pose of the TSR. More... | |
| void | setPoseFromWorld (const WorldPtr &world) |
| Set the pose of the TSR for the desired frame in a provided world. Uses world's current configuration. More... | |
| void | setXPosTolerance (double bound) |
| Setting Position Tolerances. More... | |
| void | setYPosTolerance (double bound) |
| Set the Y position tolerance to (-bound, bound). More... | |
| void | setZPosTolerance (double bound) |
| Set the Z position tolerance to (-bound, bound). More... | |
| void | setXPosTolerance (double lower, double upper) |
| Set the X position tolerance to (lower, upper). More... | |
| void | setYPosTolerance (double lower, double upper) |
| Set the Y position tolerance to (lower, upper). More... | |
| void | setZPosTolerance (double lower, double upper) |
| Set the Z position tolerance to (lower, upper). More... | |
| void | setNoXPosTolerance () |
| Set no position tolerance on the X-axis. More... | |
| void | setNoYPosTolerance () |
| Set no position tolerance on the Y-axis. More... | |
| void | setNoZPosTolerance () |
| Set no position tolerance on the Z-axis. More... | |
| void | setNoPosTolerance () |
| Set no position tolerance at all. More... | |
| void | setXRotTolerance (double bound) |
| Setting Orientation Tolerances. More... | |
| void | setYRotTolerance (double bound) |
| Set the Y orientation tolerance to (-bound, bound). More... | |
| void | setZRotTolerance (double bound) |
| Set the Z orientation tolerance to (-bound, bound). More... | |
| void | setXRotTolerance (double lower, double upper) |
| Set the X orientation tolerance to (lower, upper). More... | |
| void | setYRotTolerance (double lower, double upper) |
| Set the Y orientation tolerance to (lower, upper). More... | |
| void | setZRotTolerance (double lower, double upper) |
| Set the Z orientation tolerance to (lower, upper). More... | |
| void | setNoXRotTolerance () |
| Set no orientation tolerance on the X-axis. More... | |
| void | setNoYRotTolerance () |
| Set no orientation tolerance on the Y-axis. More... | |
| void | setNoZRotTolerance () |
| Set no orientation tolerance on the Z-axis. More... | |
| void | setNoRotTolerance () |
| Set no orientation tolerance at all. More... | |
| Eigen::Vector3d | getPosition () const |
| Getters and Informative Methods. More... | |
| Eigen::Quaterniond | getRotation () const |
| Get the current desired orientation. More... | |
| Eigen::Vector3d | getEulerRotation () const |
| Get the current desired orientation. More... | |
| bool | isPositionConstrained () const |
| Returns true if TSR is position constrained. More... | |
| bool | isRotationConstrained () const |
| Returns true if TSR is orientation constrained. More... | |
| bool | isRelative () const |
| Returns true if TSR is a relative reference frame (not the world). More... | |
| void | print (std::ostream &out) const |
| Print out this TSR information. More... | |
| bool | intersect (const Specification &other) |
| Operations. More... | |
Public Attributes | |
| struct { | |
| std::string structure | |
| Structure target frame is in. More... | |
| std::string frame | |
| Name of target frame. More... | |
| } | target |
| Target frame. More... | |
| struct { | |
| std::string structure | |
| Structure base frame is in. More... | |
| std::string frame {magic::ROOT_FRAME} | |
| Name of base frame. More... | |
| } | base |
| Base frame. More... | |
| RobotPose | pose {RobotPose::Identity()} |
| Pose of TSR. More... | |
| struct { | |
| ROBOWFLEX_EIGEN Eigen::Vector3d upper {magic::DEFAULT_IK_TOLERANCES} | |
| Upper position tolerance. More... | |
| Eigen::Vector3d lower {-magic::DEFAULT_IK_TOLERANCES} | |
| Lower position tolerance. More... | |
| } | position |
| Position tolerances. More... | |
| struct { | |
| ROBOWFLEX_EIGEN Eigen::Vector3d upper {magic::DEFAULT_IK_TOLERANCES} | |
| Upper orientation tolerance. More... | |
| Eigen::Vector3d lower {-magic::DEFAULT_IK_TOLERANCES} | |
| Lower orientation tolerance. More... | |
| } | orientation |
| Orientation tolerances. More... | |
| std::size_t | dimension {6} |
| Number of constrained dimensions. More... | |
| std::vector< bool > | indices {std::vector<bool>(6, true)} |
| Vector of active constraints. If an index is true, that constraint is active. Ordered by X-, Y-, Z- orientation constraints, then X-, Y-, Z- position. More... | |
| std::size_t | maxIter {50} |
| Maximum iterations for solver. More... | |
| double | tolerance {magic::DEFAULT_IK_TOLERANCE} |
| Tolerance on solution for solver. More... | |
Private Member Functions | |
| void | fixBounds () |
| Fixes bounds so they are correct. More... | |
| std::size_t | getDimension () const |
| Compute and return constraint dimension of the TSR. More... | |
| bool | isPosConstrained (double lower, double upper) const |
| Checks if two values correspond to a position constraint. More... | |
| bool | isRotConstrained (double lower, double upper) const |
| Checks if two values correspond to a orientation constraint. More... | |
|
default |
Default constructor.
| TSR::Specification::Specification | ( | const std::string & | structure, |
| const std::string & | target_frame, | ||
| const Eigen::Ref< const Eigen::Vector3d > & | position, | ||
| const Eigen::Quaterniond & | rotation | ||
| ) |
Constructor for basic pose TSR constrained in world frame.
| [in] | structure | Structure TSR is on (both target and base frames). |
| [in] | target_frame | Target frame. |
| [in] | position | Desired position. |
| [in] | rotation | Desired orientation. |
Definition at line 25 of file tsr.cpp.
| void TSR::Specification::addSuffix | ( | const std::string & | suffix | ) |
Add a suffix to the structures for the target and base frame.
| [in] | suffix | Suffix to add to structures in target and base frame. |
Definition at line 58 of file tsr.cpp.
|
private |
|
private |
| Eigen::Vector3d TSR::Specification::getEulerRotation | ( | ) | const |
Get the current desired orientation.
Definition at line 321 of file tsr.cpp.
| Eigen::Vector3d TSR::Specification::getPosition | ( | ) | const |
| Eigen::Quaterniond TSR::Specification::getRotation | ( | ) | const |
| bool TSR::Specification::intersect | ( | const Specification & | other | ) |
Operations.
Compute the intersection of this TSR with the other.
Definition at line 326 of file tsr.cpp.
|
private |
Checks if two values correspond to a position constraint.
| bool TSR::Specification::isPositionConstrained | ( | ) | const |
| bool TSR::Specification::isRelative | ( | ) | const |
| bool TSR::Specification::isRotationConstrained | ( | ) | const |
|
private |
| void TSR::Specification::print | ( | std::ostream & | out | ) | const |
Print out this TSR information.
| [in] | out | Output stream. |
Definition at line 425 of file tsr.cpp.
| void TSR::Specification::setBase | ( | const std::string & | structure, |
| const std::string & | frame | ||
| ) |
| void TSR::Specification::setFrame | ( | const std::string & | structure, |
| const std::string & | target, | ||
| const std::string & | base = magic::ROOT_FRAME |
||
| ) |
Set the base and target frame.
| [in] | structure | Structure frames are in. |
| [in] | target | Target frame name. |
| [in] | base | Base frame name. |
| void TSR::Specification::setNoPosTolerance | ( | ) |
Set no position tolerance at all.
Definition at line 233 of file tsr.cpp.
| void TSR::Specification::setNoRotTolerance | ( | ) |
Set no orientation tolerance at all.
Definition at line 255 of file tsr.cpp.
| void TSR::Specification::setNoXPosTolerance | ( | ) |
Set no position tolerance on the X-axis.
Definition at line 218 of file tsr.cpp.
| void TSR::Specification::setNoXRotTolerance | ( | ) |
Set no orientation tolerance on the X-axis.
Definition at line 240 of file tsr.cpp.
| void TSR::Specification::setNoYPosTolerance | ( | ) |
Set no position tolerance on the Y-axis.
Definition at line 223 of file tsr.cpp.
| void TSR::Specification::setNoYRotTolerance | ( | ) |
Set no orientation tolerance on the Y-axis.
Definition at line 245 of file tsr.cpp.
| void TSR::Specification::setNoZPosTolerance | ( | ) |
Set no position tolerance on the Z-axis.
Definition at line 228 of file tsr.cpp.
| void TSR::Specification::setNoZRotTolerance | ( | ) |
Set no orientation tolerance on the Z-axis.
Definition at line 250 of file tsr.cpp.
| void TSR::Specification::setPose | ( | const Eigen::Ref< const Eigen::Vector3d > & | position, |
| const Eigen::Quaterniond & | rotation | ||
| ) |
Set the pose of the TSR.
| [in] | position | Desired position. |
| [in] | rotation | Desired rotation. |
Definition at line 98 of file tsr.cpp.
| void TSR::Specification::setPose | ( | const RobotPose & | other | ) |
| void TSR::Specification::setPose | ( | double | xp, |
| double | yp, | ||
| double | zp, | ||
| double | wr, | ||
| double | xr, | ||
| double | yr, | ||
| double | zr | ||
| ) |
Set the pose of the TSR.
| [in] | xp | X-coordinate of position. |
| [in] | yp | Y-coordinate of position. |
| [in] | zp | Z-coordinate of position. |
| [in] | wr | W-component of quaternion. |
| [in] | xr | X-component of quaternion. |
| [in] | yr | Y-component of quaternion. |
| [in] | zr | Z-component of quaternion. |
| void TSR::Specification::setPoseFromWorld | ( | const WorldPtr & | world | ) |
| void TSR::Specification::setPosition | ( | const Eigen::Ref< const Eigen::Vector3d > & | position | ) |
| void TSR::Specification::setPosition | ( | double | x, |
| double | y, | ||
| double | z | ||
| ) |
Set the position of the TSR.
| [in] | x | X-coordinate. |
| [in] | y | Y-coordinate. |
| [in] | z | Z-coordinate. |
| void TSR::Specification::setRotation | ( | const Eigen::Quaterniond & | orientation | ) |
Set the rotation of the TSR.
| [in] | orientation | Desired quaternion. |
| void TSR::Specification::setRotation | ( | double | w, |
| double | x, | ||
| double | y, | ||
| double | z | ||
| ) |
Set the rotation of the TSR as a quaternion.
| [in] | w | W-component of quaternion. |
| [in] | x | X-component of quaternion. |
| [in] | y | Y-component of quaternion. |
| [in] | z | Z-component of quaternion. |
| void TSR::Specification::setRotation | ( | double | x, |
| double | y, | ||
| double | z | ||
| ) |
| void TSR::Specification::setTarget | ( | const std::string & | structure, |
| const std::string & | frame | ||
| ) |
| void TSR::Specification::setXPosTolerance | ( | double | bound | ) |
Setting Position Tolerances.
Set the X position tolerance to (-bound, bound).
| [in] | bound | Bound to set. |
| void TSR::Specification::setXPosTolerance | ( | double | lower, |
| double | upper | ||
| ) |
Set the X position tolerance to (lower, upper).
| [in] | lower | Lower bound. |
| [in] | upper | Upper bound. |
Definition at line 143 of file tsr.cpp.
| void TSR::Specification::setXRotTolerance | ( | double | bound | ) |
Setting Orientation Tolerances.
Set the X orientation tolerance to (-bound, bound).
| [in] | bound | Bound to set. |
| void TSR::Specification::setXRotTolerance | ( | double | lower, |
| double | upper | ||
| ) |
| void TSR::Specification::setYPosTolerance | ( | double | bound | ) |
Set the Y position tolerance to (-bound, bound).
| [in] | bound | Bound to set. |
| void TSR::Specification::setYPosTolerance | ( | double | lower, |
| double | upper | ||
| ) |
Set the Y position tolerance to (lower, upper).
| [in] | lower | Lower bound. |
| [in] | upper | Upper bound. |
| void TSR::Specification::setYRotTolerance | ( | double | bound | ) |
Set the Y orientation tolerance to (-bound, bound).
| [in] | bound | Bound to set. |
| void TSR::Specification::setYRotTolerance | ( | double | lower, |
| double | upper | ||
| ) |
| void TSR::Specification::setZPosTolerance | ( | double | bound | ) |
Set the Z position tolerance to (-bound, bound).
| [in] | bound | Bound to set. |
| void TSR::Specification::setZPosTolerance | ( | double | lower, |
| double | upper | ||
| ) |
Set the Z position tolerance to (lower, upper).
| [in] | lower | Lower bound. |
| [in] | upper | Upper bound. |
| void TSR::Specification::setZRotTolerance | ( | double | bound | ) |
Set the Z orientation tolerance to (-bound, bound).
| [in] | bound | Bound to set. |
| void TSR::Specification::setZRotTolerance | ( | double | lower, |
| double | upper | ||
| ) |
| struct { ... } robowflex::darts::TSR::Specification::base |
Base frame.
| std::size_t robowflex::darts::TSR::Specification::dimension {6} |
| std::string robowflex::darts::TSR::Specification::frame {magic::ROOT_FRAME} |
| std::vector<bool> robowflex::darts::TSR::Specification::indices {std::vector<bool>(6, true)} |
| Eigen::Vector3d robowflex::darts::TSR::Specification::lower {-magic::DEFAULT_IK_TOLERANCES} |
| std::size_t robowflex::darts::TSR::Specification::maxIter {50} |
| struct { ... } robowflex::darts::TSR::Specification::orientation |
Orientation tolerances.
| RobotPose robowflex::darts::TSR::Specification::pose {RobotPose::Identity()} |
| struct { ... } robowflex::darts::TSR::Specification::position |
Position tolerances.
| std::string robowflex::darts::TSR::Specification::structure |
| ROBOWFLEX_EIGEN { ... } robowflex::darts::TSR::Specification::target |
Target frame.
| double robowflex::darts::TSR::Specification::tolerance {magic::DEFAULT_IK_TOLERANCE} |
| ROBOWFLEX_EIGEN Eigen::Vector3d robowflex::darts::TSR::Specification::upper {magic::DEFAULT_IK_TOLERANCES} |