Go to the source code of this file.
Namespaces | |
namespace | mtk |
Functions | |
double | mtk::distance2D (double ax, double ay, double bx, double by) |
double | mtk::distance2D (geometry_msgs::Point a, geometry_msgs::Point b=geometry_msgs::Point()) |
double | mtk::distance2D (geometry_msgs::Pose a, geometry_msgs::Pose b=geometry_msgs::Pose()) |
double | mtk::distance2D (const tf::Vector3 &a, const tf::Vector3 &b=tf::Vector3()) |
double | mtk::distance2D (const tf::Transform &a, const tf::Transform &b=tf::Transform()) |
double | mtk::distance3D (double ax, double ay, double az, double bx, double by, double bz) |
double | mtk::distance3D (geometry_msgs::Point a, geometry_msgs::Point b=geometry_msgs::Point()) |
double | mtk::distance3D (geometry_msgs::Pose a, geometry_msgs::Pose b=geometry_msgs::Pose()) |
double | mtk::distance3D (const tf::Vector3 &a, const tf::Vector3 &b) |
double | mtk::distance3D (const tf::Transform &a, const tf::Transform &b) |
double | mtk::heading (geometry_msgs::Point a, geometry_msgs::Point b=geometry_msgs::Point()) |
double | mtk::heading (geometry_msgs::Pose a, geometry_msgs::Pose b=geometry_msgs::Pose()) |
double | mtk::heading (const tf::Vector3 &a, const tf::Vector3 &b) |
double | mtk::heading (const tf::Transform &a, const tf::Transform &b) |
double | mtk::minAngle (geometry_msgs::Quaternion a, geometry_msgs::Quaternion b) |
double | mtk::minAngle (geometry_msgs::Pose a, geometry_msgs::Pose b) |
double | mtk::minAngle (const tf::Quaternion &a, const tf::Quaternion &b) |
double | mtk::minAngle (const tf::Transform &a, const tf::Transform &b) |
double | mtk::pitch (const tf::Transform &tf) |
double | mtk::pitch (geometry_msgs::Pose pose) |
double | mtk::pitch (geometry_msgs::PoseStamped pose) |
double | mtk::pointSegmentDistance (double px, double py, double s1x, double s1y, double s2x, double s2y) |
bool | mtk::rayCircleIntersection (double rx, double ry, double cx, double cy, double radius, double &ix, double &iy, double &distance) |
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) |
double | mtk::roll (const tf::Transform &tf) |
double | mtk::roll (geometry_msgs::Pose pose) |
double | mtk::roll (geometry_msgs::PoseStamped pose) |
bool | mtk::sameFrame (const std::string &frame_a, const std::string &frame_b) |
bool | mtk::sameFrame (const geometry_msgs::PoseStamped &a, const geometry_msgs::PoseStamped &b) |
double | mtk::wrapAngle (double a) |