APM:Libraries
SIM_Calibration.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015-2016 Intel Corporation. All rights reserved.
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 #include <assert.h>
18 
19 #include <AP_Math/AP_Math.h>
20 
21 #include "SIM_Calibration.h"
22 
23 #define MAX_ANGULAR_SPEED (2 * M_PI)
24 
25 #include <stdio.h>
26 
27 SITL::Calibration::Calibration(const char *home_str, const char *frame_str)
28  : Aircraft(home_str, frame_str)
29 {
30  mass = 1.5f;
31 }
32 
33 void SITL::Calibration::update(const struct sitl_input& input)
34 {
35  Vector3f rot_accel{0, 0, 0};
36 
37  float switcher_pwm = input.servos[4];
38  if (switcher_pwm < 1100) {
39  _stop_control(input, rot_accel);
40  } else if (switcher_pwm < 1200) {
41  _attitude_control(input, rot_accel);
42  } else if (switcher_pwm < 1300) {
43  _calibration_poses(rot_accel);
44  } else {
45  _angular_velocity_control(input, rot_accel);
46  }
47 
48  accel_body(0, 0, 0);
49  update_dynamics(rot_accel);
51  time_advance();
52 
53  // update magnetic field
55 }
56 
58  Vector3f& rot_accel)
59 {
60  Vector3f desired_angvel{0, 0, 0};
61  Vector3f error = desired_angvel - gyro;
62  float dt = frame_time_us * 1.0e-6f;
63  rot_accel = error * (1.0f / dt);
64  /* Provide a somewhat "smooth" transition */
65  rot_accel *= 0.002f;
66 }
67 
69  Vector3f& rot_accel)
70 {
71  float desired_roll = -M_PI + 2 * M_PI * (input.servos[5] - 1000) / 1000.f;
72  float desired_pitch = -M_PI + 2 * M_PI * (input.servos[6] - 1000) / 1000.f;
73  float desired_yaw = -M_PI + 2 * M_PI * (input.servos[7] - 1000) / 1000.f;
74 
75  _attitude_set(desired_roll, desired_pitch, desired_yaw, rot_accel);
76 }
77 
78 
79 void SITL::Calibration::_attitude_set(float desired_roll, float desired_pitch, float desired_yaw,
80  Vector3f& rot_accel)
81 {
82  float dt = frame_time_us * 1.0e-6f;
83 
84  Quaternion desired_q;
85  desired_q.from_euler(desired_roll, desired_pitch, desired_yaw);
86  desired_q.normalize();
87 
88  Quaternion current_q;
89  current_q.from_rotation_matrix(dcm);
90  current_q.normalize();
91 
92  Quaternion error_q = desired_q / current_q;
93 
94  Vector3f angle_differential;
95  error_q.normalize();
96  error_q.to_axis_angle(angle_differential);
97 
98  Vector3f desired_angvel = angle_differential * (1 / dt);
99  /* Provide a somewhat "smooth" transition */
100  desired_angvel *= .005f;
101 
102  Vector3f error = desired_angvel - gyro;
103  rot_accel = error * (1.0f / dt);
104 }
105 
107  Vector3f& rot_accel)
108 {
109  Vector3f axis{(float)(in.servos[5] - 1500),
110  (float)(in.servos[6] - 1500),
111  (float)(in.servos[7] - 1500)};
112  float theta = MAX_ANGULAR_SPEED * (in.servos[4] - 1300) / 700.f;
113  float dt = frame_time_us * 1.0e-6f;
114 
115  if (axis.length() > 0) {
116  axis.normalize();
117  }
118 
119  Vector3f desired_angvel = axis * theta;
120  Vector3f error = desired_angvel - gyro;
121 
122  rot_accel = error * (1.0f / dt);
123  /* Provide a somewhat "smooth" transition */
124  rot_accel *= .05f;
125 }
126 
127 /*
128  move continuously through 6 calibration poses, doing a rotation
129  about each pose over 3 seconds
130  */
132 {
133  const struct pose {
134  int16_t roll, pitch, yaw;
135  uint8_t axis;
136  } poses[] = {
137  { 0, 0, 0, 0 },
138  { 0, 0, 0, 1 },
139  { 0, 0, 0, 2 },
140  { 90, 0, 0, 1 },
141  { 0, 90, 0, 1 },
142  { 0, 180, 0, 2 },
143  { 45, 0, 0, 1 },
144  { 0, 45, 0, 2 },
145  { 0, 0, 45, 0 },
146  { 30, 0, 0, 1 },
147  { 0, 30, 0, 0 },
148  { 30, 0, 0, 1 },
149  { 0, 0, 30, 0 },
150  { 0, 0, 30, 1 },
151  { 60, 20, 0, 1 },
152  { 0, 50, 10, 0 },
153  { 0, 30, 50, 1 },
154  { 0, 30, 50, 2 },
155  };
156  const float secs_per_pose = 6;
157  const float rate = radians(360 / secs_per_pose);
158  float tnow = AP_HAL::millis() * 1.0e-3;
159  float t_in_pose = fmod(tnow, secs_per_pose);
160  uint8_t pose_num = ((unsigned)(tnow / secs_per_pose)) % ARRAY_SIZE(poses);
161  const struct pose &pose = poses[pose_num];
162 
163  // let the sensor smoothing create sensible gyro values
164  use_smoothing = true;
165  dcm.identity();
166  dcm.from_euler(radians(pose.roll), radians(pose.pitch), radians(pose.yaw));
167 
168  Vector3f axis;
169  axis[pose.axis] = 1;
170  float rot_angle = rate * t_in_pose;
171  Matrix3f r2;
172  r2.from_axis_angle(axis, rot_angle);
173  dcm = r2 * dcm;
174 
175  accel_body(0, 0, -GRAVITY_MSS);
176  accel_body = dcm.transposed() * accel_body;
177 }
Vector3f accel_body
Definition: SIM_Aircraft.h:142
void to_axis_angle(Vector3f &v)
Definition: quaternion.cpp:189
void from_axis_angle(const Vector3< T > &v, float theta)
Definition: matrix3.cpp:248
void update(const struct sitl_input &input)
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
void from_euler(float roll, float pitch, float yaw)
Definition: quaternion.cpp:130
void _attitude_set(float desired_roll, float desired_pitch, float desired_yaw, Vector3f &rot_accel)
void from_rotation_matrix(const Matrix3f &m)
Definition: quaternion.cpp:76
void _angular_velocity_control(const struct sitl_input &input, Vector3f &rot_accel)
void _attitude_control(const struct sitl_input &input, Vector3f &rot_accel)
#define GRAVITY_MSS
Definition: definitions.h:47
#define f(i)
uint32_t millis()
Definition: system.cpp:157
void _stop_control(const struct sitl_input &input, Vector3f &rot_accel)
void _calibration_poses(Vector3f &rot_accel)
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
void update_mag_field_bf(void)
uint64_t frame_time_us
Definition: SIM_Aircraft.h:167
#define MAX_ANGULAR_SPEED
void normalize()
Definition: quaternion.cpp:297
void update_position(void)
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void update_dynamics(const Vector3f &rot_accel)
#define error(fmt, args ...)
#define M_PI
Definition: definitions.h:10
void identity(void)
Definition: matrix3.h:219
Calibration(const char *home_str, const char *frame_str)