APM:Libraries
SIM_Frame.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  multicopter frame simulator class
17 */
18 
19 #include "SIM_Frame.h"
20 #include <AP_Motors/AP_Motors.h>
21 
22 #include <stdio.h>
23 
24 using namespace SITL;
25 
27 {
32 };
33 
34 static Motor quad_x_motors[] =
35 {
40 };
41 
43 {
44  Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1, -1, 0, 0, 7, 10, -90),
45  Motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3, -1, 0, 0, 8, 10, -90),
46  Motor(AP_MOTORS_MOT_3, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4, -1, 0, 0, 8, 10, -90),
47  Motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2, -1, 0, 0, 7, 10, -90),
48 };
49 
50 static Motor hexa_motors[] =
51 {
58 };
59 
60 static Motor hexax_motors[] =
61 {
68 };
69 
70 static Motor octa_motors[] =
71 {
80 };
81 
83 {
92 };
93 
95 {
108 };
109 
110 static Motor tri_motors[] =
111 {
115 };
116 
118 {
122 };
123 
125 {
126  Motor(AP_MOTORS_MOT_1, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1, -1, 0, 0, 7, 10, -90),
127  Motor(AP_MOTORS_MOT_2, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3, -1, 0, 0, 8, 10, -90),
129 };
130 
131 static Motor y6_motors[] =
132 {
139 };
140 
141 /*
142  FireflyY6 is a Y6 with front motors tiltable using servo on channel 9 (output 8)
143  */
145 {
147  Motor(AP_MOTORS_MOT_2, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1, -1, 0, 0, 6, 0, -90),
148  Motor(AP_MOTORS_MOT_3, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5, -1, 0, 0, 6, 0, -90),
150  Motor(AP_MOTORS_MOT_5, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2, -1, 0, 0, 6, 0, -90),
151  Motor(AP_MOTORS_MOT_6, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6, -1, 0, 0, 6, 0, -90)
152 };
153 
154 /*
155  table of supported frame types. String order is important for
156  partial name matching
157  */
159 {
160  Frame("+", 4, quad_plus_motors),
161  Frame("quad", 4, quad_plus_motors),
162  Frame("copter", 4, quad_plus_motors),
163  Frame("x", 4, quad_x_motors),
164  Frame("tilthvec", 4, tiltquad_h_vectored_motors),
165  Frame("hexax", 6, hexax_motors),
166  Frame("hexa", 6, hexa_motors),
167  Frame("octa-quad", 8, octa_quad_motors),
168  Frame("octa", 8, octa_motors),
169  Frame("dodeca-hexa", 12, dodeca_hexa_motors),
170  Frame("tri", 3, tri_motors),
171  Frame("tilttrivec",3, tilttri_vectored_motors),
172  Frame("tilttri", 3, tilttri_motors),
173  Frame("y6", 6, y6_motors),
174  Frame("firefly", 6, firefly_motors)
175 };
176 
177 void Frame::init(float _mass, float hover_throttle, float _terminal_velocity, float _terminal_rotation_rate)
178 {
179  /*
180  scaling from total motor power to Newtons. Allows the copter
181  to hover against gravity when each motor is at hover_throttle
182  */
183  thrust_scale = (_mass * GRAVITY_MSS) / (num_motors * hover_throttle);
184 
185  terminal_velocity = _terminal_velocity;
186  terminal_rotation_rate = _terminal_rotation_rate;
187 }
188 
189 /*
190  find a frame by name
191  */
193 {
194  for (uint8_t i=0; i < ARRAY_SIZE(supported_frames); i++) {
195  // do partial name matching to allow for frame variants
196  if (strncasecmp(name, supported_frames[i].name, strlen(supported_frames[i].name)) == 0) {
197  return &supported_frames[i];
198  }
199  }
200  return nullptr;
201 }
202 
203 // calculate rotational and linear accelerations
204 void Frame::calculate_forces(const Aircraft &aircraft,
205  const Aircraft::sitl_input &input,
206  Vector3f &rot_accel,
207  Vector3f &body_accel)
208 {
209  Vector3f thrust; // newtons
210 
211  for (uint8_t i=0; i<num_motors; i++) {
212  Vector3f mraccel, mthrust;
213  motors[i].calculate_forces(input, thrust_scale, motor_offset, mraccel, mthrust);
214  rot_accel += mraccel;
215  thrust += mthrust;
216  }
217 
218  body_accel = thrust/aircraft.gross_mass();
219 
220  if (terminal_rotation_rate > 0) {
221  // rotational air resistance
222  const Vector3f &gyro = aircraft.get_gyro();
223  rot_accel.x -= gyro.x * radians(400.0) / terminal_rotation_rate;
224  rot_accel.y -= gyro.y * radians(400.0) / terminal_rotation_rate;
225  rot_accel.z -= gyro.z * radians(400.0) / terminal_rotation_rate;
226  }
227 
228  if (terminal_velocity > 0) {
229  // air resistance
230  Vector3f air_resistance = -aircraft.get_velocity_air_ef() * (GRAVITY_MSS/terminal_velocity);
231  body_accel += aircraft.get_dcm().transposed() * air_resistance;
232  }
233 
234  // add some noise
235  const float gyro_noise = radians(0.1);
236  const float accel_noise = 0.3;
237  const float noise_scale = thrust.length() / (thrust_scale * num_motors);
238  rot_accel += Vector3f(aircraft.rand_normal(0, 1),
239  aircraft.rand_normal(0, 1),
240  aircraft.rand_normal(0, 1)) * gyro_noise * noise_scale;
241  body_accel += Vector3f(aircraft.rand_normal(0, 1),
242  aircraft.rand_normal(0, 1),
243  aircraft.rand_normal(0, 1)) * accel_noise * noise_scale;
244 }
245 
const Vector3f & get_gyro(void) const
Definition: SIM_Aircraft.h:94
Vector3< float > Vector3f
Definition: vector3.h:246
#define AP_MOTORS_MOT_8
virtual float gross_mass() const
Definition: SIM_Aircraft.h:114
float thrust_scale
Definition: SIM_Frame.h:56
#define AP_MOTORS_MOT_4
#define AP_MOTORS_MOT_7
const Vector3f & get_velocity_air_ef(void) const
Definition: SIM_Aircraft.h:102
float terminal_rotation_rate
Definition: SIM_Frame.h:55
#define AP_MOTORS_MOT_1
#define AP_MOTORS_MOT_2
#define AP_MOTORS_MATRIX_YAW_FACTOR_CCW
static Motor hexa_motors[]
Definition: SIM_Frame.cpp:50
#define AP_MOTORS_MOT_11
Motor * motors
Definition: SIM_Frame.h:33
void init(float mass, float hover_throttle, float terminal_velocity, float terminal_rotation_rate)
Definition: SIM_Frame.cpp:177
static double rand_normal(double mean, double stddev)
Matrix3< T > transposed(void) const
Definition: matrix3.cpp:189
static Motor tiltquad_h_vectored_motors[]
Definition: SIM_Frame.cpp:42
static Motor tilttri_vectored_motors[]
Definition: SIM_Frame.cpp:124
static Motor quad_plus_motors[]
Definition: SIM_Frame.cpp:26
static Motor y6_motors[]
Definition: SIM_Frame.cpp:131
static Frame supported_frames[]
Definition: SIM_Frame.cpp:158
static Frame * find_frame(const char *name)
Definition: SIM_Frame.cpp:192
#define GRAVITY_MSS
Definition: definitions.h:47
void calculate_forces(const Aircraft::sitl_input &input, float thrust_scale, uint8_t motor_offset, Vector3f &rot_accel, Vector3f &body_thrust)
Definition: SIM_Motor.cpp:25
static Motor tilttri_motors[]
Definition: SIM_Frame.cpp:117
static Motor quad_x_motors[]
Definition: SIM_Frame.cpp:34
T y
Definition: vector3.h:67
static Motor firefly_motors[]
Definition: SIM_Frame.cpp:144
T z
Definition: vector3.h:67
uint8_t motor_offset
Definition: SIM_Frame.h:57
#define AP_MOTORS_MOT_6
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
#define AP_MOTORS_MOT_3
static Motor hexax_motors[]
Definition: SIM_Frame.cpp:60
float length(void) const
Definition: vector3.cpp:288
static Motor dodeca_hexa_motors[]
Definition: SIM_Frame.cpp:94
static Motor octa_quad_motors[]
Definition: SIM_Frame.cpp:82
void calculate_forces(const Aircraft &aircraft, const Aircraft::sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel)
Definition: SIM_Frame.cpp:204
static constexpr float radians(float deg)
Definition: AP_Math.h:158
#define AP_MOTORS_MOT_12
#define AP_MOTORS_MOT_5
#define AP_MOTORS_MOT_10
const char * name
Definition: SIM_Frame.h:31
uint8_t num_motors
Definition: SIM_Frame.h:32
float terminal_velocity
Definition: SIM_Frame.h:54
static Motor octa_motors[]
Definition: SIM_Frame.cpp:70
const Matrix3f & get_dcm(void) const
Definition: SIM_Aircraft.h:106
T x
Definition: vector3.h:67
#define AP_MOTORS_MOT_9
static Motor tri_motors[]
Definition: SIM_Frame.cpp:110
#define AP_MOTORS_MATRIX_YAW_FACTOR_CW