Functions | Variables
mtk Namespace Reference

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 a, geometry_msgs::Point b=geometry_msgs::Point())
double heading (geometry_msgs::Pose a, geometry_msgs::Pose b=geometry_msgs::Pose())
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)
const char * point2str (const geometry_msgs::Point &point)
double pointSegmentDistance (double px, double py, double s1x, double s1y, double s2x, double s2y)
const char * pose2str (const geometry_msgs::Pose &pose)
const char * pose2str (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)
double wrapAngle (double a)

Variables

char ___buffer___ [256]

Function Documentation

double mtk::distance2D ( double  ax,
double  ay,
double  bx,
double  by 
)

Euclidean distance between 2D points; z coordinate is ignored

Parameters:
apoint a
bpoint b
Returns:
Distance

Definition at line 73 of file geometry.cpp.

Definition at line 83 of file geometry.cpp.

Definition at line 88 of file geometry.cpp.

double mtk::distance2D ( const tf::Vector3 a,
const tf::Vector3 b = tf::Vector3() 
)

Definition at line 78 of file geometry.cpp.

double mtk::distance2D ( const tf::Transform a,
const tf::Transform b = tf::Transform() 
)

Definition at line 93 of file geometry.cpp.

double mtk::distance2D ( double  x,
double  y 
)

Definition at line 63 of file geometry.cpp.

double mtk::distance2D ( const tf::Point p)

Definition at line 68 of file geometry.cpp.

double mtk::distance3D ( double  ax,
double  ay,
double  az,
double  bx,
double  by,
double  bz 
)

Euclidean distance between 3D points

Parameters:
apoint a
bpoint b
Returns:
Distance

Definition at line 109 of file geometry.cpp.

Definition at line 119 of file geometry.cpp.

Definition at line 124 of file geometry.cpp.

double mtk::distance3D ( const tf::Vector3 a,
const tf::Vector3 b 
)

Definition at line 114 of file geometry.cpp.

double mtk::distance3D ( const tf::Transform a,
const tf::Transform b 
)

Definition at line 129 of file geometry.cpp.

double mtk::distance3D ( double  x,
double  y,
double  z 
)

Definition at line 99 of file geometry.cpp.

double mtk::distance3D ( const tf::Point p)

Definition at line 104 of file geometry.cpp.

Heading angle from point a to point b

Parameters:
apoint a
bpoint b
Returns:
Heading angle

Definition at line 140 of file geometry.cpp.

Definition at line 145 of file geometry.cpp.

double mtk::heading ( const tf::Vector3 a,
const tf::Vector3 b 
)

Definition at line 135 of file geometry.cpp.

double mtk::heading ( const tf::Transform a,
const tf::Transform b 
)

Definition at line 150 of file geometry.cpp.

template<typename T >
T mtk::mean ( const std::vector< T > &  v)

Definition at line 35 of file common.hpp.

template<typename T >
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

Parameters:
aquaternion a
bquaternion b
Returns:
Minimum angle

Definition at line 160 of file geometry.cpp.

Definition at line 165 of file geometry.cpp.

double mtk::minAngle ( const tf::Quaternion a,
const tf::Quaternion b 
)

Definition at line 155 of file geometry.cpp.

double mtk::minAngle ( const tf::Transform a,
const tf::Transform b 
)

Definition at line 170 of file geometry.cpp.

template<typename T >
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

Parameters:
tf/pose
Returns:
Transform/pose's pitch

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 47 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

Parameters:
pxpoint x-coordinate
pypoint y-coordinate
s1xsegment's point 1 x-coordinate
s1ysegment's point 1 y-coordinate
s2xsegment's point 2 x-coordinate
s2ysegment's point 2 y-coordinate
Returns:
distance

Definition at line 201 of file geometry.cpp.

const char * mtk::pose2str ( const geometry_msgs::Pose pose)

Definition at line 53 of file common.cpp.

const char * mtk::pose2str ( const geometry_msgs::PoseStamped &  pose)

Definition at line 59 of file common.cpp.

void mtk::pose2tf ( const geometry_msgs::Pose pose,
tf::Transform tf 
)

Definition at line 30 of file common.cpp.

void mtk::pose2tf ( const geometry_msgs::PoseStamped &  pose,
tf::StampedTransform tf 
)

Definition at line 38 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?

Parameters:
rxrays's end point x-coordinate
ryrays's end point y-coordinate
cxcircle's center x-coordinate
cycircle's center y-coordinate
radiuscircle's radius
ixclosest intersection point (if any) x-coordinate
iyclosest intersection point (if any) y-coordinate
distanceDistance from rays's start (zero) to intersection point
Returns:
True if ray intersects the circle

Definition at line 251 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?

Parameters:
r1xrays's start point x-coordinate
r1yrays's start point y-coordinate
r2xrays's end point x-coordinate
r2yrays's end point y-coordinate
s1xsegment's point 1 x-coordinate
s1ysegment's point 1 y-coordinate
s2xsegment's point 2 x-coordinate
s2ysegment's point 2 y-coordinate
ixintersection point (if any) x-coordinate
iyintersection point (if any) y-coordinate
distanceDistance from rays's start to intersection point
Returns:
True if ray intersects the segment

Definition at line 223 of file geometry.cpp.

double mtk::roll ( const tf::Transform tf)

Shortcut to take the roll of a transform/pose

Parameters:
tf/pose
Returns:
Transform/pose's roll

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.

Parameters:
frame_a
frame_b
Returns:
true if frame ids match regardless leading /

Definition at line 180 of file geometry.cpp.

bool mtk::sameFrame ( const geometry_msgs::PoseStamped &  a,
const geometry_msgs::PoseStamped &  b 
)

Definition at line 175 of file geometry.cpp.

template<typename T >
T mtk::sign ( T  x)

Definition at line 58 of file common.hpp.

template<typename T >
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 15 of file common.cpp.

void mtk::tf2pose ( const tf::StampedTransform tf,
geometry_msgs::PoseStamped &  pose 
)

Definition at line 23 of file common.cpp.

template<typename T >
T mtk::variance ( const std::vector< T > &  v)

Definition at line 43 of file common.hpp.

double mtk::wrapAngle ( double  a)

Normalize an angle between -π and +π

Parameters:
aUnnormalized angle
Returns:
Normalized angle

Definition at line 16 of file geometry.cpp.


Variable Documentation

char mtk::___buffer___[256]

Definition at line 45 of file common.cpp.



yocs_math_toolkit
Author(s): Jorge Santos
autogenerated on Thu Jun 6 2019 21:47:25