blob: 611012e3540f87a68f353d0a66e19a69a198c95e [file] [log] [blame]
Brian Silvermanb691f5e2015-08-02 11:37:55 -07001#ifndef Y2015_UTIL_KINEMATICS_H_
2#define Y2015_UTIL_KINEMATICS_H_
Benjamin Fredricksona74b0bd2015-03-07 00:32:52 -08003
4#include <cmath>
5#include "Eigen/Dense"
Brian Silvermanb691f5e2015-08-02 11:37:55 -07006#include "y2015/constants.h"
Benjamin Fredricksona74b0bd2015-03-07 00:32:52 -08007
8namespace aos {
9namespace util {
10
11// A class for performing forward and inverse kinematics on the elevator-arm
12// system. It can calculate where the fridge grabbers will be if the arm and
13// elevator are at a given position, as well as where the arm and elevator
14// should go in order to get the grabbers to a specific location.
15class ElevatorArmKinematics {
16 public:
17 typedef enum {
18 // These specify the particular region that an invalid request was in. Right
19 // is toward the front of the robot, left is toward the back.
20
21 // Request is valid.
22 REGION_VALID = 0,
23 // Request is farther right than the arm can extend.
24 REGION_RIGHT = 1 << 0,
25 // Request is towards the front of the robot but higher than we can extend
26 // with the elevator and the arm.
27 REGION_UPPER_RIGHT = 1 << 1,
28 // We can get the x part of the request, which is towards the front of the
29 // robot, but not the h part, which is too high.
30 REGION_INSIDE_UPPER_RIGHT = 1 << 2,
31 // We can get the x part of the request, which is towards the front of the
32 // robot, but not the h part, which is too low.
33 REGION_INSIDE_LOWER_RIGHT = 1 << 3,
34 // Request is towards the front of the robot but lower than we can extend
35 // with the elevator and the arm.
36 REGION_LOWER_RIGHT = 1 << 4,
37 // Request is farther left than the arm can extend.
38 REGION_LEFT = 1 << 5,
39 // Request is towards the back of the robot but higher than we can extend
40 // with the elevator and the arm.
41 REGION_UPPER_LEFT = 1 << 6,
42 // We can get the x part of the request, which is towards the front of the
43 // robot, but not the h part, which is too high.
44 REGION_INSIDE_UPPER_LEFT = 1 << 7,
45 // We can get the x part of the request, which is towards the back of the
46 // robot, but not the h part, which is too low.
47 REGION_INSIDE_LOWER_LEFT = 1 << 8,
48 // Request is towards the back of the robot but lower than we can extend
49 // with the elevator and the arm.
50 REGION_LOWER_LEFT = 1 << 9,
51 // Request is invalid, but don't know where it is out of range.
52 REGION_UNKNOWN = 1 << 10,
53 } Region;
54
55 class KinematicResult {
56 public:
57 // The elevator height result from an inverse kinematic.
58 double elevator_height;
59 // The arm angle result from an inverse kinematic.
60 double arm_angle;
61 // Resulting velocity of the elevator given x,y velocities.
62 double elevator_velocity;
63 // Resulting velocity of the arm given x,y velocities.
64 double arm_velocity;
65 // The fridge height value from a forward kinematic.
66 double fridge_h;
67 // The fridge x value from a forward kinematic.
68 double fridge_x;
69 // Resulting velocity of the fridge height given arm and elevator
70 // velocities.
71 double fridge_h_velocity;
72 // Resulting velocity of the fridge x given arm and elevator velocities.
73 double fridge_x_velocity;
74 };
75
76 // If we use the default constructor we wil just always not be able to move.
77 ElevatorArmKinematics()
78 : length_arm_(1.0),
79 elevator_max_(0.0),
80 elevator_min_(0.0),
81 upper_angle_limit_(0.0),
82 lower_angle_limit_(0.0) {}
83
84 ElevatorArmKinematics(double length_arm, double height_max, double height_min,
85 double angle_max, double angle_min)
86 : length_arm_(length_arm),
87 elevator_max_(height_max),
88 elevator_min_(height_min),
89 upper_angle_limit_(angle_max),
90 lower_angle_limit_(angle_min),
91 geometry_(frc971::constants::GetValues().clawGeometry) {}
92
93 ~ElevatorArmKinematics() {}
94
95 // Limit a number to the speed of light. The loops should handle this a lot
96 // better than overflow.
97 void LimitLightSpeed(double* num) {
98 if (*num > 299792458.0) {
99 *num = 299792458.0;
100 }
101 if (*num < -299792458.0) {
102 *num = -299792458.0;
103 }
104 if (!::std::isfinite(*num)) {
105 *num = 0.0;
106 }
107 }
108
109 // Calculates the arm angle in radians and the elevator height in meters for
110 // a desired Fridge grabber height and x location. x is positive going
111 // toward the front of the robot.
112 // h is positive going up. x=0 and h=0 is the location of the top fridge
113 // grabber when the elevator is at 0 height and the arm angle is 0 (vertical).
114 // Both the x and h values are given in meters.
115 // Returns the region of the request.
116 // Result is:
117 // the angle of the arm in radians
118 // the height of the elevator in meters
119 // the resulting x
120 // and the resulting h
121 // If an impossible location is requested, the arm angle and elevator height
122 // returned are the closest possible for the requested fridge grabber height.
123 // If the requested height is above the max possible height, the angle
124 // will be 0 and the height will be the max possible height of the elevator.
125 int InverseKinematic(double request_x, double request_h,
126 double request_x_velocity, double request_y_velocity,
127 KinematicResult* result) {
128 int valid_or_invalid = REGION_VALID;
129
130 double square_arm = length_arm_ * length_arm_;
131 double term = ::std::sqrt(square_arm - request_x * request_x);
132
133 // Check to see if the x location can be satisfied. If the requested x
134 // location
135 // is further out than the arm can go, it is not possible for any elevator
136 // location.
137 if (request_x > length_arm_) {
138 result->arm_angle = -M_PI * 0.5;
139 valid_or_invalid |= REGION_RIGHT;
140 } else if (request_x < -length_arm_) {
141 result->arm_angle = M_PI * 0.5;
142 valid_or_invalid |= REGION_LEFT;
143 } else {
144 result->arm_angle = ::std::asin(-request_x / length_arm_);
145 result->arm_velocity = (-1.0 / term) * request_x_velocity;
146 LimitLightSpeed(&result->arm_velocity);
147 }
148
149 result->elevator_height =
150 request_h + length_arm_ * (1.0 - ::std::cos(result->arm_angle));
151 result->elevator_velocity =
152 (request_x / (square_arm * term)) * request_x_velocity +
153 request_y_velocity;
154 LimitLightSpeed(&result->elevator_velocity);
155
156 // Check to see if the requested elevator height is possible
157 if (request_h > elevator_max_) {
158 // The elevator cannot go high enough with any arm angle to satisfy this
159 // request. So position the elevator at the top and the arm angle set to
160 // vertical.
161 result->elevator_height = elevator_max_;
162 result->arm_angle = 0.0;
163 if (request_x >= 0) {
164 valid_or_invalid |= REGION_UPPER_RIGHT;
165 } else {
166 valid_or_invalid |= REGION_UPPER_LEFT;
167 }
168 } else if (request_h < -length_arm_ + elevator_min_) {
169 // The elevator cannot go low enough with any arm angle to satisfy this
170 // request. So position the elevator at the bottom and the arm angle to
171 // satisfy the x request The elevator will move up as the grabber moves to
172 // the center of the robot when in this part of the motion space.
173 result->elevator_height = elevator_min_;
174 if (request_x >= 0) {
175 valid_or_invalid |= REGION_LOWER_RIGHT;
176 } else {
177 valid_or_invalid |= REGION_LOWER_LEFT;
178 }
179 } else if (result->elevator_height > elevator_max_) {
180 // Impossibly high request. So get as close to the x request with the
181 // elevator at the top of its range.
182 result->elevator_height = elevator_max_;
183 if (request_x >= 0) {
184 result->arm_angle =
185 -::std::acos((length_arm_ + request_h - elevator_max_) /
186 length_arm_);
187 valid_or_invalid |= REGION_INSIDE_UPPER_RIGHT;
188 } else {
189 result->arm_angle = ::std::acos(
190 (length_arm_ + request_h - elevator_max_) / length_arm_);
191 valid_or_invalid |= REGION_INSIDE_UPPER_LEFT;
192 }
193 } else if (result->elevator_height < elevator_min_) {
194 // Impossibly low request. So satisfy the x request with the elevator
195 // at the bottom of its range.
196 // The elevator will move up as the grabber moves to the center of the
197 // robot
198 // when in this part of the motion space.
199 result->elevator_height = elevator_min_;
200 if (request_x >= 0) {
201 valid_or_invalid |= REGION_INSIDE_LOWER_RIGHT;
202 } else {
203 valid_or_invalid |= REGION_INSIDE_LOWER_LEFT;
204 }
205 }
206
207 // if we are not in a valid region we will zero the velocity for now
208 if (valid_or_invalid != REGION_VALID) {
209 result->arm_velocity = 0.0;
210 result->elevator_velocity = 0.0;
211 }
212
213 if (ForwardKinematic(result->elevator_height, result->arm_angle,
214 result->elevator_velocity, result->arm_velocity,
215 result) == REGION_UNKNOWN) {
216 return REGION_UNKNOWN;
217 }
218 return valid_or_invalid;
219 }
220
221 // Takes an elevator height and arm angle and projects these to the resulting
222 // fridge height and x offset. Returns REGION_UNKNOWN if the values are
223 // outside
224 // limits. This will result in the height/angle being bounded and the
225 // resulting position will be returned.
226 Region ForwardKinematic(double elevator_height, double arm_angle,
227 double elevator_velocity, double arm_velocity,
228 KinematicResult* result) {
229 result->elevator_height = elevator_height;
230 result->arm_angle = arm_angle;
231
232 Region valid = REGION_VALID;
233 if (elevator_height < elevator_min_) {
234 LOG(WARNING, "elevator %.2f limited at %.2f\n", result->elevator_height,
235 elevator_min_);
236 result->elevator_height = elevator_min_;
237 valid = REGION_UNKNOWN;
238 }
239 if (elevator_height > elevator_max_) {
240 LOG(WARNING, "elevator %.2f limited at %.2f\n", result->elevator_height,
241 elevator_max_);
242 result->elevator_height = elevator_max_;
243 valid = REGION_UNKNOWN;
244 }
245 if (arm_angle < lower_angle_limit_) {
246 LOG(WARNING, "arm %.2f limited at %.2f\n", result->arm_angle,
247 lower_angle_limit_);
248 result->arm_angle = lower_angle_limit_;
249 valid = REGION_UNKNOWN;
250 }
251 if (arm_angle > upper_angle_limit_) {
252 result->arm_angle = upper_angle_limit_;
253 LOG(WARNING, "arm %.2f limited at %.2f\n", result->arm_angle,
254 upper_angle_limit_);
255 valid = REGION_UNKNOWN;
256 }
257 // Compute the fridge grabber height and x location using the computed
258 // elevator height and arm angle.
259 result->fridge_h = result->elevator_height +
260 (::std::cos(result->arm_angle) - 1.0) * length_arm_;
261 result->fridge_x = -::std::sin(result->arm_angle) * length_arm_;
262 // velocity based on joacobian
263 result->fridge_x_velocity =
264 -length_arm_ * ::std::cos(result->arm_angle) * arm_velocity;
265 LimitLightSpeed(&result->fridge_x_velocity);
266 result->fridge_h_velocity =
267 -length_arm_ * ::std::sin(result->arm_angle) * arm_velocity +
268 elevator_velocity;
269 LimitLightSpeed(&result->fridge_h_velocity);
270 return valid;
271 }
272
273 // Same as ForwardKinematic but without any checking.
274 Eigen::Vector2d ForwardKinematicNoChecking(double elevator_height,
275 double arm_angle) {
276 // Compute the fridge grabber height and x location using the computed
277 // elevator height and arm angle.
278 Eigen::Vector2d grabber_location;
279 grabber_location.y() =
280 elevator_height + (::std::cos(arm_angle) - 1.0) * length_arm_;
281 grabber_location.x() = -::std::sin(arm_angle) * length_arm_;
282 return grabber_location;
283 }
284
285 // 2 dimensional version of cross product
286 double Cross(Eigen::Vector2d a, Eigen::Vector2d b) {
287 double crossProduct = a.x() * b.y() - a.y() * b.x();
288 return crossProduct;
289 }
290
291 // Tell whether or not it is safe to move the grabber to a position.
292 // Returns true if the current move is safe.
293 // If it returns false then a safe_claw_angle that is greater than zero is
294 // acceptable otherwise if safe_claw_angle is less than zero there will be no
295 // valid solution.
296 bool GrabberArmIntersectionCheck(double elevator_height, double arm_angle,
297 double claw_angle, double* safe_claw_angle) {
298 Eigen::Vector2d grabber_location =
299 ForwardKinematicNoChecking(elevator_height, arm_angle);
300 if (grabber_location.x() < geometry_.grabber_always_safe_x_max ||
301 grabber_location.y() > geometry_.grabber_always_safe_h_min) {
302 *safe_claw_angle = claw_angle;
303 return true;
304 }
305 Eigen::Vector2d grabber_bottom_end;
306 Eigen::Vector2d claw_i_unit_direction(::std::cos(claw_angle),
307 sin(claw_angle));
308 Eigen::Vector2d claw_j_unit_direction(-::std::sin(claw_angle),
309 cos(claw_angle));
310
311 // Vector from the center of the arm rotation axis to front bottom
312 // corner of the grabber.
313 Eigen::Vector2d grabber_end_location_from_arm_axis(
314 geometry_.grabber_half_length, -geometry_.grabber_delta_y);
315
316 // Bottom front corner of the grabber. This is what will usually hit the
317 // claw first.
318 grabber_bottom_end = grabber_location + grabber_end_location_from_arm_axis;
319
320 // Location of the claw horizontal axis of rotation relative to the
321 // arm axis of rotation with the elevator at 0 and the arm angle of 0
322 // The horizontal axis is the up and down motion axis.
323 Eigen::Vector2d claw_updown_axis(geometry_.grabber_arm_horz_separation,
324 -geometry_.grabber_arm_vert_separation);
325
326 // This point is used to make a cross product with the bottom end of the
327 // grabber
328 // The result of the cross product tells if the parts intersect or not.
329 Eigen::Vector2d claw_top_ref_point =
330 claw_updown_axis + geometry_.claw_top_thickness * claw_j_unit_direction;
331
332 Eigen::Vector2d claw_top_ref_point_to_grabber_bottom_end =
333 grabber_bottom_end - claw_top_ref_point;
334 double claw_grabber_check =
335 Cross(claw_i_unit_direction, claw_top_ref_point_to_grabber_bottom_end);
336
337 // Now set the safe claw angle.
338 if (claw_grabber_check > 0.0) {
339 *safe_claw_angle = claw_angle;
340 return true;
341 } else if (grabber_bottom_end.y() <
342 claw_updown_axis.y() +
343 geometry_.claw_top_thickness) { // grabber is too close
344 *safe_claw_angle = -1.0;
345 return false;
346 } else {
347 // To find the safe angle for the claw, draw a line between the claw
348 // rotation axis and the lower front corner of the grabber. The angle of
349 // this line is used with the angle between the edge of the claw and the
350 // center line of the claw to determine the angle of the claw.
351 Eigen::Vector2d claw_axis_to_grabber_bottom_end =
352 grabber_bottom_end - claw_updown_axis;
353 double hypot = claw_axis_to_grabber_bottom_end.norm();
354 double angleDiff = ::std::asin(geometry_.claw_top_thickness / hypot);
355 *safe_claw_angle = ::std::atan2(claw_axis_to_grabber_bottom_end.y(),
356 claw_axis_to_grabber_bottom_end.x()) -
357 angleDiff;
358 return false;
359 }
360 }
361
362 double get_elevator_min() { return elevator_min_; }
363
364 double get_elevator_max() { return elevator_max_; }
365
366 double get_upper_angle_limit() { return upper_angle_limit_; }
367
368 double get_lower_angle_limit() { return lower_angle_limit_; }
369
370 private:
371 // length of the arm
372 double length_arm_;
373 // max height the elevator can go.
374 double elevator_max_;
375 // min height the elevator can go.
376 double elevator_min_;
377 // arm angle upper limit
378 double upper_angle_limit_;
379 // arm angle lower limit
380 double lower_angle_limit_;
381 // Geometry of the arm + fridge
382 frc971::constants::Values::ClawGeometry geometry_;
383};
384
385} // namespace util
386} // namespace aos
387
Brian Silvermanb691f5e2015-08-02 11:37:55 -0700388#endif // Y2015_UTIL_KINEMATICS_H_