angles.h 9.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284
  1. /*********************************************************************
  2. * Software License Agreement (BSD License)
  3. *
  4. * Copyright (c) 2008, Willow Garage, Inc.
  5. * All rights reserved.
  6. *
  7. * Redistribution and use in source and binary forms, with or without
  8. * modification, are permitted provided that the following conditions
  9. * are met:
  10. *
  11. * * Redistributions of source code must retain the above copyright
  12. * notice, this list of conditions and the following disclaimer.
  13. * * Redistributions in binary form must reproduce the above
  14. * copyright notice, this list of conditions and the following
  15. * disclaimer in the documentation and/or other materials provided
  16. * with the distribution.
  17. * * Neither the name of the Willow Garage nor the names of its
  18. * contributors may be used to endorse or promote products derived
  19. * from this software without specific prior written permission.
  20. *
  21. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  22. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  23. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  24. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  25. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  26. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  27. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  28. * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  29. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  30. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  31. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  32. * POSSIBILITY OF SUCH DAMAGE.
  33. *********************************************************************/
  34. #ifndef GEOMETRY_ANGLES_UTILS_H
  35. #define GEOMETRY_ANGLES_UTILS_H
  36. #include <algorithm>
  37. #include <cmath>
  38. #ifndef M_PI
  39. #define M_PI 3.14159265358979323846
  40. #endif // !M_PI
  41. namespace angles
  42. {
  43. /*!
  44. * \brief Convert degrees to radians
  45. */
  46. static inline double from_degrees(double degrees)
  47. {
  48. return degrees * M_PI / 180.0;
  49. }
  50. /*!
  51. * \brief Convert radians to degrees
  52. */
  53. static inline double to_degrees(double radians)
  54. {
  55. return radians * 180.0 / M_PI;
  56. }
  57. /*!
  58. * \brief normalize_angle_positive
  59. *
  60. * Normalizes the angle to be 0 to 2*M_PI
  61. * It takes and returns radians.
  62. */
  63. static inline double normalize_angle_positive(double angle)
  64. {
  65. return fmod(fmod(angle, 2.0*M_PI) + 2.0*M_PI, 2.0*M_PI);
  66. }
  67. /*!
  68. * \brief normalize
  69. *
  70. * Normalizes the angle to be -M_PI circle to +M_PI circle
  71. * It takes and returns radians.
  72. *
  73. */
  74. static inline double normalize_angle(double angle)
  75. {
  76. double a = normalize_angle_positive(angle);
  77. if (a > M_PI)
  78. a -= 2.0 *M_PI;
  79. return a;
  80. }
  81. /*!
  82. * \function
  83. * \brief shortest_angular_distance
  84. *
  85. * Given 2 angles, this returns the shortest angular
  86. * difference. The inputs and ouputs are of course radians.
  87. *
  88. * The result
  89. * would always be -pi <= result <= pi. Adding the result
  90. * to "from" will always get you an equivelent angle to "to".
  91. */
  92. static inline double shortest_angular_distance(double from, double to)
  93. {
  94. return normalize_angle(to-from);
  95. }
  96. /*!
  97. * \function
  98. *
  99. * \brief returns the angle in [-2*M_PI, 2*M_PI] going the other way along the unit circle.
  100. * \param angle The angle to which you want to turn in the range [-2*M_PI, 2*M_PI]
  101. * E.g. two_pi_complement(-M_PI/4) returns 7_M_PI/4
  102. * two_pi_complement(M_PI/4) returns -7*M_PI/4
  103. *
  104. */
  105. static inline double two_pi_complement(double angle)
  106. {
  107. //check input conditions
  108. if (angle > 2*M_PI || angle < -2.0*M_PI)
  109. angle = fmod(angle, 2.0*M_PI);
  110. if(angle < 0)
  111. return (2*M_PI+angle);
  112. else if (angle > 0)
  113. return (-2*M_PI+angle);
  114. return(2*M_PI);
  115. }
  116. /*!
  117. * \function
  118. *
  119. * \brief This function is only intended for internal use and not intended for external use. If you do use it, read the documentation very carefully. Returns the min and max amount (in radians) that can be moved from "from" angle to "left_limit" and "right_limit".
  120. * \return returns false if "from" angle does not lie in the interval [left_limit,right_limit]
  121. * \param from - "from" angle - must lie in [-M_PI, M_PI)
  122. * \param left_limit - left limit of valid interval for angular position - must lie in [-M_PI, M_PI], left and right limits are specified on the unit circle w.r.t to a reference pointing inwards
  123. * \param right_limit - right limit of valid interval for angular position - must lie in [-M_PI, M_PI], left and right limits are specified on the unit circle w.r.t to a reference pointing inwards
  124. * \param result_min_delta - minimum (delta) angle (in radians) that can be moved from "from" position before hitting the joint stop
  125. * \param result_max_delta - maximum (delta) angle (in radians) that can be movedd from "from" position before hitting the joint stop
  126. */
  127. static bool find_min_max_delta(double from, double left_limit, double right_limit, double &result_min_delta, double &result_max_delta)
  128. {
  129. double delta[4];
  130. delta[0] = shortest_angular_distance(from,left_limit);
  131. delta[1] = shortest_angular_distance(from,right_limit);
  132. delta[2] = two_pi_complement(delta[0]);
  133. delta[3] = two_pi_complement(delta[1]);
  134. if(delta[0] == 0)
  135. {
  136. result_min_delta = delta[0];
  137. result_max_delta = std::max<double>(delta[1],delta[3]);
  138. return true;
  139. }
  140. if(delta[1] == 0)
  141. {
  142. result_max_delta = delta[1];
  143. result_min_delta = std::min<double>(delta[0],delta[2]);
  144. return true;
  145. }
  146. double delta_min = delta[0];
  147. double delta_min_2pi = delta[2];
  148. if(delta[2] < delta_min)
  149. {
  150. delta_min = delta[2];
  151. delta_min_2pi = delta[0];
  152. }
  153. double delta_max = delta[1];
  154. double delta_max_2pi = delta[3];
  155. if(delta[3] > delta_max)
  156. {
  157. delta_max = delta[3];
  158. delta_max_2pi = delta[1];
  159. }
  160. // printf("%f %f %f %f\n",delta_min,delta_min_2pi,delta_max,delta_max_2pi);
  161. if((delta_min <= delta_max_2pi) || (delta_max >= delta_min_2pi))
  162. {
  163. result_min_delta = delta_max_2pi;
  164. result_max_delta = delta_min_2pi;
  165. if(left_limit == -M_PI && right_limit == M_PI)
  166. return true;
  167. else
  168. return false;
  169. }
  170. result_min_delta = delta_min;
  171. result_max_delta = delta_max;
  172. return true;
  173. }
  174. /*!
  175. * \function
  176. *
  177. * \brief Returns the delta from "from_angle" to "to_angle" making sure it does not violate limits specified by left_limit and right_limit.
  178. * The valid interval of angular positions is [left_limit,right_limit]. E.g., [-0.25,0.25] is a 0.5 radians wide interval that contains 0.
  179. * But [0.25,-0.25] is a 2*M_PI-0.5 wide interval that contains M_PI (but not 0).
  180. * The value of shortest_angle is the angular difference between "from" and "to" that lies within the defined valid interval.
  181. * E.g. shortest_angular_distance_with_limits(-0.5,0.5,0.25,-0.25,ss) evaluates ss to 2*M_PI-1.0 and returns true while
  182. * shortest_angular_distance_with_limits(-0.5,0.5,-0.25,0.25,ss) returns false since -0.5 and 0.5 do not lie in the interval [-0.25,0.25]
  183. *
  184. * \return true if "from" and "to" positions are within the limit interval, false otherwise
  185. * \param from - "from" angle
  186. * \param to - "to" angle
  187. * \param left_limit - left limit of valid interval for angular position, left and right limits are specified on the unit circle w.r.t to a reference pointing inwards
  188. * \param right_limit - right limit of valid interval for angular position, left and right limits are specified on the unit circle w.r.t to a reference pointing inwards
  189. * \param shortest_angle - result of the shortest angle calculation
  190. */
  191. static inline bool shortest_angular_distance_with_limits(double from, double to, double left_limit, double right_limit, double &shortest_angle)
  192. {
  193. double min_delta = -2*M_PI;
  194. double max_delta = 2*M_PI;
  195. double min_delta_to = -2*M_PI;
  196. double max_delta_to = 2*M_PI;
  197. bool flag = find_min_max_delta(from,left_limit,right_limit,min_delta,max_delta);
  198. double delta = shortest_angular_distance(from,to);
  199. double delta_mod_2pi = two_pi_complement(delta);
  200. if(flag)//from position is within the limits
  201. {
  202. if(delta >= min_delta && delta <= max_delta)
  203. {
  204. shortest_angle = delta;
  205. return true;
  206. }
  207. else if(delta_mod_2pi >= min_delta && delta_mod_2pi <= max_delta)
  208. {
  209. shortest_angle = delta_mod_2pi;
  210. return true;
  211. }
  212. else //to position is outside the limits
  213. {
  214. find_min_max_delta(to,left_limit,right_limit,min_delta_to,max_delta_to);
  215. if(fabs(min_delta_to) < fabs(max_delta_to))
  216. shortest_angle = std::max<double>(delta,delta_mod_2pi);
  217. else if(fabs(min_delta_to) > fabs(max_delta_to))
  218. shortest_angle = std::min<double>(delta,delta_mod_2pi);
  219. else
  220. {
  221. if (fabs(delta) < fabs(delta_mod_2pi))
  222. shortest_angle = delta;
  223. else
  224. shortest_angle = delta_mod_2pi;
  225. }
  226. return false;
  227. }
  228. }
  229. else // from position is outside the limits
  230. {
  231. find_min_max_delta(to,left_limit,right_limit,min_delta_to,max_delta_to);
  232. if(fabs(min_delta) < fabs(max_delta))
  233. shortest_angle = std::min<double>(delta,delta_mod_2pi);
  234. else if (fabs(min_delta) > fabs(max_delta))
  235. shortest_angle = std::max<double>(delta,delta_mod_2pi);
  236. else
  237. {
  238. if (fabs(delta) < fabs(delta_mod_2pi))
  239. shortest_angle = delta;
  240. else
  241. shortest_angle = delta_mod_2pi;
  242. }
  243. return false;
  244. }
  245. shortest_angle = delta;
  246. return false;
  247. }
  248. }
  249. #endif