embedded_flight_control/attitude/
mod.rs

1use core::f32::consts::PI;
2use nalgebra::{Quaternion, Vector2, Vector3};
3use num_traits::Float;
4
5mod multi_copter;
6pub use multi_copter::MultiCopterAttitudeController;
7
8/// The attitude controller works around the concept of the desired attitude, target attitude
9/// and measured attitude. The desired attitude is the attitude input into the attitude controller
10/// that expresses where the higher level code would like the aircraft to move to. The target attitude is moved
11/// to the desired attitude with jerk, acceleration, and velocity limits. The target angular velocities are fed
12/// directly into the rate controllers. The angular error between the measured attitude and the target attitude is
13/// fed into the angle controller and the output of the angle controller summed at the input of the rate controllers.
14/// By feeding the target angular velocity directly into the rate controllers the measured and target attitudes
15/// remain very close together.
16///
17/// All input functions below follow the same procedure
18/// 1. define the desired attitude the aircraft should attempt to achieve using the input variables
19/// 2. using the desired attitude and input variables, define the target angular velocity so that it should
20///    move the target attitude towards the desired attitude
21/// 3. if _rate_bf_ff_enabled is not being used then make the target attitude
22///    and target angular velocities equal to the desired attitude and desired angular velocities.
23/// 4. ensure _attitude_target, _euler_angle_target, _euler_rate_target and
24///    _ang_vel_target have been defined. This ensures input modes can be changed without discontinuity.
25/// 5. attitude_controller_run_quat is then run to pass the target angular velocities to the rate controllers and
26///    integrate them into the target attitude. Any errors between the target attitude and the measured attitude are
27///    corrected by first correcting the thrust vector until the angle between the target thrust vector measured
28///    trust vector drops below 2*AC_ATTITUDE_THRUST_ERROR_ANGLE. At this point the heading is also corrected.
29pub struct AttitudeController {
30    /// The angular velocity (in radians per second) in the body frame.
31    pub ang_vel_body: Vector3<f32>,
32    pub actuator_sysid: Vector3<f32>,
33    pub sysid_ang_vel_body: Vector3<f32>,
34    pub feed_forward_scalar: f32,
35    pub throttle_rpy_mix: f32,
36    pub throttle_rpy_mix_desired: f32,
37
38    // Maximum throttle mix
39    pub attitude_control_max: f32,
40    pub dt: f32,
41
42    // @Param: ACCEL_P_MAX
43    // @DisplayName: Acceleration Max
44    // @Description: Maximum acceleration
45    // @Units: radian/s/s
46    // @Range: 0 180000
47    // @Increment: 1000
48    // @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast
49    // @User: Advanced
50    pub accel_max: Vector3<f32>,
51    pub use_sqrt_controller: bool,
52
53    // @Param: ANG_RLL_P
54    // @DisplayName: Roll axis angle controller P gain
55    // @Description: Roll axis angle controller P gain.  Converts the error between the desired roll angle and actual angle to a desired roll rate
56    // @Range: 3.000 12.000
57    // @Range{Sub}: 0.0 12.000
58    // @User: Standard
59    pub p_angle_roll: P,
60
61    // @Param: ANG_PIT_P
62    // @DisplayName: Pitch axis angle controller P gain
63    // @Description: Pitch axis angle controller P gain.  Converts the error between the desired pitch angle and actual angle to a desired pitch rate
64    // @Range: 3.000 12.000
65    // @Range{Sub}: 0.0 12.000
66    // @User: Standard
67    pub p_angle_pitch: P,
68
69    // @Param: ANG_YAW_P
70    // @DisplayName: Yaw axis angle controller P gain
71    // @Description: Yaw axis angle controller P gain.  Converts the error between the desired yaw angle and actual angle to a desired yaw rate
72    // @Range: 3.000 12.000
73    // @Range{Sub}: 0.0 6.000
74    // @User: Standard
75    pub p_angle_yaw: P,
76    pub thrust_error_angle: f32,
77    pub attitude_target: Quaternion<f32>,
78
79    // @Param: RATE_P_MAX
80    // @DisplayName: Angular Velocity Max for Pitch
81    // @Description: Maximum angular velocity in pitch axis
82    // @Units: radians/s
83    // @Range: 0 1080
84    // @Increment: 1
85    // @Values: 0:Disabled, 60:Slow, 180:Medium, 360:Fast
86    // @User: Advanced
87    pub ang_vel_max: Vector3<f32>,
88    pub ang_vel_target: Vector3<f32>,
89
90    // @Param: RATE_FF_ENAB
91    // @DisplayName: Rate Feedforward Enable
92    // @Description: Controls whether body-frame rate feedfoward is enabled or disabled
93    // @Values: 0:Disabled, 1:Enabled
94    // @User: Advanced
95    pub rate_bf_ff_enabled: bool,
96
97    // @Param: INPUT_TC
98    // @DisplayName: Attitude control input time constant
99    // @Description: Attitude control input time constant.  Low numbers lead to sharper response, higher numbers to softer response
100    // @Units: s
101    // @Range: 0 1
102    // @Increment: 0.01
103    // @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp
104    // @User: Standard
105    pub input_tc: f32,
106
107    pub euler_angle_target: Vector3<f32>,
108    pub euler_rate_target: Vector3<f32>,
109}
110
111impl Default for AttitudeController {
112    fn default() -> Self {
113        Self {
114            ang_vel_body: Vector3::zeros(),
115            actuator_sysid: Vector3::zeros(),
116            sysid_ang_vel_body: Vector3::zeros(),
117            feed_forward_scalar: 1.,
118            throttle_rpy_mix: 0.5,
119            throttle_rpy_mix_desired: 0.5,
120            attitude_control_max: 5.,
121            dt: Default::default(),
122            accel_max: Vector3::new(110000., 110000., 27000.),
123            use_sqrt_controller: true,
124            p_angle_roll: P::new(4.5),
125            p_angle_pitch: P::new(4.5),
126            p_angle_yaw: P::new(4.5),
127            thrust_error_angle: 0.,
128            attitude_target: Quaternion::default(),
129            ang_vel_max: Vector3::zeros(),
130            ang_vel_target: Vector3::zeros(),
131            rate_bf_ff_enabled: true,
132            input_tc: 0.15,
133            euler_angle_target: Vector3::zeros(),
134            euler_rate_target: Vector3::zeros(),
135        }
136    }
137}
138
139impl AttitudeController {
140    /// Command a Quaternion attitude with feed-forward and smoothing.
141    /// Returns `attitude_desired` updated by the integral of the angular velocity
142    pub fn input(
143        &mut self,
144        mut attitude_desired: Quaternion<f32>,
145        ang_vel_target: Vector3<f32>,
146        attitude_body: Quaternion<f32>,
147    ) -> Quaternion<f32> {
148        let attitude_error_quat =
149            self.attitude_target.try_inverse().unwrap_or_default() * attitude_desired;
150        let attitude_error_angle = to_axis_angle(attitude_error_quat);
151
152        // Limit the angular velocity
153        let ang_vel_target = ang_vel_limit(ang_vel_target, self.ang_vel_max);
154
155        if self.rate_bf_ff_enabled {
156            // When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler
157            // angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration
158            // and an exponential decay specified by _input_tc at the end.
159            self.ang_vel_target.x = input_shaping_angle(
160                wrap_PI(attitude_error_angle.x),
161                self.input_tc,
162                self.accel_max.x,
163                self.ang_vel_target.x,
164                ang_vel_target.x,
165                self.ang_vel_max.x,
166                self.dt,
167            );
168            self.ang_vel_target.y = input_shaping_angle(
169                wrap_PI(attitude_error_angle.y),
170                self.input_tc,
171                self.accel_max.y,
172                self.ang_vel_target.y,
173                ang_vel_target.y,
174                self.ang_vel_max.x,
175                self.dt,
176            );
177            self.ang_vel_target.z = input_shaping_angle(
178                wrap_PI(attitude_error_angle.z),
179                self.input_tc,
180                self.accel_max.z,
181                self.ang_vel_target.z,
182                ang_vel_target.z,
183                self.ang_vel_max.x,
184                self.dt,
185            );
186        } else {
187            self.attitude_target = attitude_desired;
188            self.ang_vel_target = ang_vel_target;
189        }
190
191        // calculate the attitude target euler angles
192        self.euler_angle_target = to_euler(self.attitude_target);
193
194        // Convert body-frame angular velocity into euler angle derivative of desired attitude
195        if let Some(euler_rate) =
196            ang_vel_to_euler_rate(self.euler_angle_target, self.ang_vel_target)
197        {
198            self.euler_rate_target = euler_rate;
199        }
200
201        let attitude_desired_update = from_axis_angle(ang_vel_target * self.dt);
202        attitude_desired = (attitude_desired * attitude_desired_update).normalize();
203
204        // Call quaternion attitude controller
205        self.attitude_control(attitude_body);
206
207        attitude_desired
208    }
209
210    /// Calculate the body frame angular velocities to follow the target attitude.
211    /// `attitude_body` represents a quaternion rotation in NED frame to the body
212    pub fn attitude_control(&mut self, attitude_body: Quaternion<f32>) {
213        // Vector representing the angular error to rotate the thrust vector using x and y and heading using z
214        let (_attitude_target, attitude_error) =
215            self.thrust_heading_rotation_angles(self.attitude_target, attitude_body);
216
217        // Compute the angular velocity corrections in the body frame from the attitude error
218        self.ang_vel_body = self.angular_velocity_target_from_attitude_error(attitude_error);
219    }
220
221    // Calculates two ordered rotations to move `attitude_body` to `attitude_target`.
222    // The maximum error in the yaw axis is limited based on the angle yaw P value and acceleration.
223    pub fn thrust_heading_rotation_angles(
224        &self,
225        mut attitude_target: Quaternion<f32>,
226        attitude_body: Quaternion<f32>,
227    ) -> (Quaternion<f32>, Vector3<f32>) {
228        let ac_attitude_accel_y_controller_max_radss = 120f32.to_radians();
229
230        let (thrust_angle, thrust_vector_correction, mut attitude_error, thrust_error_angle) =
231            thrust_vector_rotation_angles(attitude_target, attitude_body);
232
233        // Todo: Limit roll an pitch error based on output saturation and maximum error.
234
235        // Limit Yaw Error based on maximum acceleration - Update to include output saturation and maximum error.
236        // Currently the limit is based on the maximum acceleration using the linear part of the SQRT controller.
237        // This should be updated to be based on an angle limit, saturation, or unlimited based on user defined parameters.
238
239        if (self.p_angle_yaw.kp != 0.
240            && attitude_error.z.abs()
241                > ac_attitude_accel_y_controller_max_radss / self.p_angle_yaw.kp)
242        {
243            attitude_error.z = wrap_PI(attitude_error.z)
244                .max(-ac_attitude_accel_y_controller_max_radss / self.p_angle_yaw.kp)
245                .min(ac_attitude_accel_y_controller_max_radss / self.p_angle_yaw.kp);
246            let yaw_vec_correction_quat = from_axis_angle(Vector3::new(0., 0., attitude_error.z));
247            attitude_target = attitude_body * thrust_vector_correction * yaw_vec_correction_quat;
248        }
249
250        (attitude_target, attitude_error)
251    }
252
253    /// Calculate the rate target angular velocity using the attitude error rotation vector (in radians)
254    pub fn angular_velocity_target_from_attitude_error(
255        &self,
256        attitude_error_rot_vec_rad: Vector3<f32>,
257    ) -> Vector3<f32> {
258        let ac_attitude_accel_rp_controller_min_radss = 40f32.to_radians();
259        let ac_attitude_accel_rp_controller_max_radss = 720f32.to_radians();
260
261        let ac_attitude_accel_y_rp_controller_min_radss = 10f32.to_radians();
262        let ac_attitude_accel_y_rp_controller_max_radss = 120f32.to_radians();
263
264        // Compute the roll angular velocity demand from the roll angle error
265        let target_roll_angular_velocity = if self.use_sqrt_controller && self.accel_max[0] != 0. {
266            sqrt_controller(
267                attitude_error_rot_vec_rad.x,
268                self.p_angle_roll.kp,
269                (self.accel_max[0] / 2.)
270                    .max(ac_attitude_accel_rp_controller_min_radss)
271                    .min(ac_attitude_accel_rp_controller_max_radss),
272                self.dt,
273            )
274        } else {
275            self.p_angle_roll.kp * attitude_error_rot_vec_rad.x
276        };
277
278        // Compute the pitch angular velocity demand from the pitch angle error
279        let target_pitch_angular_velocity = if self.use_sqrt_controller && self.accel_max[1] != 0. {
280            sqrt_controller(
281                attitude_error_rot_vec_rad.y,
282                self.p_angle_pitch.kp,
283                (self.accel_max[1] / 2.)
284                    .max(ac_attitude_accel_rp_controller_min_radss)
285                    .min(ac_attitude_accel_rp_controller_max_radss),
286                self.dt,
287            )
288        } else {
289            self.p_angle_pitch.kp * attitude_error_rot_vec_rad.y
290        };
291
292        // Compute the yaw angular velocity demand from the yaw angle error
293        let target_yaw_angular_velocity = if self.use_sqrt_controller && self.accel_max[2] != 0. {
294            sqrt_controller(
295                attitude_error_rot_vec_rad.z,
296                self.p_angle_yaw.kp,
297                (self.accel_max[2] / 2.)
298                    .max(ac_attitude_accel_y_rp_controller_min_radss)
299                    .min(ac_attitude_accel_y_rp_controller_max_radss),
300                self.dt,
301            )
302        } else {
303            self.p_angle_yaw.kp * attitude_error_rot_vec_rad.z
304        };
305
306        Vector3::new(
307            target_roll_angular_velocity,
308            target_pitch_angular_velocity,
309            target_yaw_angular_velocity,
310        )
311    }
312}
313
314// get euler roll angle
315pub fn euler_roll(q: Quaternion<f32>) -> f32 {
316    (2. * (q[0] * q[1] + q[2] * q[3])).atan2(1. - 2. * (q[1] * q[1] + q[2] * q[2]))
317}
318
319// get euler pitch angle
320pub fn euler_pitch(q: Quaternion<f32>) -> f32 {
321    safe_asin(2. * (q[0] * q[2] - q[3] * q[1]))
322}
323
324// get euler yaw angle
325pub fn euler_yaw(q: Quaternion<f32>) -> f32 {
326    (2. * (q[0] * q[3] + q[1] * q[2])).atan2(1. - 2. * (q[2] * q[2] + q[3] * q[3]))
327}
328
329// create eulers from a quaternion
330pub fn to_euler(q: Quaternion<f32>) -> Vector3<f32> {
331    Vector3::new(euler_roll(q), euler_pitch(q), euler_yaw(q))
332}
333
334fn safe_asin(f: f32) -> f32 {
335    if f.is_nan() {
336        0.
337    } else if f >= 1. {
338        PI * 2.
339    } else if f <= -1. {
340        -PI * 2.
341    } else {
342        f.asin()
343    }
344}
345
346// Convert an angular velocity vector to a 321-intrinsic euler angle derivative (in radians/second).
347// Returns None if the vehicle is pitched 90 degrees up or down
348pub fn ang_vel_to_euler_rate(
349    euler_rad: Vector3<f32>,
350    ang_vel_rads: Vector3<f32>,
351) -> Option<Vector3<f32>> {
352    let sin_theta = euler_rad.y.sin();
353    let cos_theta = euler_rad.y.cos();
354    let sin_phi = euler_rad.x.sin();
355    let cos_phi = euler_rad.x.cos();
356
357    // When the vehicle pitches all the way up or all the way down, the euler angles become discontinuous.
358    // In this case, we return None
359    if cos_theta != 0. {
360        let euler_rate_rads = Vector3::new(
361            ang_vel_rads.x
362                + sin_phi * (sin_theta / cos_theta) * ang_vel_rads.y
363                + cos_phi * (sin_theta / cos_theta) * ang_vel_rads.z,
364            cos_phi * ang_vel_rads.y - sin_phi * ang_vel_rads.z,
365            (sin_phi / cos_theta) * ang_vel_rads.y + (cos_phi / cos_theta) * ang_vel_rads.z,
366        );
367        Some(euler_rate_rads)
368    } else {
369        None
370    }
371}
372
373pub struct P {
374    pub kp: f32,
375}
376
377impl Default for P {
378    fn default() -> Self {
379        Self::new(0.)
380    }
381}
382
383impl P {
384    pub fn new(kp: f32) -> Self {
385        Self { kp }
386    }
387}
388
389pub fn ang_vel_limit(mut euler_rad: Vector3<f32>, ang_vel_max: Vector3<f32>) -> Vector3<f32> {
390    if ang_vel_max[0] == 0. || ang_vel_max[1] == 0. {
391        if ang_vel_max[0] != 0. {
392            euler_rad.x = euler_rad.x.max(-ang_vel_max[0]).min(ang_vel_max[0]);
393        }
394        if ang_vel_max[1] != 0. {
395            euler_rad.y = euler_rad.y.max(-ang_vel_max[1]).min(ang_vel_max[1]);
396        }
397    } else {
398        let thrust_vector_ang_vel =
399            Vector2::new(euler_rad.x / ang_vel_max[0], euler_rad.y / ang_vel_max[1]);
400        let thrust_vector_length = thrust_vector_ang_vel.norm();
401        if thrust_vector_length > 1. {
402            euler_rad.x = thrust_vector_ang_vel.x * ang_vel_max[0] / thrust_vector_length;
403            euler_rad.y = thrust_vector_ang_vel.y * ang_vel_max[1] / thrust_vector_length;
404        }
405    }
406    if ang_vel_max[2] != 0. {
407        euler_rad.z = euler_rad.z.max(-ang_vel_max[2]).min(ang_vel_max[2]);
408    }
409
410    euler_rad
411}
412
413/// thrust_vector_rotation_angles - calculates two ordered rotations to move the attitude_body quaternion to the attitude_target quaternion.
414/// The first rotation corrects the thrust vector and the second rotation corrects the heading vector.
415pub fn thrust_vector_rotation_angles(
416    attitude_target: Quaternion<f32>,
417    attitude_body: Quaternion<f32>,
418) -> (f32, Quaternion<f32>, Vector3<f32>, f32) {
419    // The direction of thrust is [0,0,-1] is any body-fixed frame, inc. body frame and target frame.
420    let thrust_vector_up = Vector3::new(0., 0., -1.);
421
422    // attitude_target and attitute_body are passive rotations from target / body frames to the NED frame
423
424    // Rotating [0,0,-1] by attitude_target expresses (gets a view of) the target thrust vector in the inertial frame
425    let att_target_thrust_vec = mul(attitude_target, thrust_vector_up); // target thrust vector
426
427    // Rotating [0,0,-1] by attitude_target expresses (gets a view of) the current thrust vector in the inertial frame
428    let att_body_thrust_vec = mul(attitude_body, thrust_vector_up); // current thrust vector
429
430    // the dot product is used to calculate the current lean angle for use of external functions
431    let thrust_angle = ((thrust_vector_up.dot(&att_body_thrust_vec))
432        .max(-1.)
433        .min(1.))
434    .acos();
435
436    // the cross product of the desired and target thrust vector defines the rotation vector
437    let mut thrust_vec_cross = att_body_thrust_vec.cross(&att_target_thrust_vec);
438
439    // the dot product is used to calculate the angle between the target and desired thrust vectors
440    let thrust_error_angle = ((att_body_thrust_vec.dot(&att_target_thrust_vec))
441        .max(-1.)
442        .min(1.))
443    .acos();
444
445    // Normalize the thrust rotation vector
446    let thrust_vector_length = thrust_vec_cross.norm();
447    if thrust_vector_length == 0. || thrust_error_angle == 0. {
448        thrust_vec_cross = thrust_vector_up;
449    } else {
450        thrust_vec_cross /= thrust_vector_length;
451    }
452
453    // thrust_vector_correction is defined relative to the body frame but its axis `thrust_vec_cross` was computed in
454    // the inertial frame. First rotate it by the inverse of attitude_body to express it back in the body frame
455    thrust_vec_cross = mul(
456        attitude_body.try_inverse().unwrap_or_default(),
457        thrust_vec_cross,
458    );
459    let thrust_vector_correction = from_axis_angle_with_theta(thrust_vec_cross, thrust_error_angle);
460
461    // calculate the angle error in x and y.
462    let mut rotation = to_axis_angle(thrust_vector_correction);
463    let attitude_error_x = rotation.x;
464    let attitude_error_y = rotation.y;
465
466    // calculate the remaining rotation required after thrust vector is rotated transformed to the body frame
467    // heading_vector_correction
468    let heading_vec_correction_quat = thrust_vector_correction.try_inverse().unwrap_or_default()
469        * attitude_body.try_inverse().unwrap_or_default()
470        * attitude_target;
471
472    // calculate the angle error in z (x and y should be zero here).
473    rotation = to_axis_angle(heading_vec_correction_quat);
474    let attitude_error_z = rotation.z;
475
476    (
477        thrust_angle,
478        thrust_vector_correction,
479        Vector3::new(attitude_error_x, attitude_error_y, attitude_error_z),
480        thrust_error_angle,
481    )
482}
483
484/// Limit the acceleration and deceleration of a velocity request.
485pub fn input_shaping_ang_vel(
486    target_ang_vel: f32,
487    desired_ang_vel: f32,
488    accel_max: f32,
489    dt: f32,
490) -> f32 {
491    // Acceleration is limited directly to smooth the beginning of the curve.
492    if accel_max >= 0. {
493        let delta_ang_vel = accel_max * dt;
494        desired_ang_vel
495            .max(target_ang_vel - delta_ang_vel)
496            .min(target_ang_vel + delta_ang_vel)
497    } else {
498        desired_ang_vel
499    }
500}
501
502/// Calculate the velocity correction from an angle error.
503/// The angular velocity has acceleration and deceleration limits
504/// including basic jerk limiting using _input_tc
505pub fn input_shaping_angle(
506    error_angle: f32,
507    input_tc: f32,
508    accel_max: f32,
509    target_ang_vel: f32,
510    mut desired_ang_vel: f32,
511    max_ang_vel: f32,
512    dt: f32,
513) -> f32 {
514    // Calculate the velocity as error approaches zero with acceleration limited by accel_max_rads
515    desired_ang_vel += sqrt_controller(error_angle, 1.0 / input_tc.max(0.01), accel_max, dt);
516    if max_ang_vel > 0. {
517        desired_ang_vel = desired_ang_vel.max(-max_ang_vel).min(max_ang_vel);
518    }
519
520    // Acceleration is limited directly to smooth the beginning of the curve.
521    input_shaping_ang_vel(target_ang_vel, desired_ang_vel, accel_max, dt)
522}
523
524/// Calculate the correction based on a proportional controller (with piecewise sqrt sections to constrain second derivative).
525pub fn sqrt_controller(error: f32, p: f32, second_ord_lim: f32, dt: f32) -> f32 {
526    let correction_rate;
527    if second_ord_lim <= 0. {
528        // second order limit is zero or negative.
529        correction_rate = error * p;
530    } else if p == 0. {
531        // P term is zero but we have a second order limit.
532        if error > 0. {
533            correction_rate = safe_sqrt(2.0 * second_ord_lim * (error));
534        } else if error < 0. {
535            correction_rate = -safe_sqrt(2.0 * second_ord_lim * (-error));
536        } else {
537            correction_rate = 0.;
538        }
539    } else {
540        // Both the P and second order limit have been defined.
541        let linear_dist = second_ord_lim / (p * p);
542        if (error > linear_dist) {
543            correction_rate = safe_sqrt(2. * second_ord_lim * (error - (linear_dist / 2.)));
544        } else if (error < -linear_dist) {
545            correction_rate = -safe_sqrt(2. * second_ord_lim * (-error - (linear_dist / 2.)));
546        } else {
547            correction_rate = error * p;
548        }
549    }
550    if dt != 0. {
551        // this ensures we do not get small oscillations by over shooting the error correction in the last time step.
552        correction_rate
553            .max(-(error.abs()) / dt)
554            .min(error.abs() / dt)
555    } else {
556        correction_rate
557    }
558}
559
560fn safe_sqrt(v: f32) -> f32 {
561    let ret = v.sqrt();
562    if ret.is_nan() {
563        0.
564    } else {
565        ret
566    }
567}
568
569// Optimized quaternion rotation operator, equivalent to converting
570// (*this) to a rotation matrix then multiplying it to the argument `v`.
571//
572// 15 multiplies and 15 add / subtracts. Caches 3 floats
573fn mul(quat: Quaternion<f32>, v: Vector3<f32>) -> Vector3<f32> {
574    // This uses the formula
575    //
576    //    v2 = v1 + 2 q[0] * qv x v1 + 2 qv x qv x v1
577    //
578    // where "x" is the cross product (explicitly inlined for performance below),
579    // "q[0]" is the scalar part and "qv" is the vector part of this quaternion
580
581    let mut ret = v;
582
583    // Compute and cache "qv x v1"
584    let mut uv = [
585        quat[2] * v.z - quat[3] * v.y,
586        quat[3] * v.x - quat[1] * v.z,
587        quat[1] * v.y - quat[2] * v.x,
588    ];
589
590    uv[0] += uv[0];
591    uv[1] += uv[1];
592    uv[2] += uv[2];
593    ret.x += quat[0] * uv[0] + quat[2] * uv[2] - quat[3] * uv[1];
594    ret.y += quat[0] * uv[1] + quat[3] * uv[0] - quat[1] * uv[2];
595    ret.z += quat[0] * uv[2] + quat[1] * uv[1] - quat[2] * uv[0];
596    ret
597}
598
599// create a quaternion from its axis-angle representation
600fn from_axis_angle(v: Vector3<f32>) -> Quaternion<f32> {
601    let theta = v.norm();
602    if theta == 0. {
603        Quaternion::new(1., 0., 0., 0.)
604    } else {
605        from_axis_angle_with_theta(v / theta, theta)
606    }
607}
608
609// create a quaternion from its axis-angle representation
610// the axis vector must be length 1, theta is in radians
611fn from_axis_angle_with_theta(axis: Vector3<f32>, theta: f32) -> Quaternion<f32> {
612    // axis must be a unit vector as there is no check for length
613    if theta == 0. {
614        Quaternion::new(1., 0., 0., 0.)
615    } else {
616        let st2 = (0.5 * theta).sin();
617
618        Quaternion::new(
619            (0.5 * theta).cos(),
620            axis.x * st2,
621            axis.y * st2,
622            axis.z * st2,
623        )
624    }
625}
626
627fn to_axis_angle(quat: Quaternion<f32>) -> Vector3<f32> {
628    let l = (quat[1] * quat[1] + quat[2] * quat[2] + quat[3] * quat[3]).sqrt();
629    let v = Vector3::new(quat[1], quat[2], quat[3]);
630    if l == 0. {
631        (v / l) * wrap_PI(2. * l.atan2(quat[0]))
632    } else {
633        v
634    }
635}
636
637fn wrap_PI(radian: f32) -> f32 {
638    let res = wrap_2PI(radian);
639    if res > PI {
640        res - (PI * 2.)
641    } else {
642        res
643    }
644}
645
646fn wrap_2PI(radian: f32) -> f32 {
647    let res = radian % (PI * 2.);
648    if res < 0. {
649        res + (PI * 2.)
650    } else {
651        res
652    }
653}