Functions | |
double | distance2D (double ax, double ay, double bx, double by) |
double | distance2D (geometry_msgs::Point a, geometry_msgs::Point b=geometry_msgs::Point()) |
double | distance2D (geometry_msgs::Pose a, geometry_msgs::Pose b=geometry_msgs::Pose()) |
double | distance2D (const tf::Vector3 &a, const tf::Vector3 &b=tf::Vector3()) |
double | distance2D (const tf::Transform &a, const tf::Transform &b=tf::Transform()) |
double | distance2D (double x, double y) |
double | distance2D (const tf::Point &p) |
double | distance3D (double ax, double ay, double az, double bx, double by, double bz) |
double | distance3D (geometry_msgs::Point a, geometry_msgs::Point b=geometry_msgs::Point()) |
double | distance3D (geometry_msgs::Pose a, geometry_msgs::Pose b=geometry_msgs::Pose()) |
double | distance3D (const tf::Vector3 &a, const tf::Vector3 &b) |
double | distance3D (const tf::Transform &a, const tf::Transform &b) |
double | distance3D (double x, double y, double z) |
double | distance3D (const tf::Point &p) |
double | heading (geometry_msgs::Point p) |
double | heading (geometry_msgs::Pose p) |
double | heading (const tf::Vector3 &p) |
double | heading (const tf::Transform &t) |
double | heading (geometry_msgs::Point a, geometry_msgs::Point b) |
double | heading (geometry_msgs::Pose a, geometry_msgs::Pose b) |
double | heading (const tf::Vector3 &a, const tf::Vector3 &b) |
double | heading (const tf::Transform &a, const tf::Transform &b) |
template<typename T > | |
T | mean (const std::vector< T > &v) |
template<typename T > | |
T | median (const std::vector< T > &v) |
double | minAngle (geometry_msgs::Quaternion a, geometry_msgs::Quaternion b) |
double | minAngle (geometry_msgs::Pose a, geometry_msgs::Pose b) |
double | minAngle (const tf::Quaternion &a, const tf::Quaternion &b) |
double | minAngle (const tf::Transform &a, const tf::Transform &b) |
template<typename T > | |
std::string | nb2str (T x) |
double | pitch (const tf::Transform &tf) |
double | pitch (geometry_msgs::Pose pose) |
double | pitch (geometry_msgs::PoseStamped pose) |
ECL_DEPRECATED const char * | point2str (const geometry_msgs::Point &point) |
std::string | point2str2D (const geometry_msgs::Point &point) |
std::string | point2str2D (const geometry_msgs::PointStamped &point) |
std::string | point2str3D (const geometry_msgs::Point &point) |
std::string | point2str3D (const geometry_msgs::PointStamped &point) |
double | pointSegmentDistance (double px, double py, double s1x, double s1y, double s2x, double s2y) |
ECL_DEPRECATED const char * | pose2str (const geometry_msgs::Pose &pose) |
ECL_DEPRECATED const char * | pose2str (const geometry_msgs::PoseStamped &pose) |
std::string | pose2str2D (const geometry_msgs::Pose &pose) |
std::string | pose2str2D (const geometry_msgs::PoseStamped &pose) |
std::string | pose2str3D (const geometry_msgs::Pose &pose) |
std::string | pose2str3D (const geometry_msgs::PoseStamped &pose) |
void | pose2tf (const geometry_msgs::Pose &pose, tf::Transform &tf) |
void | pose2tf (const geometry_msgs::PoseStamped &pose, tf::StampedTransform &tf) |
bool | rayCircleIntersection (double rx, double ry, double cx, double cy, double radius, double &ix, double &iy, double &distance) |
bool | raySegmentIntersection (double r1x, double r1y, double r2x, double r2y, double s1x, double s1y, double s2x, double s2y, double &ix, double &iy, double &distance) |
double | roll (const tf::Transform &tf) |
double | roll (geometry_msgs::Pose pose) |
double | roll (geometry_msgs::PoseStamped pose) |
bool | sameFrame (const std::string &frame_a, const std::string &frame_b) |
bool | sameFrame (const geometry_msgs::PoseStamped &a, const geometry_msgs::PoseStamped &b) |
template<typename T > | |
T | sign (T x) |
template<typename T > | |
T | std_dev (const std::vector< T > &v) |
void | tf2pose (const tf::Transform &tf, geometry_msgs::Pose &pose) |
void | tf2pose (const tf::StampedTransform &tf, geometry_msgs::PoseStamped &pose) |
template<typename T > | |
T | variance (const std::vector< T > &v) |
std::string | vector2str3D (const geometry_msgs::Vector3 &vector) |
std::string | vector2str3D (const geometry_msgs::Vector3Stamped &vector) |
double | wrapAngle (double a) |
double | yaw (const tf::Transform &tf) |
double | yaw (geometry_msgs::Pose pose) |
double | yaw (geometry_msgs::PoseStamped pose) |
Variables | |
char | ___buffer___ [256] |
double mtk::distance2D | ( | double | ax, |
double | ay, | ||
double | bx, | ||
double | by | ||
) |
Euclidean distance between 2D points; z coordinate is ignored
a | point a |
b | point b |
Definition at line 88 of file geometry.cpp.
double mtk::distance2D | ( | geometry_msgs::Point | a, |
geometry_msgs::Point | b = geometry_msgs::Point() |
||
) |
Definition at line 98 of file geometry.cpp.
double mtk::distance2D | ( | geometry_msgs::Pose | a, |
geometry_msgs::Pose | b = geometry_msgs::Pose() |
||
) |
Definition at line 103 of file geometry.cpp.
double mtk::distance2D | ( | const tf::Vector3 & | a, |
const tf::Vector3 & | b = tf::Vector3() |
||
) |
Definition at line 93 of file geometry.cpp.
double mtk::distance2D | ( | const tf::Transform & | a, |
const tf::Transform & | b = tf::Transform() |
||
) |
Definition at line 108 of file geometry.cpp.
double mtk::distance2D | ( | double | x, |
double | y | ||
) |
Definition at line 78 of file geometry.cpp.
double mtk::distance2D | ( | const tf::Point & | p | ) |
Definition at line 83 of file geometry.cpp.
double mtk::distance3D | ( | double | ax, |
double | ay, | ||
double | az, | ||
double | bx, | ||
double | by, | ||
double | bz | ||
) |
Euclidean distance between 3D points
a | point a |
b | point b |
Definition at line 124 of file geometry.cpp.
double mtk::distance3D | ( | geometry_msgs::Point | a, |
geometry_msgs::Point | b = geometry_msgs::Point() |
||
) |
Definition at line 134 of file geometry.cpp.
double mtk::distance3D | ( | geometry_msgs::Pose | a, |
geometry_msgs::Pose | b = geometry_msgs::Pose() |
||
) |
Definition at line 139 of file geometry.cpp.
double mtk::distance3D | ( | const tf::Vector3 & | a, |
const tf::Vector3 & | b | ||
) |
Definition at line 129 of file geometry.cpp.
double mtk::distance3D | ( | const tf::Transform & | a, |
const tf::Transform & | b | ||
) |
Definition at line 144 of file geometry.cpp.
double mtk::distance3D | ( | double | x, |
double | y, | ||
double | z | ||
) |
Definition at line 114 of file geometry.cpp.
double mtk::distance3D | ( | const tf::Point & | p | ) |
Definition at line 119 of file geometry.cpp.
double mtk::heading | ( | geometry_msgs::Point | p | ) |
Heading angle from origin to point p
p | point p |
Definition at line 155 of file geometry.cpp.
double mtk::heading | ( | geometry_msgs::Pose | p | ) |
Definition at line 160 of file geometry.cpp.
double mtk::heading | ( | const tf::Vector3 & | p | ) |
Definition at line 150 of file geometry.cpp.
double mtk::heading | ( | const tf::Transform & | t | ) |
Definition at line 165 of file geometry.cpp.
double mtk::heading | ( | geometry_msgs::Point | a, |
geometry_msgs::Point | b | ||
) |
Heading angle from point a to point b
a | point a |
b | point b |
Definition at line 175 of file geometry.cpp.
double mtk::heading | ( | geometry_msgs::Pose | a, |
geometry_msgs::Pose | b | ||
) |
Definition at line 180 of file geometry.cpp.
double mtk::heading | ( | const tf::Vector3 & | a, |
const tf::Vector3 & | b | ||
) |
Definition at line 170 of file geometry.cpp.
double mtk::heading | ( | const tf::Transform & | a, |
const tf::Transform & | b | ||
) |
Definition at line 185 of file geometry.cpp.
T mtk::mean | ( | const std::vector< T > & | v | ) |
Definition at line 35 of file common.hpp.
T mtk::median | ( | const std::vector< T > & | v | ) |
Definition at line 28 of file common.hpp.
double mtk::minAngle | ( | geometry_msgs::Quaternion | a, |
geometry_msgs::Quaternion | b | ||
) |
Minimum angle between quaternions
a | quaternion a |
b | quaternion b |
Definition at line 195 of file geometry.cpp.
double mtk::minAngle | ( | geometry_msgs::Pose | a, |
geometry_msgs::Pose | b | ||
) |
Definition at line 200 of file geometry.cpp.
double mtk::minAngle | ( | const tf::Quaternion & | a, |
const tf::Quaternion & | b | ||
) |
Definition at line 190 of file geometry.cpp.
double mtk::minAngle | ( | const tf::Transform & | a, |
const tf::Transform & | b | ||
) |
Definition at line 205 of file geometry.cpp.
std::string mtk::nb2str | ( | T | x | ) |
Definition at line 23 of file common.hpp.
double mtk::pitch | ( | const tf::Transform & | tf | ) |
Shortcut to take the pitch of a transform/pose
tf/pose |
Definition at line 43 of file geometry.cpp.
double mtk::pitch | ( | geometry_msgs::Pose | pose | ) |
Definition at line 50 of file geometry.cpp.
double mtk::pitch | ( | geometry_msgs::PoseStamped | pose | ) |
Definition at line 57 of file geometry.cpp.
const char * mtk::point2str | ( | const geometry_msgs::Point & | point | ) |
Definition at line 48 of file common.cpp.
std::string mtk::point2str2D | ( | const geometry_msgs::Point & | point | ) |
Definition at line 77 of file common.cpp.
std::string mtk::point2str2D | ( | const geometry_msgs::PointStamped & | point | ) |
Definition at line 83 of file common.cpp.
std::string mtk::point2str3D | ( | const geometry_msgs::Point & | point | ) |
Definition at line 88 of file common.cpp.
std::string mtk::point2str3D | ( | const geometry_msgs::PointStamped & | point | ) |
Definition at line 94 of file common.cpp.
double mtk::pointSegmentDistance | ( | double | px, |
double | py, | ||
double | s1x, | ||
double | s1y, | ||
double | s2x, | ||
double | s2y | ||
) |
Minimum distance from a point to a line segment
px | point x-coordinate |
py | point y-coordinate |
s1x | segment's point 1 x-coordinate |
s1y | segment's point 1 y-coordinate |
s2x | segment's point 2 x-coordinate |
s2y | segment's point 2 y-coordinate |
Definition at line 236 of file geometry.cpp.
const char * mtk::pose2str | ( | const geometry_msgs::Pose & | pose | ) |
Definition at line 54 of file common.cpp.
const char * mtk::pose2str | ( | const geometry_msgs::PoseStamped & | pose | ) |
Definition at line 60 of file common.cpp.
std::string mtk::pose2str2D | ( | const geometry_msgs::Pose & | pose | ) |
Definition at line 99 of file common.cpp.
std::string mtk::pose2str2D | ( | const geometry_msgs::PoseStamped & | pose | ) |
Definition at line 105 of file common.cpp.
std::string mtk::pose2str3D | ( | const geometry_msgs::Pose & | pose | ) |
Definition at line 110 of file common.cpp.
std::string mtk::pose2str3D | ( | const geometry_msgs::PoseStamped & | pose | ) |
Definition at line 117 of file common.cpp.
void mtk::pose2tf | ( | const geometry_msgs::Pose & | pose, |
tf::Transform & | tf | ||
) |
Definition at line 31 of file common.cpp.
void mtk::pose2tf | ( | const geometry_msgs::PoseStamped & | pose, |
tf::StampedTransform & | tf | ||
) |
Definition at line 39 of file common.cpp.
bool mtk::rayCircleIntersection | ( | double | rx, |
double | ry, | ||
double | cx, | ||
double | cy, | ||
double | radius, | ||
double & | ix, | ||
double & | iy, | ||
double & | distance | ||
) |
Do a zero-centered, finite length ray intersects a circle?
rx | rays's end point x-coordinate |
ry | rays's end point y-coordinate |
cx | circle's center x-coordinate |
cy | circle's center y-coordinate |
radius | circle's radius |
ix | closest intersection point (if any) x-coordinate |
iy | closest intersection point (if any) y-coordinate |
distance | Distance from rays's start (zero) to intersection point |
Definition at line 286 of file geometry.cpp.
bool mtk::raySegmentIntersection | ( | double | r1x, |
double | r1y, | ||
double | r2x, | ||
double | r2y, | ||
double | s1x, | ||
double | s1y, | ||
double | s2x, | ||
double | s2y, | ||
double & | ix, | ||
double & | iy, | ||
double & | distance | ||
) |
Do a finite length ray intersects a line segment?
r1x | rays's start point x-coordinate |
r1y | rays's start point y-coordinate |
r2x | rays's end point x-coordinate |
r2y | rays's end point y-coordinate |
s1x | segment's point 1 x-coordinate |
s1y | segment's point 1 y-coordinate |
s2x | segment's point 2 x-coordinate |
s2y | segment's point 2 y-coordinate |
ix | intersection point (if any) x-coordinate |
iy | intersection point (if any) y-coordinate |
distance | Distance from rays's start to intersection point |
Definition at line 258 of file geometry.cpp.
double mtk::roll | ( | const tf::Transform & | tf | ) |
Shortcut to take the roll of a transform/pose
tf/pose |
Definition at line 24 of file geometry.cpp.
double mtk::roll | ( | geometry_msgs::Pose | pose | ) |
Definition at line 31 of file geometry.cpp.
double mtk::roll | ( | geometry_msgs::PoseStamped | pose | ) |
Definition at line 38 of file geometry.cpp.
bool mtk::sameFrame | ( | const std::string & | frame_a, |
const std::string & | frame_b | ||
) |
Compares frame ids ignoring the leading /, as it is frequently omitted.
frame_a | |
frame_b |
Definition at line 215 of file geometry.cpp.
bool mtk::sameFrame | ( | const geometry_msgs::PoseStamped & | a, |
const geometry_msgs::PoseStamped & | b | ||
) |
Definition at line 210 of file geometry.cpp.
T mtk::sign | ( | T | x | ) |
Definition at line 58 of file common.hpp.
T mtk::std_dev | ( | const std::vector< T > & | v | ) |
Definition at line 52 of file common.hpp.
void mtk::tf2pose | ( | const tf::Transform & | tf, |
geometry_msgs::Pose & | pose | ||
) |
Definition at line 16 of file common.cpp.
void mtk::tf2pose | ( | const tf::StampedTransform & | tf, |
geometry_msgs::PoseStamped & | pose | ||
) |
Definition at line 24 of file common.cpp.
T mtk::variance | ( | const std::vector< T > & | v | ) |
Definition at line 43 of file common.hpp.
std::string mtk::vector2str3D | ( | const geometry_msgs::Vector3 & | vector | ) |
Definition at line 66 of file common.cpp.
std::string mtk::vector2str3D | ( | const geometry_msgs::Vector3Stamped & | vector | ) |
Definition at line 72 of file common.cpp.
double mtk::wrapAngle | ( | double | a | ) |
Normalize an angle between -π and +π
a | Unnormalized angle |
Definition at line 16 of file geometry.cpp.
double mtk::yaw | ( | const tf::Transform & | tf | ) |
Shortcut to take the yaw of a transform/pose
tf/pose |
Definition at line 62 of file geometry.cpp.
double mtk::yaw | ( | geometry_msgs::Pose | pose | ) |
Definition at line 67 of file geometry.cpp.
double mtk::yaw | ( | geometry_msgs::PoseStamped | pose | ) |
Definition at line 72 of file geometry.cpp.
char mtk::___buffer___[256] |
Definition at line 46 of file common.cpp.