__init__.py
Go to the documentation of this file.
1 #*********************************************************************
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2015, Bossa Nova Robotics
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 Bossa Nova Robotics 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 
35 from math import fmod, pi, fabs
36 
38  """ Normalizes the angle to be 0 to 2*pi
39  It takes and returns radians. """
40  return angle % (2.0*pi)
41 
42 def normalize_angle(angle):
43  """ Normalizes the angle to be -pi to +pi
44  It takes and returns radians."""
45  a = normalize_angle_positive(angle)
46  if a > pi:
47  a -= 2.0 *pi
48  return a
49 
50 def shortest_angular_distance(from_angle, to_angle):
51  """ Given 2 angles, this returns the shortest angular
52  difference. The inputs and ouputs are of course radians.
53 
54  The result would always be -pi <= result <= pi. Adding the result
55  to "from" will always get you an equivelent angle to "to".
56  """
57  return normalize_angle(to_angle-from_angle)
58 
59 def two_pi_complement(angle):
60  """ returns the angle in [-2*pi, 2*pi] going the other way along the unit circle.
61  \param angle The angle to which you want to turn in the range [-2*pi, 2*pi]
62  E.g. two_pi_complement(-pi/4) returns 7_pi/4
63  two_pi_complement(pi/4) returns -7*pi/4
64  """
65  #check input conditions
66  if angle > 2*pi or angle < -2.0*pi:
67  angle = fmod(angle, 2.0*pi)
68  if angle < 0:
69  return 2*pi+angle
70  elif angle > 0:
71  return -2*pi+angle
72 
73  return 2*pi
74 
75 def _find_min_max_delta(from_angle, left_limit, right_limit):
76  """ This function is only intended for internal use and not intended for external use.
77  If you do use it, read the documentation very carefully.
78 
79  Returns the min and max amount (in radians) that can be moved
80  from "from" angle to "left_limit" and "right_limit".
81 
82  \param from - "from" angle - must lie in [-pi, pi)
83  \param left_limit - left limit of valid interval for angular position
84  - must lie in [-pi, pi], left and right limits are specified on
85  the unit circle w.r.t to a reference pointing inwards
86  \param right_limit - right limit of valid interval for angular position
87  - must lie in [-pi, pi], left and right limits are specified on
88  the unit circle w.r.t to a reference pointing inwards
89  \return (valid, min, max) - angle in radians that can be moved from "from" position before hitting the joint stop
90  valid is False if "from" angle does not lie in the interval [left_limit,right_limit]
91  """
92  delta = [0]*4
93  delta[0] = shortest_angular_distance(from_angle,left_limit)
94  delta[1] = shortest_angular_distance(from_angle,right_limit)
95  delta[2] = two_pi_complement(delta[0])
96  delta[3] = two_pi_complement(delta[1])
97 
98  if delta[0] == 0:
99  return True, delta[0], max(delta[1], delta[3])
100 
101  if delta[1] == 0:
102  return True, min(delta[0], delta[2]), delta[1]
103 
104  delta_min = delta[0]
105  delta_min_2pi = delta[2]
106  if delta[2] < delta_min:
107  delta_min = delta[2]
108  delta_min_2pi = delta[0]
109 
110  delta_max = delta[1]
111  delta_max_2pi = delta[3]
112  if delta[3] > delta_max:
113  delta_max = delta[3]
114  delta_max_2pi = delta[1]
115 
116  # printf("%f %f %f %f\n",delta_min,delta_min_2pi,delta_max,delta_max_2pi)
117  if (delta_min <= delta_max_2pi) or (delta_max >= delta_min_2pi):
118  if left_limit == -pi and right_limit == pi:
119  return (True, delta_max_2pi, delta_min_2pi)
120  else:
121  return (False, delta_max_2pi, delta_min_2pi)
122  return True, delta_min, delta_max
123 
124 def shortest_angular_distance_with_limits(from_angle, to_angle, left_limit, right_limit):
125  """ Returns the delta from "from_angle" to "to_angle" making sure it does not violate limits specified by left_limit and right_limit.
126  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.
127  But [0.25,-0.25] is a 2*pi-0.5 wide interval that contains pi (but not 0).
128  The value of shortest_angle is the angular difference between "from" and "to" that lies within the defined valid interval.
129 
130  E.g. shortest_angular_distance_with_limits(-0.5,0.5,0.25,-0.25) returns 2*pi-1.0
131  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]
132 
133  \param left_limit - left limit of valid interval for angular position
134  - must lie in [-pi, pi], left and right limits are specified on
135  the unit circle w.r.t to a reference pointing inwards
136  \param right_limit - right limit of valid interval for angular position
137  - must lie in [-pi, pi], left and right limits are specified on
138  the unit circle w.r.t to a reference pointing inwards
139  \returns valid_flag, shortest_angle
140  """
141  min_delta = -2*pi
142  max_delta = 2*pi
143  min_delta_to = -2*pi
144  max_delta_to = 2*pi
145  flag, min_delta, max_delta = _find_min_max_delta(from_angle, left_limit, right_limit)
146  delta = shortest_angular_distance(from_angle,to_angle)
147  delta_mod_2pi = two_pi_complement(delta)
148 
149  if flag: #from position is within the limits
150  if delta >= min_delta and delta <= max_delta:
151  return True, delta
152  elif delta_mod_2pi >= min_delta and delta_mod_2pi <= max_delta:
153  return True, delta_mod_2pi
154  else: #to position is outside the limits
155  flag, min_delta_to, max_delta_to = _find_min_max_delta(to_angle,left_limit,right_limit)
156  if fabs(min_delta_to) < fabs(max_delta_to):
157  shortest_angle = max(delta, delta_mod_2pi)
158  elif fabs(min_delta_to) > fabs(max_delta_to):
159  shortest_angle = min(delta,delta_mod_2pi)
160  else:
161  if fabs(delta) < fabs(delta_mod_2pi):
162  shortest_angle = delta
163  else:
164  shortest_angle = delta_mod_2pi
165  return False, shortest_angle
166  else: # from position is outside the limits
167  flag, min_delta_to, max_delta_to = _find_min_max_delta(to_angle,left_limit,right_limit)
168 
169  if fabs(min_delta) < fabs(max_delta):
170  shortest_angle = min(delta,delta_mod_2pi)
171  elif fabs(min_delta) > fabs(max_delta):
172  shortest_angle = max(delta,delta_mod_2pi)
173  else:
174  if fabs(delta) < fabs(delta_mod_2pi):
175  shortest_angle = delta
176  else:
177  shortest_angle = delta_mod_2pi
178  return False, shortest_angle
179 
180 def shortest_angular_distance_with_large_limits(from_angle, to_angle, left_limit, right_limit):
181  """ Returns the delta from `from_angle` to `to_angle`, making sure it does not violate limits specified by `left_limit` and `right_limit`.
182  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.
183  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]`.
184 
185  In this case, a strict requirement is to have `left_limit` smaller than `right_limit`.
186  Note also that `from_angle` must lie inside the valid range, while `to_angle` does not need to.
187  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`.
188  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`.
189  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)`.
190  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.
191  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`.
192  However, `shortest_angle` in this case will be `-1.5*M_PI`.
193 
194  \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.
195  \param left_limit - left limit of valid interval, must be smaller than right_limit.
196  \param right_limit - right limit of valid interval, must be greater than left_limit.
197  """
198  # Shortest steps in the two directions
199  delta = shortest_angular_distance(from_angle, to_angle)
200  delta_2pi = two_pi_complement(delta)
201 
202  # "sort" distances so that delta is shorter than delta_2pi
203  if fabs(delta) > fabs(delta_2pi):
204  delta, delta_2pi = delta_2pi, delta
205 
206  if left_limit > right_limit:
207  # If limits are something like [PI/2 , -PI/2] it actually means that we
208  # want rotations to be in the interval [-PI,PI/2] U [PI/2,PI], ie, the
209  # half unit circle not containing the 0. This is already gracefully
210  # handled by shortest_angular_distance_with_limits, and therefore this
211  # function should not be called at all. However, if one has limits that
212  # are larger than PI, the same rationale behind shortest_angular_distance_with_limits
213  # does not hold, ie, M_PI+x should not be directly equal to -M_PI+x.
214  # In this case, the correct way of getting the shortest solution is to
215  # properly set the limits, eg, by saying that the interval is either
216  # [PI/2, 3*PI/2] or [-3*M_PI/2, -M_PI/2]. For this reason, here we
217  # return false by default.
218  return False, delta
219 
220 
221  # Check in which direction we should turn (clockwise or counter-clockwise).
222 
223  # start by trying with the shortest angle (delta).
224  to2 = from_angle + delta
225  if left_limit <= to2 and to2 <= right_limit:
226  # we can move in this direction: return success if the "from" angle is inside limits
227  valid_flag = left_limit <= from_angle and from_angle <= right_limit
228  return valid_flag, delta
229 
230  # delta is not ok, try to move in the other direction (using its complement)
231  to2 = from_angle + delta_2pi
232  if left_limit <= to2 and to2 <= right_limit:
233  # we can move in this direction: return success if the "from" angle is inside limits
234  valid_flag = left_limit <= from_angle and from_angle <= right_limit
235  return valid_flag, delta_2pi
236 
237  # nothing works: we always go outside limits
238  return False, delta
static bool shortest_angular_distance_with_limits(double from, double to, double left_limit, double right_limit, double &shortest_angle)
Returns the delta from "from_angle" to "to_angle" making sure it does not violate limits specified by...
Definition: angles.h:289
static double shortest_angular_distance(double from, double to)
shortest_angular_distance
Definition: angles.h:103
static double normalize_angle(double angle)
normalize
Definition: angles.h:83
static bool shortest_angular_distance_with_large_limits(double from, double to, double left_limit, double right_limit, double &shortest_angle)
Returns the delta from from_angle to to_angle, making sure it does not violate limits specified by le...
Definition: angles.h:222
static double normalize_angle_positive(double angle)
normalize_angle_positive
Definition: angles.h:68
static double two_pi_complement(double angle)
returns the angle in [-2*M_PI, 2*M_PI] going the other way along the unit circle. ...
Definition: angles.h:117
def _find_min_max_delta(from_angle, left_limit, right_limit)
Definition: __init__.py:75


angles
Author(s): John Hsu
autogenerated on Fri Mar 13 2020 03:55:59