#include <GeometryHelper.hpp>
Static Public Member Functions | |
static PointPtr | applyQuatAndRadiusToPose (const PosePtr &pose, const QuaternionPtr &quat, double radius) |
static bool | checkIfDoubleNaN (double &c) |
static VoteSpecifierPtr | createVoteSpecifier (const PosePtr &sourcePose, const PosePtr &refPose) |
static double | deg2rad (double deg) |
static QuaternionPtr | eigenQuatToQuat (const Eigen::Quaternion< double > &q) |
static double | getAngleBetweenAxes (const Eigen::Vector3d &v1, const Eigen::Vector3d &v2) |
static double | getAngleBetweenQuats (const QuaternionPtr &q1, const QuaternionPtr &q2) |
static QuaternionPtr | getAveragePose (const std::vector< QuaternionPtr > &poseQuats) |
static Eigen::Vector3d | getAxisFromQuat (const QuaternionPtr &quat, const Eigen::Vector3d &viewport=Eigen::Vector3d::UnitX()) |
static Eigen::Vector3d | getDirectionVector (const PosePtr &first, const PosePtr &second) |
static double | getDistanceBetweenPoints (const PointPtr &p1, const PointPtr &p2) |
static bool | getNextCombination (const std::vector< unsigned int >::iterator first, std::vector< unsigned int >::iterator k, const std::vector< unsigned int >::iterator last) |
static PosePtr | getPoseFromVote (const PosePtr &source, const VoteSpecifierPtr &vote) |
static QuaternionPtr | getQuatFromRPY (const QuaternionPtr &q, const double alpha, const double beta, const double gamma) |
static PosePtr | getReferencePose (const PosePtr &source, const PointPtr &refPoint, const QuaternionPtr &objectToRefPoseQuat) |
static void | getReferencePose (const PosePtr &source, const PointPtr &refPoint, const QuaternionPtr &objectToRefPoseQuat, PosePtr &result) |
static PointPtr | getSourcePoint (const PosePtr &refPose, const QuaternionPtr &refToObjectQuat, double radius) |
static void | getSourcePoint (const PosePtr &refPose, const QuaternionPtr &refToObjectQuat, double radius, PointPtr &result) |
static PosePtr | getSourcePose (const PosePtr &reference, const PointPtr &sourcePoint, const QuaternionPtr &refToObjectPoseQuat) |
static void | getSourcePose (const PosePtr &reference, const PointPtr &sourcePoint, const QuaternionPtr &refToObjectPoseQuat, PosePtr &result) |
static double | getSquaredDistanceBetweenPoints (const PointPtr &p1, const PointPtr &p2) |
static bool | isSelfVote (const VoteSpecifierPtr &vote) |
static QuaternionPtr | normalize (const QuaternionPtr &quat) |
static bool | pointEqual (const PointPtr &p1, const PointPtr &p2) |
static Eigen::Vector3d | pointToVector (const PointPtr &p) |
static bool | poseEqual (const PosePtr &p1, const PosePtr &p2) |
static bool | quatEqual (const QuaternionPtr &q1, const QuaternionPtr &q2) |
static bool | quatEqual (const Quaternion &q1, const Quaternion &q2) |
static Eigen::Quaternion< double > | quatToEigenQuat (const QuaternionPtr &q) |
static double | rad2deg (double rad) |
static bool | sharedNeighborhoodEvaluation (const PosePtr &p1, const PosePtr &p2, double distanceNeighbourThreshold, double angleNeighbourThreshold) |
static Eigen::Quaternion< double > | vectorRotationToEigenQuat (const Eigen::Vector3d &v1, const Eigen::Vector3d &v2) |
static PointPtr | vectorToPoint (const Eigen::Vector3d &v) |
Static Public Attributes | |
static double constexpr | epsylon = 1e-4 |
static Quaternion | selfQuat = Quaternion() |
Definition at line 28 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 88 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 325 of file GeometryHelper.hpp.
|
inlinestatic |
Pose related methods
Definition at line 112 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 321 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 206 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 223 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 214 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 265 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 218 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 155 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 182 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 277 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 144 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 252 of file GeometryHelper.hpp.
|
inlinestatic |
Voting related methods Calculates an absolute pose at refPoint based on a relative orientation refToSourceQuat towards source.
source | Absolute position in refPoint has been calculated be combining source and the relative position of refPoint towards source. |
refPoint | Absolute position for which we want to calculate the corresponding orientation. |
refToSourceQuat | Relative orientation of searched absolute pose relative to source. |
Definition at line 43 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 50 of file GeometryHelper.hpp.
|
inlinestatic |
Calculate an absolute position by combining refPose and a relative position vector composed of refToObjectQuat and radius.
refPose | Absolute position that is combined with relative pose. |
refToObjectQuat | Orientation of Eigen::Vector3d connecting refPose and position being searched for. |
radius | Length of Eigen::Vector3d connecting refPose and position being searched for. |
Definition at line 63 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 70 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 76 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 83 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 187 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 100 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 210 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 192 of file GeometryHelper.hpp.
|
inlinestatic |
Point related methods
Definition at line 174 of file GeometryHelper.hpp.
Definition at line 150 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 233 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 238 of file GeometryHelper.hpp.
|
inlinestatic |
Quaternion related methods
Definition at line 202 of file GeometryHelper.hpp.
|
inlinestatic |
Various geometry related helpers
Definition at line 317 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 163 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 246 of file GeometryHelper.hpp.
|
inlinestatic |
Definition at line 178 of file GeometryHelper.hpp.
|
static |
Definition at line 99 of file GeometryHelper.hpp.
|
static |
Definition at line 98 of file GeometryHelper.hpp.