APM:Libraries
SIM_Helicopter.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  helicopter simulator class
17 */
18 
19 #include "SIM_Helicopter.h"
20 
21 #include <stdio.h>
22 
23 namespace SITL {
24 
25 Helicopter::Helicopter(const char *home_str, const char *frame_str) :
26  Aircraft(home_str, frame_str)
27 {
28  mass = 2.13f;
29 
30  /*
31  scaling from motor power to Newtons. Allows the copter
32  to hover against gravity when the motor is at hover_throttle
33  */
35 
36  // calculate lateral thrust ratio for tail rotor
38 
39  frame_height = 0.1;
40 
41  if (strstr(frame_str, "-dual")) {
43  } else if (strstr(frame_str, "-compound")) {
45  } else {
47  }
48  gas_heli = (strstr(frame_str, "-gas") != nullptr);
49 
51 }
52 
53 /*
54  update the helicopter simulation by one time step
55  */
56 void Helicopter::update(const struct sitl_input &input)
57 {
58  // get wind vector setup
59  update_wind(input);
60 
61  float rsc = constrain_float((input.servos[7]-1000) / 1000.0f, 0, 1);
62  // ignition only for gas helis
63  bool ignition_enabled = gas_heli?(input.servos[5] > 1500):true;
64 
65  float thrust = 0;
66  float roll_rate = 0;
67  float pitch_rate = 0;
68  float yaw_rate = 0;
69  float torque_effect_accel = 0;
70  float lateral_x_thrust = 0;
71  float lateral_y_thrust = 0;
72 
73  float swash1 = (input.servos[0]-1000) / 1000.0f;
74  float swash2 = (input.servos[1]-1000) / 1000.0f;
75  float swash3 = (input.servos[2]-1000) / 1000.0f;
76 
77  if (!ignition_enabled) {
78  rsc = 0;
79  }
80  float rsc_scale = rsc/rsc_setpoint;
81 
82  switch (frame_type) {
84  // simulate a traditional helicopter
85 
86  float tail_rotor = (input.servos[3]-1000) / 1000.0f;
87 
88  thrust = (rsc/rsc_setpoint) * (swash1+swash2+swash3) / 3.0f;
89  torque_effect_accel = (rsc_scale+thrust) * rotor_rot_accel;
90 
91  roll_rate = swash1 - swash2;
92  pitch_rate = (swash1+swash2) / 2.0f - swash3;
93  yaw_rate = tail_rotor - 0.5f;
94 
95  lateral_y_thrust = yaw_rate * rsc_scale * tail_thrust_scale;
96  break;
97  }
98 
99  case HELI_FRAME_DUAL: {
100  // simulate a tandem helicopter
101 
102  float swash4 = (input.servos[3]-1000) / 1000.0f;
103  float swash5 = (input.servos[4]-1000) / 1000.0f;
104  float swash6 = (input.servos[5]-1000) / 1000.0f;
105 
106  thrust = (rsc / rsc_setpoint) * (swash1+swash2+swash3+swash4+swash5+swash6) / 6.0f;
107  torque_effect_accel = (rsc_scale + rsc / rsc_setpoint) * rotor_rot_accel * ((swash1+swash2+swash3) - (swash4+swash5+swash6));
108 
109  roll_rate = (swash1-swash2) + (swash4-swash5);
110  pitch_rate = (swash1+swash2+swash3) - (swash4+swash5+swash6);
111  yaw_rate = (swash1-swash2) + (swash5-swash4);
112  break;
113  }
114 
115  case HELI_FRAME_COMPOUND: {
116  // simulate a compound helicopter
117 
118  float right_rotor = (input.servos[3]-1000) / 1000.0f;
119  float left_rotor = (input.servos[4]-1000) / 1000.0f;
120 
121  thrust = (rsc/rsc_setpoint) * (swash1+swash2+swash3) / 3.0f;
122  torque_effect_accel = (rsc_scale+thrust) * rotor_rot_accel;
123 
124  roll_rate = swash1 - swash2;
125  pitch_rate = (swash1+swash2) / 2.0f - swash3;
126  yaw_rate = right_rotor - left_rotor;
127 
128  lateral_x_thrust = (left_rotor+right_rotor-1) * rsc_scale * tail_thrust_scale;
129  break;
130  }
131  }
132 
133  roll_rate *= rsc_scale;
134  pitch_rate *= rsc_scale;
135  yaw_rate *= rsc_scale;
136 
137  // rotational acceleration, in rad/s/s, in body frame
138  Vector3f rot_accel;
139  rot_accel.x = roll_rate * roll_rate_max;
140  rot_accel.y = pitch_rate * pitch_rate_max;
141  rot_accel.z = yaw_rate * yaw_rate_max;
142 
143  // rotational air resistance
144  rot_accel.x -= gyro.x * radians(5000.0) / terminal_rotation_rate;
145  rot_accel.y -= gyro.y * radians(5000.0) / terminal_rotation_rate;
146  rot_accel.z -= gyro.z * radians(400.0) / terminal_rotation_rate;
147 
148  // torque effect on tail
149  rot_accel.z += torque_effect_accel;
150 
151  // air resistance
153 
154  // simulate rotor speed
155  rpm1 = thrust * 1300;
156 
157  // scale thrust to newtons
158  thrust *= thrust_scale;
159 
160  accel_body = Vector3f(lateral_x_thrust, lateral_y_thrust, -thrust / mass);
161  accel_body += dcm.transposed() * air_resistance;
162 
163  update_dynamics(rot_accel);
164 
165  // update lat/lon/altitude
166  update_position();
167  time_advance();
168 
169  // update magnetic field
171 }
172 
173 } // namespace SITL
Vector3f accel_body
Definition: SIM_Aircraft.h:142
void update_wind(const struct sitl_input &input)
Vector3< float > Vector3f
Definition: vector3.h:246
Vector3f velocity_air_ef
Definition: SIM_Aircraft.h:138
void update(const struct sitl_input &input)
Matrix3< T > transposed(void) const
Definition: matrix3.cpp:189
#define GRAVITY_MSS
Definition: definitions.h:47
#define f(i)
T y
Definition: vector3.h:67
Helicopter(const char *home_str, const char *frame_str)
T z
Definition: vector3.h:67
void update_mag_field_bf(void)
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
void update_position(void)
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void update_dynamics(const Vector3f &rot_accel)
enum SITL::Helicopter::frame_types frame_type
enum SITL::Aircraft::@199 ground_behavior
float terminal_rotation_rate
T x
Definition: vector3.h:67