pax_global_header00006660000000000000000000000064136322435340014517gustar00rootroot0000000000000052 comment=381658b8f202cad91fbcf533dc6e8bb55354efca angles-1.9.13/000077500000000000000000000000001363224353400130635ustar00rootroot00000000000000angles-1.9.13/README.md000066400000000000000000000010361363224353400143420ustar00rootroot00000000000000This package provides a set of simple math utilities to work with angles. Homepage: The utilities cover simple things like normalizing an angle and conversion between degrees and radians. But even if you're trying to calculate things like the shortest angular distance between two joint space positions of your robot, but the joint motion is constrained by joint limits, this package is what you need. The code in this package is stable and well tested. There are no plans for major changes in the near future. angles-1.9.13/angles/000077500000000000000000000000001363224353400143345ustar00rootroot00000000000000angles-1.9.13/angles/CHANGELOG.rst000066400000000000000000000045001363224353400163540ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package angles ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.9.13 (2020-03-11) ------------------- * Update the angle normalization function to a simpler implementation (`#19 `_) * Update the angle normalization function for a simpler alternative * Simplify 2*pi angle wrapping. * Simplify/fasten the C++ implementation of angle normalization (removes one fmod call) * Bump CMake version to avoid CMP0048 warning (`#20 `_) * Contributors: Alexis Paques, Shane Loretz 1.9.12 (2020-01-08) ------------------- * Added support for "large limits" (`#16 `_) * Small documentation updates. * Contributors: Franco Fusco, Tully Foote 1.9.11 (2017-04-14) ------------------- * Add a python implementation of angles * Do not use catkin_add_gtest if CATKIN_ENABLE_TESTING * Contributors: David V. Lu, David V. Lu!!, Ryohei Ueda 1.9.10 (2014-12-29) ------------------- * Export architecture_independent flag in package.xml * Simply and improve performance of shortest_angular_distance(). adding two unit test cases * check for CATKIN_ENABLE_TESTING * Contributors: Derek King, Lukas Bulwahn, Scott K Logan, Tully Foote 1.9.9 (2013-03-23) ------------------ * catkin as a buildtool dependency * Contributors: Tully Foote 1.9.8 (2012-12-05) ------------------ * Removed 'copyright' tag from package.xml * Contributors: William Woodall 1.9.7 (2012-10-02 21:23) ------------------------ * fix typo * Contributors: Vincent Rabaud 1.9.6 (2012-10-02 15:39) ------------------------ * comply to the new catkin API * Contributors: Vincent Rabaud 1.9.5 (2012-09-16 18:11) ------------------------ * fixes to build * Contributors: Ioan Sucan 1.9.4 (2012-09-16 01:24) ------------------------ * rename the include folder to angles as it should be * Contributors: Vincent Rabaud 1.9.3 (2012-09-03 00:55) ------------------------ * fix relative path * Contributors: Ioan Sucan 1.9.2 (2012-09-03 00:32) ------------------------ 1.9.1 (2012-07-24) ------------------ * add proper manifest * Contributors: Ioan Sucan 1.9.0 (2012-07-23) ------------------ * fix the test for the new headers * fix the guard * package builds with catkin * remove useless header * copying from geometry/ * Contributors: Ioan Sucan, Vincent Rabaud angles-1.9.13/angles/CMakeLists.txt000066400000000000000000000005651363224353400171020ustar00rootroot00000000000000cmake_minimum_required(VERSION 3.0.2) project(angles) find_package(catkin REQUIRED) catkin_package(INCLUDE_DIRS include) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} FILES_MATCHING PATTERN "*.h") include_directories(include) if(CATKIN_ENABLE_TESTING) add_subdirectory(test) endif() catkin_python_setup()angles-1.9.13/angles/doc.dox000066400000000000000000000006451363224353400156220ustar00rootroot00000000000000/** @mainpage @htmlinclude manifest.html The Angles contains the following methods: \li Angular conversions: angles::from_degrees, angles::to_degrees \li Angular manipulations: angles::normalize_angle_positive, angles::normalize_angle \li Angular distance: angles::shortest_angular_distance, angles::shortest_angular_distance_with_limits \li Angular tools: angles::find_min_max_delta, angles::two_pi_complement **/ angles-1.9.13/angles/include/000077500000000000000000000000001363224353400157575ustar00rootroot00000000000000angles-1.9.13/angles/include/angles/000077500000000000000000000000001363224353400172305ustar00rootroot00000000000000angles-1.9.13/angles/include/angles/angles.h000066400000000000000000000336161363224353400206630ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ #ifndef GEOMETRY_ANGLES_UTILS_H #define GEOMETRY_ANGLES_UTILS_H #include #include namespace angles { /*! * \brief Convert degrees to radians */ static inline double from_degrees(double degrees) { return degrees * M_PI / 180.0; } /*! * \brief Convert radians to degrees */ static inline double to_degrees(double radians) { return radians * 180.0 / M_PI; } /*! * \brief normalize_angle_positive * * Normalizes the angle to be 0 to 2*M_PI * It takes and returns radians. */ static inline double normalize_angle_positive(double angle) { const double result = fmod(angle, 2.0*M_PI); if(result < 0) return result + 2.0*M_PI; return result; } /*! * \brief normalize * * Normalizes the angle to be -M_PI circle to +M_PI circle * It takes and returns radians. * */ static inline double normalize_angle(double angle) { const double result = fmod(angle + M_PI, 2.0*M_PI); if(result <= 0.0) return result + M_PI; return result - M_PI; } /*! * \function * \brief shortest_angular_distance * * Given 2 angles, this returns the shortest angular * difference. The inputs and ouputs are of course radians. * * The result * would always be -pi <= result <= pi. Adding the result * to "from" will always get you an equivelent angle to "to". */ static inline double shortest_angular_distance(double from, double to) { return normalize_angle(to-from); } /*! * \function * * \brief returns the angle in [-2*M_PI, 2*M_PI] going the other way along the unit circle. * \param angle The angle to which you want to turn in the range [-2*M_PI, 2*M_PI] * E.g. two_pi_complement(-M_PI/4) returns 7_M_PI/4 * two_pi_complement(M_PI/4) returns -7*M_PI/4 * */ static inline double two_pi_complement(double angle) { //check input conditions if (angle > 2*M_PI || angle < -2.0*M_PI) angle = fmod(angle, 2.0*M_PI); if(angle < 0) return (2*M_PI+angle); else if (angle > 0) return (-2*M_PI+angle); return(2*M_PI); } /*! * \function * * \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". * \return returns false if "from" angle does not lie in the interval [left_limit,right_limit] * \param from - "from" angle - must lie in [-M_PI, M_PI) * \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 * \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 * \param result_min_delta - minimum (delta) angle (in radians) that can be moved from "from" position before hitting the joint stop * \param result_max_delta - maximum (delta) angle (in radians) that can be movedd from "from" position before hitting the joint stop */ static bool find_min_max_delta(double from, double left_limit, double right_limit, double &result_min_delta, double &result_max_delta) { double delta[4]; delta[0] = shortest_angular_distance(from,left_limit); delta[1] = shortest_angular_distance(from,right_limit); delta[2] = two_pi_complement(delta[0]); delta[3] = two_pi_complement(delta[1]); if(delta[0] == 0) { result_min_delta = delta[0]; result_max_delta = std::max(delta[1],delta[3]); return true; } if(delta[1] == 0) { result_max_delta = delta[1]; result_min_delta = std::min(delta[0],delta[2]); return true; } double delta_min = delta[0]; double delta_min_2pi = delta[2]; if(delta[2] < delta_min) { delta_min = delta[2]; delta_min_2pi = delta[0]; } double delta_max = delta[1]; double delta_max_2pi = delta[3]; if(delta[3] > delta_max) { delta_max = delta[3]; delta_max_2pi = delta[1]; } // printf("%f %f %f %f\n",delta_min,delta_min_2pi,delta_max,delta_max_2pi); if((delta_min <= delta_max_2pi) || (delta_max >= delta_min_2pi)) { result_min_delta = delta_max_2pi; result_max_delta = delta_min_2pi; if(left_limit == -M_PI && right_limit == M_PI) return true; else return false; } result_min_delta = delta_min; result_max_delta = delta_max; return true; } /*! * \function * * \brief Returns the delta from `from_angle` to `to_angle`, making sure it does not violate limits specified by `left_limit` and `right_limit`. * This function is similar to `shortest_angular_distance_with_limits()`, with the main difference that it accepts limits outside the `[-M_PI, M_PI]` range. * Even if this is quite uncommon, one could indeed consider revolute joints with large rotation limits, e.g., in the range `[-2*M_PI, 2*M_PI]`. * * In this case, a strict requirement is to have `left_limit` smaller than `right_limit`. * Note also that `from` must lie inside the valid range, while `to` does not need to. * In fact, this function will evaluate the shortest (valid) angle `shortest_angle` so that `from+shortest_angle` equals `to` up to an integer multiple of `2*M_PI`. * As an example, a call to `shortest_angular_distance_with_large_limits(0, 10.5*M_PI, -2*M_PI, 2*M_PI, shortest_angle)` will return `true`, with `shortest_angle=0.5*M_PI`. * This is because `from` and `from+shortest_angle` are both inside the limits, and `fmod(to+shortest_angle, 2*M_PI)` equals `fmod(to, 2*M_PI)`. * On the other hand, `shortest_angular_distance_with_large_limits(10.5*M_PI, 0, -2*M_PI, 2*M_PI, shortest_angle)` will return false, since `from` is not in the valid range. * Finally, note that the call `shortest_angular_distance_with_large_limits(0, 10.5*M_PI, -2*M_PI, 0.1*M_PI, shortest_angle)` will also return `true`. * However, `shortest_angle` in this case will be `-1.5*M_PI`. * * \return true if `left_limit < right_limit` and if "from" and "from+shortest_angle" positions are within the valid interval, false otherwise. * \param from - "from" angle. * \param to - "to" angle. * \param left_limit - left limit of valid interval, must be smaller than right_limit. * \param right_limit - right limit of valid interval, must be greater than left_limit. * \param shortest_angle - result of the shortest angle calculation. */ static inline bool shortest_angular_distance_with_large_limits(double from, double to, double left_limit, double right_limit, double &shortest_angle) { // Shortest steps in the two directions double delta = shortest_angular_distance(from, to); double delta_2pi = two_pi_complement(delta); // "sort" distances so that delta is shorter than delta_2pi if(std::fabs(delta) > std::fabs(delta_2pi)) std::swap(delta, delta_2pi); if(left_limit > right_limit) { // If limits are something like [PI/2 , -PI/2] it actually means that we // want rotations to be in the interval [-PI,PI/2] U [PI/2,PI], ie, the // half unit circle not containing the 0. This is already gracefully // handled by shortest_angular_distance_with_limits, and therefore this // function should not be called at all. However, if one has limits that // are larger than PI, the same rationale behind shortest_angular_distance_with_limits // does not hold, ie, M_PI+x should not be directly equal to -M_PI+x. // In this case, the correct way of getting the shortest solution is to // properly set the limits, eg, by saying that the interval is either // [PI/2, 3*PI/2] or [-3*M_PI/2, -M_PI/2]. For this reason, here we // return false by default. shortest_angle = delta; return false; } // Check in which direction we should turn (clockwise or counter-clockwise). // start by trying with the shortest angle (delta). double to2 = from + delta; if(left_limit <= to2 && to2 <= right_limit) { // we can move in this direction: return success if the "from" angle is inside limits shortest_angle = delta; return left_limit <= from && from <= right_limit; } // delta is not ok, try to move in the other direction (using its complement) to2 = from + delta_2pi; if(left_limit <= to2 && to2 <= right_limit) { // we can move in this direction: return success if the "from" angle is inside limits shortest_angle = delta_2pi; return left_limit <= from && from <= right_limit; } // nothing works: we always go outside limits shortest_angle = delta; // at least give some "coherent" result return false; } /*! * \function * * \brief Returns the delta from "from_angle" to "to_angle" making sure it does not violate limits specified by left_limit and right_limit. * 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. * But [0.25,-0.25] is a 2*M_PI-0.5 wide interval that contains M_PI (but not 0). * The value of shortest_angle is the angular difference between "from" and "to" that lies within the defined valid interval. * 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 * 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] * * \return true if "from" and "to" positions are within the limit interval, false otherwise * \param from - "from" angle * \param to - "to" angle * \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 * \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 * \param shortest_angle - result of the shortest angle calculation */ static inline bool shortest_angular_distance_with_limits(double from, double to, double left_limit, double right_limit, double &shortest_angle) { double min_delta = -2*M_PI; double max_delta = 2*M_PI; double min_delta_to = -2*M_PI; double max_delta_to = 2*M_PI; bool flag = find_min_max_delta(from,left_limit,right_limit,min_delta,max_delta); double delta = shortest_angular_distance(from,to); double delta_mod_2pi = two_pi_complement(delta); if(flag)//from position is within the limits { if(delta >= min_delta && delta <= max_delta) { shortest_angle = delta; return true; } else if(delta_mod_2pi >= min_delta && delta_mod_2pi <= max_delta) { shortest_angle = delta_mod_2pi; return true; } else //to position is outside the limits { find_min_max_delta(to,left_limit,right_limit,min_delta_to,max_delta_to); if(fabs(min_delta_to) < fabs(max_delta_to)) shortest_angle = std::max(delta,delta_mod_2pi); else if(fabs(min_delta_to) > fabs(max_delta_to)) shortest_angle = std::min(delta,delta_mod_2pi); else { if (fabs(delta) < fabs(delta_mod_2pi)) shortest_angle = delta; else shortest_angle = delta_mod_2pi; } return false; } } else // from position is outside the limits { find_min_max_delta(to,left_limit,right_limit,min_delta_to,max_delta_to); if(fabs(min_delta) < fabs(max_delta)) shortest_angle = std::min(delta,delta_mod_2pi); else if (fabs(min_delta) > fabs(max_delta)) shortest_angle = std::max(delta,delta_mod_2pi); else { if (fabs(delta) < fabs(delta_mod_2pi)) shortest_angle = delta; else shortest_angle = delta_mod_2pi; } return false; } shortest_angle = delta; return false; } } #endif angles-1.9.13/angles/package.xml000066400000000000000000000017761363224353400164640ustar00rootroot00000000000000 angles 1.9.13 This package provides a set of simple math utilities to work with angles. The utilities cover simple things like normalizing an angle and conversion between degrees and radians. But even if you're trying to calculate things like the shortest angular distance between two joint space positions of your robot, but the joint motion is constrained by joint limits, this package is what you need. The code in this package is stable and well tested. There are no plans for major changes in the near future. John Hsu Tully Foote BSD http://wiki.ros.org/angles catkin rosunit angles-1.9.13/angles/setup.py000066400000000000000000000003551363224353400160510ustar00rootroot00000000000000#!/usr/bin/env python from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup package_info = generate_distutils_setup( packages=['angles'], package_dir={'': 'src'} ) setup(**package_info) angles-1.9.13/angles/src/000077500000000000000000000000001363224353400151235ustar00rootroot00000000000000angles-1.9.13/angles/src/angles/000077500000000000000000000000001363224353400163745ustar00rootroot00000000000000angles-1.9.13/angles/src/angles/__init__.py000066400000000000000000000301501363224353400205040ustar00rootroot00000000000000#********************************************************************* # Software License Agreement (BSD License) # # Copyright (c) 2015, Bossa Nova Robotics # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above # copyright notice, this list of conditions and the following # disclaimer in the documentation and/or other materials provided # with the distribution. # * Neither the name of the Bossa Nova Robotics nor the names of its # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. #********************************************************************/ from math import fmod, pi, fabs def normalize_angle_positive(angle): """ Normalizes the angle to be 0 to 2*pi It takes and returns radians. """ return angle % (2.0*pi) def normalize_angle(angle): """ Normalizes the angle to be -pi to +pi It takes and returns radians.""" a = normalize_angle_positive(angle) if a > pi: a -= 2.0 *pi return a def shortest_angular_distance(from_angle, to_angle): """ Given 2 angles, this returns the shortest angular difference. The inputs and ouputs are of course radians. The result would always be -pi <= result <= pi. Adding the result to "from" will always get you an equivelent angle to "to". """ return normalize_angle(to_angle-from_angle) def two_pi_complement(angle): """ returns the angle in [-2*pi, 2*pi] going the other way along the unit circle. \param angle The angle to which you want to turn in the range [-2*pi, 2*pi] E.g. two_pi_complement(-pi/4) returns 7_pi/4 two_pi_complement(pi/4) returns -7*pi/4 """ #check input conditions if angle > 2*pi or angle < -2.0*pi: angle = fmod(angle, 2.0*pi) if angle < 0: return 2*pi+angle elif angle > 0: return -2*pi+angle return 2*pi def _find_min_max_delta(from_angle, left_limit, right_limit): """ 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". \param from - "from" angle - must lie in [-pi, pi) \param left_limit - left limit of valid interval for angular position - must lie in [-pi, pi], left and right limits are specified on the unit circle w.r.t to a reference pointing inwards \param right_limit - right limit of valid interval for angular position - must lie in [-pi, pi], left and right limits are specified on the unit circle w.r.t to a reference pointing inwards \return (valid, min, max) - angle in radians that can be moved from "from" position before hitting the joint stop valid is False if "from" angle does not lie in the interval [left_limit,right_limit] """ delta = [0]*4 delta[0] = shortest_angular_distance(from_angle,left_limit) delta[1] = shortest_angular_distance(from_angle,right_limit) delta[2] = two_pi_complement(delta[0]) delta[3] = two_pi_complement(delta[1]) if delta[0] == 0: return True, delta[0], max(delta[1], delta[3]) if delta[1] == 0: return True, min(delta[0], delta[2]), delta[1] delta_min = delta[0] delta_min_2pi = delta[2] if delta[2] < delta_min: delta_min = delta[2] delta_min_2pi = delta[0] delta_max = delta[1] delta_max_2pi = delta[3] if delta[3] > delta_max: delta_max = delta[3] delta_max_2pi = delta[1] # printf("%f %f %f %f\n",delta_min,delta_min_2pi,delta_max,delta_max_2pi) if (delta_min <= delta_max_2pi) or (delta_max >= delta_min_2pi): if left_limit == -pi and right_limit == pi: return (True, delta_max_2pi, delta_min_2pi) else: return (False, delta_max_2pi, delta_min_2pi) return True, delta_min, delta_max def shortest_angular_distance_with_limits(from_angle, to_angle, left_limit, right_limit): """ Returns the delta from "from_angle" to "to_angle" making sure it does not violate limits specified by left_limit and right_limit. 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. But [0.25,-0.25] is a 2*pi-0.5 wide interval that contains pi (but not 0). The value of shortest_angle is the angular difference between "from" and "to" that lies within the defined valid interval. E.g. shortest_angular_distance_with_limits(-0.5,0.5,0.25,-0.25) returns 2*pi-1.0 shortest_angular_distance_with_limits(-0.5,0.5,-0.25,0.25) returns None since -0.5 and 0.5 do not lie in the interval [-0.25,0.25] \param left_limit - left limit of valid interval for angular position - must lie in [-pi, pi], left and right limits are specified on the unit circle w.r.t to a reference pointing inwards \param right_limit - right limit of valid interval for angular position - must lie in [-pi, pi], left and right limits are specified on the unit circle w.r.t to a reference pointing inwards \returns valid_flag, shortest_angle """ min_delta = -2*pi max_delta = 2*pi min_delta_to = -2*pi max_delta_to = 2*pi flag, min_delta, max_delta = _find_min_max_delta(from_angle, left_limit, right_limit) delta = shortest_angular_distance(from_angle,to_angle) delta_mod_2pi = two_pi_complement(delta) if flag: #from position is within the limits if delta >= min_delta and delta <= max_delta: return True, delta elif delta_mod_2pi >= min_delta and delta_mod_2pi <= max_delta: return True, delta_mod_2pi else: #to position is outside the limits flag, min_delta_to, max_delta_to = _find_min_max_delta(to_angle,left_limit,right_limit) if fabs(min_delta_to) < fabs(max_delta_to): shortest_angle = max(delta, delta_mod_2pi) elif fabs(min_delta_to) > fabs(max_delta_to): shortest_angle = min(delta,delta_mod_2pi) else: if fabs(delta) < fabs(delta_mod_2pi): shortest_angle = delta else: shortest_angle = delta_mod_2pi return False, shortest_angle else: # from position is outside the limits flag, min_delta_to, max_delta_to = _find_min_max_delta(to_angle,left_limit,right_limit) if fabs(min_delta) < fabs(max_delta): shortest_angle = min(delta,delta_mod_2pi) elif fabs(min_delta) > fabs(max_delta): shortest_angle = max(delta,delta_mod_2pi) else: if fabs(delta) < fabs(delta_mod_2pi): shortest_angle = delta else: shortest_angle = delta_mod_2pi return False, shortest_angle def shortest_angular_distance_with_large_limits(from_angle, to_angle, left_limit, right_limit): """ Returns the delta from `from_angle` to `to_angle`, making sure it does not violate limits specified by `left_limit` and `right_limit`. This function is similar to `shortest_angular_distance_with_limits()`, with the main difference that it accepts limits outside the `[-M_PI, M_PI]` range. Even if this is quite uncommon, one could indeed consider revolute joints with large rotation limits, e.g., in the range `[-2*M_PI, 2*M_PI]`. In this case, a strict requirement is to have `left_limit` smaller than `right_limit`. Note also that `from_angle` must lie inside the valid range, while `to_angle` does not need to. In fact, this function will evaluate the shortest (valid) angle `shortest_angle` so that `from_angle+shortest_angle` equals `to_angle` up to an integer multiple of `2*M_PI`. As an example, a call to `shortest_angular_distance_with_large_limits(0, 10.5*M_PI, -2*M_PI, 2*M_PI)` will return `true`, with `shortest_angle=0.5*M_PI`. This is because `from_angle` and `from_angle+shortest_angle` are both inside the limits, and `fmod(to_angle+shortest_angle, 2*M_PI)` equals `fmod(to_angle, 2*M_PI)`. On the other hand, `shortest_angular_distance_with_large_limits(10.5*M_PI, 0, -2*M_PI, 2*M_PI)` will return false, since `from_angle` is not in the valid range. Finally, note that the call `shortest_angular_distance_with_large_limits(0, 10.5*M_PI, -2*M_PI, 0.1*M_PI)` will also return `true`. However, `shortest_angle` in this case will be `-1.5*M_PI`. \return valid_flag, shortest_angle - valid_flag will be true if `left_limit < right_limit` and if "from_angle" and "from_angle+shortest_angle" positions are within the valid interval, false otherwise. \param left_limit - left limit of valid interval, must be smaller than right_limit. \param right_limit - right limit of valid interval, must be greater than left_limit. """ # Shortest steps in the two directions delta = shortest_angular_distance(from_angle, to_angle) delta_2pi = two_pi_complement(delta) # "sort" distances so that delta is shorter than delta_2pi if fabs(delta) > fabs(delta_2pi): delta, delta_2pi = delta_2pi, delta if left_limit > right_limit: # If limits are something like [PI/2 , -PI/2] it actually means that we # want rotations to be in the interval [-PI,PI/2] U [PI/2,PI], ie, the # half unit circle not containing the 0. This is already gracefully # handled by shortest_angular_distance_with_limits, and therefore this # function should not be called at all. However, if one has limits that # are larger than PI, the same rationale behind shortest_angular_distance_with_limits # does not hold, ie, M_PI+x should not be directly equal to -M_PI+x. # In this case, the correct way of getting the shortest solution is to # properly set the limits, eg, by saying that the interval is either # [PI/2, 3*PI/2] or [-3*M_PI/2, -M_PI/2]. For this reason, here we # return false by default. return False, delta # Check in which direction we should turn (clockwise or counter-clockwise). # start by trying with the shortest angle (delta). to2 = from_angle + delta if left_limit <= to2 and to2 <= right_limit: # we can move in this direction: return success if the "from" angle is inside limits valid_flag = left_limit <= from_angle and from_angle <= right_limit return valid_flag, delta # delta is not ok, try to move in the other direction (using its complement) to2 = from_angle + delta_2pi if left_limit <= to2 and to2 <= right_limit: # we can move in this direction: return success if the "from" angle is inside limits valid_flag = left_limit <= from_angle and from_angle <= right_limit return valid_flag, delta_2pi # nothing works: we always go outside limits return False, delta angles-1.9.13/angles/test/000077500000000000000000000000001363224353400153135ustar00rootroot00000000000000angles-1.9.13/angles/test/CMakeLists.txt000066400000000000000000000001761363224353400200570ustar00rootroot00000000000000if (CATKIN_ENABLE_TESTING) catkin_add_gtest(utest utest.cpp) catkin_add_nosetests(utest.py) endif (CATKIN_ENABLE_TESTING) angles-1.9.13/angles/test/utest.cpp000066400000000000000000000306121363224353400171650ustar00rootroot00000000000000#include "angles/angles.h" #include using namespace angles; TEST(Angles, shortestDistanceWithLimits){ double shortest_angle; bool result = angles::shortest_angular_distance_with_limits(-0.5, 0.5,-0.25,0.25,shortest_angle); EXPECT_FALSE(result); result = angles::shortest_angular_distance_with_limits(-0.5, 0.5,0.25,0.25,shortest_angle); EXPECT_FALSE(result); result = angles::shortest_angular_distance_with_limits(-0.5, 0.5,0.25,-0.25,shortest_angle); EXPECT_TRUE(result); EXPECT_NEAR(shortest_angle, -2*M_PI+1.0,1e-6); result = angles::shortest_angular_distance_with_limits(0.5, 0.5,0.25,-0.25,shortest_angle); EXPECT_TRUE(result); EXPECT_NEAR(shortest_angle, 0,1e-6); result = angles::shortest_angular_distance_with_limits(0.5, 0,0.25,-0.25,shortest_angle); EXPECT_FALSE(result); EXPECT_NEAR(shortest_angle, -0.5,1e-6); result = angles::shortest_angular_distance_with_limits(-0.5, 0,0.25,-0.25,shortest_angle); EXPECT_FALSE(result); EXPECT_NEAR(shortest_angle, 0.5,1e-6); result = angles::shortest_angular_distance_with_limits(-0.2,0.2,0.25,-0.25,shortest_angle); EXPECT_FALSE(result); EXPECT_NEAR(shortest_angle, -2*M_PI+0.4,1e-6); result = angles::shortest_angular_distance_with_limits(0.2,-0.2,0.25,-0.25,shortest_angle); EXPECT_FALSE(result); EXPECT_NEAR(shortest_angle,2*M_PI-0.4,1e-6); result = angles::shortest_angular_distance_with_limits(0.2,0,0.25,-0.25,shortest_angle); EXPECT_FALSE(result); EXPECT_NEAR(shortest_angle,2*M_PI-0.2,1e-6); result = angles::shortest_angular_distance_with_limits(-0.2,0,0.25,-0.25,shortest_angle); EXPECT_FALSE(result); EXPECT_NEAR(shortest_angle,-2*M_PI+0.2,1e-6); result = angles::shortest_angular_distance_with_limits(-0.25,-0.5,0.25,-0.25,shortest_angle); EXPECT_TRUE(result); EXPECT_NEAR(shortest_angle,-0.25,1e-6); result = angles::shortest_angular_distance_with_limits(-0.25,0.5,0.25,-0.25,shortest_angle); EXPECT_TRUE(result); EXPECT_NEAR(shortest_angle,-2*M_PI+0.75,1e-6); result = angles::shortest_angular_distance_with_limits(-0.2500001,0.5,0.25,-0.25,shortest_angle); EXPECT_TRUE(result); EXPECT_NEAR(shortest_angle,-2*M_PI+0.5+0.2500001,1e-6); result = angles::shortest_angular_distance_with_limits(-0.6, 0.5,-0.25,0.25,shortest_angle); EXPECT_FALSE(result); result = angles::shortest_angular_distance_with_limits(-0.5, 0.6,-0.25,0.25,shortest_angle); EXPECT_FALSE(result); result = angles::shortest_angular_distance_with_limits(-0.6, 0.75,-0.25,0.3,shortest_angle); EXPECT_FALSE(result); result = angles::shortest_angular_distance_with_limits(-0.6, M_PI*3.0/4.0,-0.25,0.3,shortest_angle); EXPECT_FALSE(result); result = angles::shortest_angular_distance_with_limits(-M_PI, M_PI,-M_PI,M_PI,shortest_angle); EXPECT_TRUE(result); EXPECT_NEAR(shortest_angle,0.0,1e-6); } TEST(Angles, shortestDistanceWithLargeLimits) { double shortest_angle; bool result; // 'delta' is valid result = angles::shortest_angular_distance_with_large_limits(0, 10.5*M_PI, -2*M_PI, 2*M_PI, shortest_angle); EXPECT_TRUE(result); EXPECT_NEAR(shortest_angle, 0.5*M_PI, 1e-6); // 'delta' is not valid, but 'delta_2pi' is result = angles::shortest_angular_distance_with_large_limits(0, 10.5*M_PI, -2*M_PI, 0.1*M_PI, shortest_angle); EXPECT_TRUE(result); EXPECT_NEAR(shortest_angle, -1.5*M_PI, 1e-6); // neither 'delta' nor 'delta_2pi' are valid result = angles::shortest_angular_distance_with_large_limits(2*M_PI, M_PI, 2*M_PI-0.1, 2*M_PI+0.1, shortest_angle); EXPECT_FALSE(result); // start position outside limits result = angles::shortest_angular_distance_with_large_limits(10.5*M_PI, 0, -2*M_PI, 2*M_PI, shortest_angle); EXPECT_FALSE(result); // invalid limits (lower > upper) result = angles::shortest_angular_distance_with_large_limits(0, 0.1, 2*M_PI, -2*M_PI, shortest_angle); EXPECT_FALSE(result); // specific test case result = angles::shortest_angular_distance_with_large_limits(0.999507, 1.0, -20*M_PI, 20*M_PI, shortest_angle); EXPECT_TRUE(result); EXPECT_NEAR(shortest_angle, 0.000493, 1e-6); } TEST(Angles, from_degrees) { double epsilon = 1e-9; EXPECT_NEAR(0, from_degrees(0), epsilon); EXPECT_NEAR(M_PI/2, from_degrees(90), epsilon); EXPECT_NEAR(M_PI, from_degrees(180), epsilon); EXPECT_NEAR(M_PI*3/2, from_degrees(270), epsilon); EXPECT_NEAR(2*M_PI, from_degrees(360), epsilon); EXPECT_NEAR(M_PI/3, from_degrees(60), epsilon); EXPECT_NEAR(M_PI*2/3, from_degrees(120), epsilon); EXPECT_NEAR(M_PI/4, from_degrees(45), epsilon); EXPECT_NEAR(M_PI*3/4, from_degrees(135), epsilon); EXPECT_NEAR(M_PI/6, from_degrees(30), epsilon); } TEST(Angles, to_degrees) { double epsilon = 1e-9; EXPECT_NEAR(to_degrees(0), 0, epsilon); EXPECT_NEAR(to_degrees(M_PI/2), 90, epsilon); EXPECT_NEAR(to_degrees(M_PI), 180, epsilon); EXPECT_NEAR(to_degrees(M_PI*3/2), 270, epsilon); EXPECT_NEAR(to_degrees(2*M_PI), 360, epsilon); EXPECT_NEAR(to_degrees(M_PI/3), 60, epsilon); EXPECT_NEAR(to_degrees(M_PI*2/3), 120, epsilon); EXPECT_NEAR(to_degrees(M_PI/4), 45, epsilon); EXPECT_NEAR(to_degrees(M_PI*3/4), 135, epsilon); EXPECT_NEAR(to_degrees(M_PI/6), 30, epsilon); } TEST(Angles, normalize_angle_positive) { double epsilon = 1e-9; EXPECT_NEAR(0, normalize_angle_positive(0), epsilon); EXPECT_NEAR(M_PI, normalize_angle_positive(M_PI), epsilon); EXPECT_NEAR(0, normalize_angle_positive(2*M_PI), epsilon); EXPECT_NEAR(M_PI, normalize_angle_positive(3*M_PI), epsilon); EXPECT_NEAR(0, normalize_angle_positive(4*M_PI), epsilon); EXPECT_NEAR(0, normalize_angle_positive(-0), epsilon); EXPECT_NEAR(M_PI, normalize_angle_positive(-M_PI), epsilon); EXPECT_NEAR(0, normalize_angle_positive(-2*M_PI), epsilon); EXPECT_NEAR(M_PI, normalize_angle_positive(-3*M_PI), epsilon); EXPECT_NEAR(0, normalize_angle_positive(-4*M_PI), epsilon); EXPECT_NEAR(0, normalize_angle_positive(-0), epsilon); EXPECT_NEAR(3*M_PI/2, normalize_angle_positive(-M_PI/2), epsilon); EXPECT_NEAR(M_PI, normalize_angle_positive(-M_PI), epsilon); EXPECT_NEAR(M_PI/2, normalize_angle_positive(-3*M_PI/2), epsilon); EXPECT_NEAR(0, normalize_angle_positive(-4*M_PI/2), epsilon); EXPECT_NEAR(0, normalize_angle_positive(0), epsilon); EXPECT_NEAR(M_PI/2, normalize_angle_positive(M_PI/2), epsilon); EXPECT_NEAR(M_PI/2, normalize_angle_positive(5*M_PI/2), epsilon); EXPECT_NEAR(M_PI/2, normalize_angle_positive(9*M_PI/2), epsilon); EXPECT_NEAR(M_PI/2, normalize_angle_positive(-3*M_PI/2), epsilon); } TEST(Angles, normalize_angle) { double epsilon = 1e-9; EXPECT_NEAR(0, normalize_angle(0), epsilon); EXPECT_NEAR(M_PI, normalize_angle(M_PI), epsilon); EXPECT_NEAR(0, normalize_angle(2*M_PI), epsilon); EXPECT_NEAR(M_PI, normalize_angle(3*M_PI), epsilon); EXPECT_NEAR(0, normalize_angle(4*M_PI), epsilon); EXPECT_NEAR(0, normalize_angle(-0), epsilon); EXPECT_NEAR(M_PI, normalize_angle(-M_PI), epsilon); EXPECT_NEAR(0, normalize_angle(-2*M_PI), epsilon); EXPECT_NEAR(M_PI, normalize_angle(-3*M_PI), epsilon); EXPECT_NEAR(0, normalize_angle(-4*M_PI), epsilon); EXPECT_NEAR(0, normalize_angle(-0), epsilon); EXPECT_NEAR(-M_PI/2, normalize_angle(-M_PI/2), epsilon); EXPECT_NEAR(M_PI, normalize_angle(-M_PI), epsilon); EXPECT_NEAR(M_PI/2, normalize_angle(-3*M_PI/2), epsilon); EXPECT_NEAR(0, normalize_angle(-4*M_PI/2), epsilon); EXPECT_NEAR(0, normalize_angle(0), epsilon); EXPECT_NEAR(M_PI/2, normalize_angle(M_PI/2), epsilon); EXPECT_NEAR(M_PI/2, normalize_angle(5*M_PI/2), epsilon); EXPECT_NEAR(M_PI/2, normalize_angle(9*M_PI/2), epsilon); EXPECT_NEAR(M_PI/2, normalize_angle(-3*M_PI/2), epsilon); } TEST(Angles, shortest_angular_distance) { double epsilon = 1e-9; EXPECT_NEAR(M_PI/2, shortest_angular_distance(0, M_PI/2), epsilon); EXPECT_NEAR(-M_PI/2, shortest_angular_distance(0, -M_PI/2), epsilon); EXPECT_NEAR(-M_PI/2, shortest_angular_distance(M_PI/2, 0), epsilon); EXPECT_NEAR(M_PI/2, shortest_angular_distance(-M_PI/2, 0), epsilon); EXPECT_NEAR(-M_PI/2, shortest_angular_distance(M_PI, M_PI/2), epsilon); EXPECT_NEAR(M_PI/2, shortest_angular_distance(M_PI, -M_PI/2), epsilon); EXPECT_NEAR(M_PI/2, shortest_angular_distance(M_PI/2, M_PI), epsilon); EXPECT_NEAR(-M_PI/2, shortest_angular_distance(-M_PI/2, M_PI), epsilon); EXPECT_NEAR(-M_PI/2, shortest_angular_distance(5*M_PI, M_PI/2), epsilon); EXPECT_NEAR(M_PI/2, shortest_angular_distance(7*M_PI, -M_PI/2), epsilon); EXPECT_NEAR(M_PI/2, shortest_angular_distance(9*M_PI/2, M_PI), epsilon); EXPECT_NEAR(M_PI/2, shortest_angular_distance(-3*M_PI/2, M_PI), epsilon); // Backside wrapping EXPECT_NEAR(-M_PI/2, shortest_angular_distance(-3*M_PI/4, 3*M_PI/4), epsilon); EXPECT_NEAR(M_PI/2, shortest_angular_distance(3*M_PI/4, -3*M_PI/4), epsilon); } TEST(Angles, two_pi_complement) { double epsilon = 1e-9; EXPECT_NEAR(two_pi_complement(0), 2*M_PI, epsilon); EXPECT_NEAR(two_pi_complement(2*M_PI), 0, epsilon); EXPECT_NEAR(two_pi_complement(-2*M_PI), 0, epsilon); EXPECT_NEAR(two_pi_complement(2*M_PI-epsilon), -epsilon, epsilon); EXPECT_NEAR(two_pi_complement(-2*M_PI+epsilon), epsilon, epsilon); EXPECT_NEAR(two_pi_complement(M_PI/2), -3*M_PI/2, epsilon); EXPECT_NEAR(two_pi_complement(M_PI), -M_PI, epsilon); EXPECT_NEAR(two_pi_complement(-M_PI), M_PI, epsilon); EXPECT_NEAR(two_pi_complement(-M_PI/2), 3*M_PI/2, epsilon); EXPECT_NEAR(two_pi_complement(3*M_PI), -M_PI, epsilon); EXPECT_NEAR(two_pi_complement(-3.0*M_PI), M_PI, epsilon); EXPECT_NEAR(two_pi_complement(-5.0*M_PI/2.0), 3*M_PI/2, epsilon); } TEST(Angles, find_min_max_delta) { double epsilon = 1e-9; double min_delta, max_delta; // Straight forward full range EXPECT_TRUE(find_min_max_delta( 0, -M_PI, M_PI, min_delta, max_delta)); EXPECT_NEAR(min_delta, -M_PI, epsilon); EXPECT_NEAR(max_delta, M_PI, epsilon); // M_PI/2 Full Range EXPECT_TRUE(find_min_max_delta( M_PI/2, -M_PI, M_PI, min_delta, max_delta)); EXPECT_NEAR(min_delta, -3*M_PI/2, epsilon); EXPECT_NEAR(max_delta, M_PI/2, epsilon); // -M_PI/2 Full range EXPECT_TRUE(find_min_max_delta( -M_PI/2, -M_PI, M_PI, min_delta, max_delta)); EXPECT_NEAR(min_delta, -M_PI/2, epsilon); EXPECT_NEAR(max_delta, 3*M_PI/2, epsilon); // Straight forward partial range EXPECT_TRUE(find_min_max_delta( 0, -M_PI/2, M_PI/2, min_delta, max_delta)); EXPECT_NEAR(min_delta, -M_PI/2, epsilon); EXPECT_NEAR(max_delta, M_PI/2, epsilon); // M_PI/4 Partial Range EXPECT_TRUE(find_min_max_delta( M_PI/4, -M_PI/2, M_PI/2, min_delta, max_delta)); EXPECT_NEAR(min_delta, -3*M_PI/4, epsilon); EXPECT_NEAR(max_delta, M_PI/4, epsilon); // -M_PI/4 Partial Range EXPECT_TRUE(find_min_max_delta( -M_PI/4, -M_PI/2, M_PI/2, min_delta, max_delta)); EXPECT_NEAR(min_delta, -M_PI/4, epsilon); EXPECT_NEAR(max_delta, 3*M_PI/4, epsilon); // bump stop negative full range EXPECT_TRUE(find_min_max_delta( -M_PI, -M_PI, M_PI, min_delta, max_delta)); EXPECT_TRUE((fabs(min_delta) <= epsilon && fabs(max_delta - 2*M_PI) <= epsilon) || (fabs(min_delta+2*M_PI) <= epsilon && fabs(max_delta) <= epsilon)); EXPECT_NEAR(min_delta, 0.0, epsilon); EXPECT_NEAR(max_delta, 2*M_PI, epsilon); EXPECT_TRUE(find_min_max_delta(-0.25,0.25,-0.25,min_delta, max_delta)); EXPECT_NEAR(min_delta, -2*M_PI+0.5, epsilon); EXPECT_NEAR(max_delta, 0.0, epsilon); // bump stop positive full range EXPECT_TRUE(find_min_max_delta( M_PI-epsilon, -M_PI, M_PI, min_delta, max_delta)); //EXPECT_TRUE((fabs(min_delta) <= epsilon && fabs(max_delta - 2*M_PI) <= epsilon) || (fabs(min_delta+2*M_PI) <= epsilon && fabs(max_delta) <= epsilon)); EXPECT_NEAR(min_delta, -2*M_PI+epsilon, epsilon); EXPECT_NEAR(max_delta, epsilon, epsilon); // bump stop negative partial range EXPECT_TRUE(find_min_max_delta( -M_PI, -M_PI, M_PI, min_delta, max_delta)); EXPECT_NEAR(min_delta, 0, epsilon); EXPECT_NEAR(max_delta, 2*M_PI, epsilon); // bump stop positive partial range EXPECT_TRUE(find_min_max_delta( -M_PI/2, -M_PI/2, M_PI/2, min_delta, max_delta)); EXPECT_NEAR(min_delta, 0.0, epsilon); EXPECT_NEAR(max_delta, M_PI, epsilon); //Test out of range negative EXPECT_FALSE(find_min_max_delta( -M_PI, -M_PI/2, M_PI/2, min_delta, max_delta)); //Test out of range postive EXPECT_FALSE(find_min_max_delta( M_PI, -M_PI/2, M_PI/2, min_delta, max_delta)); // M_PI/4 Partial Range EXPECT_TRUE(find_min_max_delta( 3*M_PI/4, M_PI/2, -M_PI/2, min_delta, max_delta)); EXPECT_NEAR(min_delta, -M_PI/4, epsilon); EXPECT_NEAR(max_delta, 3*M_PI/4, epsilon); } int main(int argc, char **argv){ testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } angles-1.9.13/angles/test/utest.py000066400000000000000000000345621363224353400170430ustar00rootroot00000000000000#!/usr/bin/env python #********************************************************************* # Software License Agreement (BSD License) # # Copyright (c) 2015, Bossa Nova Robotics # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above # copyright notice, this list of conditions and the following # disclaimer in the documentation and/or other materials provided # with the distribution. # * Neither the name of the Bossa Nova Robotics nor the names of its # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. #********************************************************************/ from angles import normalize_angle_positive, normalize_angle, shortest_angular_distance, two_pi_complement, shortest_angular_distance_with_limits, shortest_angular_distance_with_large_limits from angles import _find_min_max_delta import sys import unittest from math import pi, fabs ## A sample python unit test class TestAngles(unittest.TestCase): def test_shortestDistanceWithLimits(self): result, shortest_angle = shortest_angular_distance_with_limits(-0.5, 0.5,-0.25,0.25) self.assertFalse(result) result, shortest_angle = shortest_angular_distance_with_limits(-0.5, 0.5,0.25,0.25) self.assertFalse(result) result, shortest_angle = shortest_angular_distance_with_limits(-0.5, 0.5,0.25,-0.25) self.assertTrue(result) self.assertAlmostEqual(shortest_angle, -2*pi+1.0) result, shortest_angle = shortest_angular_distance_with_limits(0.5, 0.5,0.25,-0.25) self.assertTrue(result) self.assertAlmostEqual(shortest_angle, 0) result, shortest_angle = shortest_angular_distance_with_limits(0.5, 0,0.25,-0.25) self.assertFalse(result) self.assertAlmostEqual(shortest_angle, -0.5) result, shortest_angle = shortest_angular_distance_with_limits(-0.5, 0,0.25,-0.25) self.assertFalse(result) self.assertAlmostEqual(shortest_angle, 0.5) result, shortest_angle = shortest_angular_distance_with_limits(-0.2,0.2,0.25,-0.25) self.assertFalse(result) self.assertAlmostEqual(shortest_angle, -2*pi+0.4) result, shortest_angle = shortest_angular_distance_with_limits(0.2,-0.2,0.25,-0.25) self.assertFalse(result) self.assertAlmostEqual(shortest_angle,2*pi-0.4) result, shortest_angle = shortest_angular_distance_with_limits(0.2,0,0.25,-0.25) self.assertFalse(result) self.assertAlmostEqual(shortest_angle,2*pi-0.2) result, shortest_angle = shortest_angular_distance_with_limits(-0.2,0,0.25,-0.25) self.assertFalse(result) self.assertAlmostEqual(shortest_angle,-2*pi+0.2) result, shortest_angle = shortest_angular_distance_with_limits(-0.25,-0.5,0.25,-0.25) self.assertTrue(result) self.assertAlmostEqual(shortest_angle,-0.25) result, shortest_angle = shortest_angular_distance_with_limits(-0.25,0.5,0.25,-0.25) self.assertTrue(result) self.assertAlmostEqual(shortest_angle,-2*pi+0.75) result, shortest_angle = shortest_angular_distance_with_limits(-0.2500001,0.5,0.25,-0.25) self.assertTrue(result) self.assertAlmostEqual(shortest_angle,-2*pi+0.5+0.2500001) result, shortest_angle = shortest_angular_distance_with_limits(-0.6, 0.5,-0.25,0.25) self.assertFalse(result) result, shortest_angle = shortest_angular_distance_with_limits(-0.5, 0.6,-0.25,0.25) self.assertFalse(result) result, shortest_angle = shortest_angular_distance_with_limits(-0.6, 0.75,-0.25,0.3) self.assertFalse(result) result, shortest_angle = shortest_angular_distance_with_limits(-0.6, pi*3.0/4.0,-0.25,0.3) self.assertFalse(result) result, shortest_angle = shortest_angular_distance_with_limits(-pi, pi,-pi,pi) self.assertTrue(result) self.assertAlmostEqual(shortest_angle,0.0) def test_shortestDistanceWithLargeLimits(self): # 'delta' is valid result, shortest_angle = shortest_angular_distance_with_large_limits(0, 10.5*pi, -2*pi, 2*pi) self.assertTrue(result) self.assertAlmostEqual(shortest_angle, 0.5*pi) # 'delta' is not valid, but 'delta_2pi' is result, shortest_angle = shortest_angular_distance_with_large_limits(0, 10.5*pi, -2*pi, 0.1*pi) self.assertTrue(result) self.assertAlmostEqual(shortest_angle, -1.5*pi) # neither 'delta' nor 'delta_2pi' are valid result, shortest_angle = shortest_angular_distance_with_large_limits(2*pi, pi, 2*pi-0.1, 2*pi+0.1) self.assertFalse(result) # start position outside limits result, shortest_angle = shortest_angular_distance_with_large_limits(10.5*pi, 0, -2*pi, 2*pi) self.assertFalse(result) # invalid limits (lower > upper) result, shortest_angle = shortest_angular_distance_with_large_limits(0, 0.1, 2*pi, -2*pi) self.assertFalse(result) # specific test case result, shortest_angle = shortest_angular_distance_with_large_limits(0.999507, 1.0, -20*pi, 20*pi) self.assertTrue(result) self.assertAlmostEqual(shortest_angle, 0.000493) def test_normalize_angle_positive(self): self.assertAlmostEqual(0, normalize_angle_positive(0)) self.assertAlmostEqual(pi, normalize_angle_positive(pi)) self.assertAlmostEqual(0, normalize_angle_positive(2*pi)) self.assertAlmostEqual(pi, normalize_angle_positive(3*pi)) self.assertAlmostEqual(0, normalize_angle_positive(4*pi)) self.assertAlmostEqual(0, normalize_angle_positive(-0)) self.assertAlmostEqual(pi, normalize_angle_positive(-pi)) self.assertAlmostEqual(0, normalize_angle_positive(-2*pi)) self.assertAlmostEqual(pi, normalize_angle_positive(-3*pi)) self.assertAlmostEqual(0, normalize_angle_positive(-4*pi)) self.assertAlmostEqual(0, normalize_angle_positive(-0)) self.assertAlmostEqual(3*pi/2, normalize_angle_positive(-pi/2)) self.assertAlmostEqual(pi, normalize_angle_positive(-pi)) self.assertAlmostEqual(pi/2, normalize_angle_positive(-3*pi/2)) self.assertAlmostEqual(0, normalize_angle_positive(-4*pi/2)) self.assertAlmostEqual(0, normalize_angle_positive(0)) self.assertAlmostEqual(pi/2, normalize_angle_positive(pi/2)) self.assertAlmostEqual(pi/2, normalize_angle_positive(5*pi/2)) self.assertAlmostEqual(pi/2, normalize_angle_positive(9*pi/2)) self.assertAlmostEqual(pi/2, normalize_angle_positive(-3*pi/2)) def test_normalize_angle(self): self.assertAlmostEqual(0, normalize_angle(0)) self.assertAlmostEqual(pi, normalize_angle(pi)) self.assertAlmostEqual(0, normalize_angle(2*pi)) self.assertAlmostEqual(pi, normalize_angle(3*pi)) self.assertAlmostEqual(0, normalize_angle(4*pi)) self.assertAlmostEqual(0, normalize_angle(-0)) self.assertAlmostEqual(pi, normalize_angle(-pi)) self.assertAlmostEqual(0, normalize_angle(-2*pi)) self.assertAlmostEqual(pi, normalize_angle(-3*pi)) self.assertAlmostEqual(0, normalize_angle(-4*pi)) self.assertAlmostEqual(0, normalize_angle(-0)) self.assertAlmostEqual(-pi/2, normalize_angle(-pi/2)) self.assertAlmostEqual(pi, normalize_angle(-pi)) self.assertAlmostEqual(pi/2, normalize_angle(-3*pi/2)) self.assertAlmostEqual(0, normalize_angle(-4*pi/2)) self.assertAlmostEqual(0, normalize_angle(0)) self.assertAlmostEqual(pi/2, normalize_angle(pi/2)) self.assertAlmostEqual(pi/2, normalize_angle(5*pi/2)) self.assertAlmostEqual(pi/2, normalize_angle(9*pi/2)) self.assertAlmostEqual(pi/2, normalize_angle(-3*pi/2)) def test_shortest_angular_distance(self): self.assertAlmostEqual(pi/2, shortest_angular_distance(0, pi/2)) self.assertAlmostEqual(-pi/2, shortest_angular_distance(0, -pi/2)) self.assertAlmostEqual(-pi/2, shortest_angular_distance(pi/2, 0)) self.assertAlmostEqual(pi/2, shortest_angular_distance(-pi/2, 0)) self.assertAlmostEqual(-pi/2, shortest_angular_distance(pi, pi/2)) self.assertAlmostEqual(pi/2, shortest_angular_distance(pi, -pi/2)) self.assertAlmostEqual(pi/2, shortest_angular_distance(pi/2, pi)) self.assertAlmostEqual(-pi/2, shortest_angular_distance(-pi/2, pi)) self.assertAlmostEqual(-pi/2, shortest_angular_distance(5*pi, pi/2)) self.assertAlmostEqual(pi/2, shortest_angular_distance(7*pi, -pi/2)) self.assertAlmostEqual(pi/2, shortest_angular_distance(9*pi/2, pi)) self.assertAlmostEqual(pi/2, shortest_angular_distance(-3*pi/2, pi)) # Backside wrapping self.assertAlmostEqual(-pi/2, shortest_angular_distance(-3*pi/4, 3*pi/4)) self.assertAlmostEqual(pi/2, shortest_angular_distance(3*pi/4, -3*pi/4)) def test_two_pi_complement(self): epsilon = 1e-9 self.assertAlmostEqual(two_pi_complement(0), 2*pi) self.assertAlmostEqual(two_pi_complement(2*pi), 0) self.assertAlmostEqual(two_pi_complement(-2*pi), 0) self.assertAlmostEqual(two_pi_complement(2*pi-epsilon), -epsilon) self.assertAlmostEqual(two_pi_complement(-2*pi+epsilon), epsilon) self.assertAlmostEqual(two_pi_complement(pi/2), -3*pi/2) self.assertAlmostEqual(two_pi_complement(pi), -pi) self.assertAlmostEqual(two_pi_complement(-pi), pi) self.assertAlmostEqual(two_pi_complement(-pi/2), 3*pi/2) self.assertAlmostEqual(two_pi_complement(3*pi), -pi) self.assertAlmostEqual(two_pi_complement(-3.0*pi), pi) self.assertAlmostEqual(two_pi_complement(-5.0*pi/2.0), 3*pi/2) def test_find_min_max_delta(self): epsilon = 1e-9 # Straight forward full range flag, min_delta, max_delta = _find_min_max_delta( 0, -pi, pi) self.assertTrue(flag) self.assertAlmostEqual(min_delta, -pi) self.assertAlmostEqual(max_delta, pi) # pi/2 Full Range flag, min_delta, max_delta = _find_min_max_delta( pi/2, -pi, pi) self.assertTrue(flag) self.assertAlmostEqual(min_delta, -3*pi/2) self.assertAlmostEqual(max_delta, pi/2) # -pi/2 Full range flag, min_delta, max_delta = _find_min_max_delta( -pi/2, -pi, pi) self.assertTrue(flag) self.assertAlmostEqual(min_delta, -pi/2) self.assertAlmostEqual(max_delta, 3*pi/2) # Straight forward partial range flag, min_delta, max_delta = _find_min_max_delta( 0, -pi/2, pi/2) self.assertTrue(flag) self.assertAlmostEqual(min_delta, -pi/2) self.assertAlmostEqual(max_delta, pi/2) # pi/4 Partial Range flag, min_delta, max_delta = _find_min_max_delta( pi/4, -pi/2, pi/2) self.assertTrue(flag) self.assertAlmostEqual(min_delta, -3*pi/4) self.assertAlmostEqual(max_delta, pi/4) # -pi/4 Partial Range flag, min_delta, max_delta = _find_min_max_delta( -pi/4, -pi/2, pi/2) self.assertTrue(flag) self.assertAlmostEqual(min_delta, -pi/4) self.assertAlmostEqual(max_delta, 3*pi/4) # bump stop negative full range flag, min_delta, max_delta = _find_min_max_delta( -pi, -pi, pi) self.assertTrue(flag) self.assertTrue((fabs(min_delta) <= epsilon and fabs(max_delta - 2*pi) <= epsilon) or (fabs(min_delta+2*pi) <= epsilon and fabs(max_delta) <= epsilon)) self.assertAlmostEqual(min_delta, 0.0) self.assertAlmostEqual(max_delta, 2*pi) flag, min_delta, max_delta = _find_min_max_delta(-0.25,0.25,-0.25) self.assertTrue(flag) self.assertAlmostEqual(min_delta, -2*pi+0.5) self.assertAlmostEqual(max_delta, 0.0) # bump stop positive full range flag, min_delta, max_delta = _find_min_max_delta( pi-epsilon, -pi, pi) self.assertTrue(flag) #self.assertTrue((fabs(min_delta) <= epsilon and fabs(max_delta - 2*pi) <= epsilon) or (fabs(min_delta+2*pi) <= epsilon and fabs(max_delta) <= epsilon)) self.assertAlmostEqual(min_delta, -2*pi+epsilon) self.assertAlmostEqual(max_delta, epsilon) # bump stop negative partial range flag, min_delta, max_delta = _find_min_max_delta( -pi, -pi, pi) self.assertTrue(flag) self.assertAlmostEqual(min_delta, 0) self.assertAlmostEqual(max_delta, 2*pi) # bump stop positive partial range flag, min_delta, max_delta = _find_min_max_delta( -pi/2, -pi/2, pi/2) self.assertTrue(flag) self.assertAlmostEqual(min_delta, 0.0) self.assertAlmostEqual(max_delta, pi) #Test out of range negative flag, min_delta, max_delta = _find_min_max_delta( -pi, -pi/2, pi/2) self.assertFalse(flag) #Test out of range postive flag, min_delta, max_delta = _find_min_max_delta( pi, -pi/2, pi/2) self.assertFalse(flag) # pi/4 Partial Range flag, min_delta, max_delta = _find_min_max_delta( 3*pi/4, pi/2, -pi/2) self.assertTrue(flag) self.assertAlmostEqual(min_delta, -pi/4) self.assertAlmostEqual(max_delta, 3*pi/4) if __name__ == '__main__': import rosunit rosunit.unitrun('angles', 'test_python_angles', TestAngles)