00001
00002
00003
00004
00005
00006
00007
00008 #include "yocs_math_toolkit/common.hpp"
00009 #include "yocs_math_toolkit/geometry.hpp"
00010
00011
00012 namespace mtk
00013 {
00014
00015
00016 double wrapAngle(double a)
00017 {
00018 a = fmod(a + M_PI, 2*M_PI);
00019 if (a < 0.0)
00020 a += 2.0*M_PI;
00021 return a - M_PI;
00022 }
00023
00024 double roll(const tf::Transform& tf)
00025 {
00026 double roll, pitch, yaw;
00027 tf::Matrix3x3(tf.getRotation()).getRPY(roll, pitch, yaw);
00028 return roll;
00029 }
00030
00031 double roll(geometry_msgs::Pose pose)
00032 {
00033 tf::Transform tf;
00034 pose2tf(pose, tf);
00035 return roll(tf);
00036 }
00037
00038 double roll(geometry_msgs::PoseStamped pose)
00039 {
00040 return roll(pose.pose);
00041 }
00042
00043 double pitch(const tf::Transform& tf)
00044 {
00045 double roll, pitch, yaw;
00046 tf::Matrix3x3(tf.getRotation()).getRPY(roll, pitch, yaw);
00047 return pitch;
00048 }
00049
00050 double pitch(geometry_msgs::Pose pose)
00051 {
00052 tf::Transform tf;
00053 pose2tf(pose, tf);
00054 return pitch(tf);
00055 }
00056
00057 double pitch(geometry_msgs::PoseStamped pose)
00058 {
00059 return pitch(pose.pose);
00060 }
00061
00062
00063 double distance2D(double x, double y)
00064 {
00065 return std::sqrt(std::pow(x, 2) + std::pow(y, 2));
00066 }
00067
00068 double distance2D(const tf::Point& p)
00069 {
00070 return std::sqrt(std::pow(p.x(), 2) + std::pow(p.y(), 2));
00071 }
00072
00073 double distance2D(double ax, double ay, double bx, double by)
00074 {
00075 return std::sqrt(std::pow(ax - bx, 2) + std::pow(ay - by, 2));
00076 }
00077
00078 double distance2D(const tf::Point& p1, const tf::Point& p2)
00079 {
00080 return std::sqrt(std::pow(p2.x() - p1.x(), 2) + std::pow(p2.y() - p1.y(), 2));
00081 }
00082
00083 double distance2D(geometry_msgs::Point a, geometry_msgs::Point b)
00084 {
00085 return distance2D(tf::Vector3(a.x, a.y, a.z), tf::Vector3(b.x, b.y, b.z));
00086 }
00087
00088 double distance2D(geometry_msgs::Pose a, geometry_msgs::Pose b)
00089 {
00090 return distance2D(a.position, b.position);
00091 }
00092
00093 double distance2D(const tf::Transform& a, const tf::Transform& b)
00094 {
00095 return distance2D(a.getOrigin(), b.getOrigin());
00096 }
00097
00098
00099 double distance3D(double x, double y, double z)
00100 {
00101 return std::sqrt(std::pow(x, 2) + std::pow(y, 2) + std::pow(z, 2));
00102 }
00103
00104 double distance3D(const tf::Point& p)
00105 {
00106 return std::sqrt(std::pow(p.x(), 2) + std::pow(p.y(), 2) + std::pow(p.z(), 2));
00107 }
00108
00109 double distance3D(double ax, double ay, double az, double bx, double by, double bz)
00110 {
00111 return std::sqrt(std::pow(ax - bx, 2) + std::pow(ay - by, 2) + std::pow(az - bz, 2));
00112 }
00113
00114 double distance3D(const tf::Point& p1, const tf::Point& p2)
00115 {
00116 return std::sqrt(std::pow(p2.x() - p1.x(), 2) + std::pow(p2.y() - p1.y(), 2) + std::pow(p2.z() - p1.z(), 2));
00117 }
00118
00119 double distance3D(geometry_msgs::Point a, geometry_msgs::Point b)
00120 {
00121 return distance3D(tf::Vector3(a.x, a.y, a.z), tf::Vector3(b.x, b.y, b.z));
00122 }
00123
00124 double distance3D(geometry_msgs::Pose a, geometry_msgs::Pose b)
00125 {
00126 return distance3D(a.position, b.position);
00127 }
00128
00129 double distance3D(const tf::Transform& a, const tf::Transform& b)
00130 {
00131 return distance3D(a.getOrigin(), b.getOrigin());
00132 }
00133
00134
00135 double heading(const tf::Vector3& a, const tf::Vector3& b)
00136 {
00137 return std::atan2(b.y() - a.y(), b.x() - a.x());
00138 }
00139
00140 double heading(geometry_msgs::Point a, geometry_msgs::Point b)
00141 {
00142 return heading(tf::Vector3(a.x, a.y, a.z), tf::Vector3(b.x, b.y, b.z));
00143 }
00144
00145 double heading(geometry_msgs::Pose a, geometry_msgs::Pose b)
00146 {
00147 return heading(a.position, b.position);
00148 }
00149
00150 double heading(const tf::Transform& a, const tf::Transform& b)
00151 {
00152 return heading(a.getOrigin(), b.getOrigin());
00153 }
00154
00155 double minAngle(const tf::Quaternion& a, const tf::Quaternion& b)
00156 {
00157 return tf::angleShortestPath(a, b);
00158 }
00159
00160 double minAngle(geometry_msgs::Quaternion a, geometry_msgs::Quaternion b)
00161 {
00162 return minAngle(tf::Quaternion(a.x, a.y, a.z, a.w), tf::Quaternion(b.x, b.y, b.z, b.w));
00163 }
00164
00165 double minAngle(geometry_msgs::Pose a, geometry_msgs::Pose b)
00166 {
00167 return minAngle(a.orientation, b.orientation);
00168 }
00169
00170 double minAngle(const tf::Transform& a, const tf::Transform& b)
00171 {
00172 return minAngle(a.getRotation(), b.getRotation());
00173 }
00174
00175 double pointSegmentDistance(double px, double py, double s1x, double s1y, double s2x, double s2y)
00176 {
00177
00178
00179 double l = distance2D(s1x, s1y, s2x, s2y);
00180 if (l == 0.0)
00181 return distance2D(px, py, s1x, s1y);
00182
00183
00184
00185
00186 double t = (- s1x * (s2x - s1x) - s1y * (s2y - s1y)) / l;
00187 if (t < 0.0)
00188 return distance2D(s1x, s1y);
00189
00190 if (t > 1.0)
00191 return distance2D(s2x, s2y);
00192
00193
00194 return distance2D(s1x + t * (s2x - s1x), s1y + t * (s2y - s1y));
00195 }
00196
00197 bool raySegmentIntersection(double r1x, double r1y, double r2x, double r2y,
00198 double s1x, double s1y, double s2x, double s2y,
00199 double& ix, double& iy, double& distance)
00200 {
00201 double r, s, d;
00202
00203 if ((r2y - r1y) / (r2x - r1x) != (s2y - s1y) / (s2x - s1x))
00204 {
00205 d = (((r2x - r1x) * (s2y - s1y)) - (r2y - r1y) * (s2x - s1x));
00206 if (d != 0)
00207 {
00208 r = (((r1y - s1y) * (s2x - s1x)) - (r1x - s1x) * (s2y - s1y)) / d;
00209 s = (((r1y - s1y) * (r2x - r1x)) - (r1x - s1x) * (r2y - r1y)) / d;
00210 if (r >= 0)
00211 {
00212 if (s >= 0 && s <= 1)
00213 {
00214 ix = r1x + r * (r2x - r1x);
00215 iy = r1y + r * (r2y - r1y);
00216 distance = distance2D(ix, iy);
00217 return true;
00218 }
00219 }
00220 }
00221 }
00222 return false;
00223 }
00224
00225 bool rayCircleIntersection(double rx, double ry, double cx, double cy, double radius,
00226 double& ix, double& iy, double& distance)
00227 {
00228 double a = rx * rx + ry * ry;
00229 double bBy2 = rx * cx + ry * cy;
00230 double c = cx * cx + cy * cy - radius * radius;
00231
00232 double pBy2 = bBy2 / a;
00233 double q = c / a;
00234
00235 double discriminant = pBy2 * pBy2 - q;
00236 if (discriminant < 0)
00237 return false;
00238
00239
00240 double tmpSqrt = std::sqrt(discriminant);
00241 double abScalingFactor1 = -pBy2 + tmpSqrt;
00242 double abScalingFactor2 = -pBy2 - tmpSqrt;
00243
00244 ix = - rx * abScalingFactor1;
00245 iy = - ry * abScalingFactor1;
00246 distance = distance2D(ix, iy);
00247
00248
00249 if ((ix*rx < 0.0) && (iy*ry < 0.0))
00250 return false;
00251
00252 if (discriminant == 0)
00253 return true;
00254
00255
00256 double i2x = - rx * abScalingFactor2;
00257 double i2y = - ry * abScalingFactor2;
00258 double distance2 = distance2D(i2x, i2y);
00259
00260 if (distance2 < distance)
00261 {
00262 ix = i2x;
00263 iy = i2y;
00264 distance = distance2;
00265 }
00266
00267 return true;
00268 }
00269
00270
00271 }