APM:Libraries
AP_MotorsHeli.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 /*
17  * AP_MotorsHeli.cpp - ArduCopter motors library
18  * Code by RandyMackay. DIYDrones.com
19  *
20  */
21 #include <stdlib.h>
22 #include <AP_HAL/AP_HAL.h>
23 #include "AP_MotorsHeli.h"
24 #include <GCS_MAVLink/GCS.h>
25 
26 extern const AP_HAL::HAL& hal;
27 
29 
30  // 1 was ROL_MAX which has been replaced by CYC_MAX
31 
32  // 2 was PIT_MAX which has been replaced by CYC_MAX
33 
34  // @Param: COL_MIN
35  // @DisplayName: Collective Pitch Minimum
36  // @Description: Lowest possible servo position in PWM microseconds for the swashplate
37  // @Range: 1000 2000
38  // @Units: PWM
39  // @Increment: 1
40  // @User: Standard
41  AP_GROUPINFO("COL_MIN", 3, AP_MotorsHeli, _collective_min, AP_MOTORS_HELI_COLLECTIVE_MIN),
42 
43  // @Param: COL_MAX
44  // @DisplayName: Collective Pitch Maximum
45  // @Description: Highest possible servo position in PWM microseconds for the swashplate
46  // @Range: 1000 2000
47  // @Units: PWM
48  // @Increment: 1
49  // @User: Standard
50  AP_GROUPINFO("COL_MAX", 4, AP_MotorsHeli, _collective_max, AP_MOTORS_HELI_COLLECTIVE_MAX),
51 
52  // @Param: COL_MID
53  // @DisplayName: Collective Pitch Mid-Point
54  // @Description: Swash servo position in PWM microseconds corresponding to zero collective pitch (or zero lift for Asymmetrical blades)
55  // @Range: 1000 2000
56  // @Units: PWM
57  // @Increment: 1
58  // @User: Standard
59  AP_GROUPINFO("COL_MID", 5, AP_MotorsHeli, _collective_mid, AP_MOTORS_HELI_COLLECTIVE_MID),
60 
61  // @Param: SV_MAN
62  // @DisplayName: Manual Servo Mode
63  // @Description: Manual servo override for swash set-up. Do not set this manually!
64  // @Values: 0:Disabled,1:Passthrough,2:Max collective,3:Mid collective,4:Min collective
65  // @User: Standard
66  AP_GROUPINFO("SV_MAN", 6, AP_MotorsHeli, _servo_mode, SERVO_CONTROL_MODE_AUTOMATED),
67 
68  // @Param: RSC_SETPOINT
69  // @DisplayName: External Motor Governor Setpoint
70  // @Description: PWM in microseconds passed to the external motor governor when external governor is enabled
71  // @Range: 0 1000
72  // @Units: PWM
73  // @Increment: 10
74  // @User: Standard
75  AP_GROUPINFO("RSC_SETPOINT", 7, AP_MotorsHeli, _rsc_setpoint, AP_MOTORS_HELI_RSC_SETPOINT),
76 
77  // @Param: RSC_MODE
78  // @DisplayName: Rotor Speed Control Mode
79  // @Description: Determines the method of rotor speed control
80  // @Values: 1:Ch8 Input, 2:SetPoint, 3:Throttle Curve
81  // @User: Standard
82  AP_GROUPINFO("RSC_MODE", 8, AP_MotorsHeli, _rsc_mode, (int8_t)ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH),
83 
84  // @Param: LAND_COL_MIN
85  // @DisplayName: Landing Collective Minimum
86  // @Description: Minimum collective position in PWM microseconds while landed or landing
87  // @Range: 0 500
88  // @Units: PWM
89  // @Increment: 1
90  // @User: Standard
91  AP_GROUPINFO("LAND_COL_MIN", 9, AP_MotorsHeli, _land_collective_min, AP_MOTORS_HELI_LAND_COLLECTIVE_MIN),
92 
93  // @Param: RSC_RAMP_TIME
94  // @DisplayName: RSC Ramp Time
95  // @Description: Time in seconds for the output to the main rotor's ESC to reach full speed
96  // @Range: 0 60
97  // @Units: s
98  // @User: Standard
99  AP_GROUPINFO("RSC_RAMP_TIME", 10, AP_MotorsHeli, _rsc_ramp_time, AP_MOTORS_HELI_RSC_RAMP_TIME),
100 
101  // @Param: RSC_RUNUP_TIME
102  // @DisplayName: RSC Runup Time
103  // @Description: Time in seconds for the main rotor to reach full speed. Must be longer than RSC_RAMP_TIME
104  // @Range: 0 60
105  // @Units: s
106  // @User: Standard
107  AP_GROUPINFO("RSC_RUNUP_TIME", 11, AP_MotorsHeli, _rsc_runup_time, AP_MOTORS_HELI_RSC_RUNUP_TIME),
108 
109  // @Param: RSC_CRITICAL
110  // @DisplayName: Critical Rotor Speed
111  // @Description: Rotor speed below which flight is not possible
112  // @Range: 0 1000
113  // @Increment: 10
114  // @User: Standard
115  AP_GROUPINFO("RSC_CRITICAL", 12, AP_MotorsHeli, _rsc_critical, AP_MOTORS_HELI_RSC_CRITICAL),
116 
117  // @Param: RSC_IDLE
118  // @DisplayName: Rotor Speed Output at Idle
119  // @Description: Rotor speed output while armed but rotor control speed is not engaged
120  // @Range: 0 500
121  // @Increment: 10
122  // @User: Standard
123  AP_GROUPINFO("RSC_IDLE", 13, AP_MotorsHeli, _rsc_idle_output, AP_MOTORS_HELI_RSC_IDLE_DEFAULT),
124 
125  // index 14 was RSC_POWER_LOW. Do not use this index in the future.
126 
127  // index 15 was RSC_POWER_HIGH. Do not use this index in the future.
128 
129  // @Param: CYC_MAX
130  // @DisplayName: Cyclic Pitch Angle Max
131  // @Description: Maximum pitch angle of the swash plate
132  // @Range: 0 18000
133  // @Units: cdeg
134  // @Increment: 100
135  // @User: Advanced
136  AP_GROUPINFO("CYC_MAX", 16, AP_MotorsHeli, _cyclic_max, AP_MOTORS_HELI_SWASH_CYCLIC_MAX),
137 
138  // @Param: SV_TEST
139  // @DisplayName: Boot-up Servo Test Cycles
140  // @Description: Number of cycles to run servo test on boot-up
141  // @Range: 0 10
142  // @Increment: 1
143  // @User: Standard
144  AP_GROUPINFO("SV_TEST", 17, AP_MotorsHeli, _servo_test, 0),
145 
146  // index 18 was RSC_POWER_NEGC. Do not use this index in the future.
147 
148  // @Param: RSC_SLEWRATE
149  // @DisplayName: Throttle servo slew rate
150  // @Description: This controls the maximum rate at which the throttle output can change, as a percentage per second. A value of 100 means the throttle can change over its full range in one second. A value of zero gives unlimited slew rate.
151  // @Range: 0 500
152  // @Increment: 10
153  // @User: Standard
154  AP_GROUPINFO("RSC_SLEWRATE", 19, AP_MotorsHeli, _rsc_slewrate, 0),
155 
156  // @Param: RSC_THRCRV_0
157  // @DisplayName: Throttle Servo Position for 0 percent collective
158  // @Description: Throttle Servo Position for 0 percent collective. This is on a scale from 0 to 1000, where 1000 is full throttle and 0 is zero throttle. Actual PWM values are controlled by SERVOX_MIN and SERVOX_MAX. The 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX.
159  // @Range: 0 1000
160  // @Increment: 10
161  // @User: Standard
162  AP_GROUPINFO("RSC_THRCRV_0", 20, AP_MotorsHeli, _rsc_thrcrv[0], AP_MOTORS_HELI_RSC_THRCRV_0_DEFAULT),
163 
164  // @Param: RSC_THRCRV_25
165  // @DisplayName: Throttle Servo Position for 25 percent collective
166  // @Description: Throttle Servo Position for 25 percent collective. This is on a scale from 0 to 1000, where 1000 is full throttle and 0 is zero throttle. Actual PWM values are controlled by SERVOX_MIN and SERVOX_MAX. The 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX.
167  // @Range: 0 1000
168  // @Increment: 10
169  // @User: Standard
170  AP_GROUPINFO("RSC_THRCRV_25", 21, AP_MotorsHeli, _rsc_thrcrv[1], AP_MOTORS_HELI_RSC_THRCRV_25_DEFAULT),
171 
172  // @Param: RSC_THRCRV_50
173  // @DisplayName: Throttle Servo Position for 50 percent collective
174  // @Description: Throttle Servo Position for 50 percent collective. This is on a scale from 0 to 1000, where 1000 is full throttle and 0 is zero throttle. Actual PWM values are controlled by SERVOX_MIN and SERVOX_MAX. The 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX.
175  // @Range: 0 1000
176  // @Increment: 10
177  // @User: Standard
178  AP_GROUPINFO("RSC_THRCRV_50", 22, AP_MotorsHeli, _rsc_thrcrv[2], AP_MOTORS_HELI_RSC_THRCRV_50_DEFAULT),
179 
180  // @Param: RSC_THRCRV_75
181  // @DisplayName: Throttle Servo Position for 75 percent collective
182  // @Description: Throttle Servo Position for 75 percent collective. This is on a scale from 0 to 1000, where 1000 is full throttle and 0 is zero throttle. Actual PWM values are controlled by SERVOX_MIN and SERVOX_MAX. The 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX.
183  // @Range: 0 1000
184  // @Increment: 10
185  // @User: Standard
186  AP_GROUPINFO("RSC_THRCRV_75", 23, AP_MotorsHeli, _rsc_thrcrv[3], AP_MOTORS_HELI_RSC_THRCRV_75_DEFAULT),
187 
188  // @Param: RSC_THRCRV_100
189  // @DisplayName: Throttle Servo Position for 100 percent collective
190  // @Description: Throttle Servo Position for 100 percent collective. This is on a scale from 0 to 1000, where 1000 is full throttle and 0 is zero throttle. Actual PWM values are controlled by SERVOX_MIN and SERVOX_MAX. The 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX.
191  // @Range: 0 1000
192  // @Increment: 10
193  // @User: Standard
194  AP_GROUPINFO("RSC_THRCRV_100", 24, AP_MotorsHeli, _rsc_thrcrv[4], AP_MOTORS_HELI_RSC_THRCRV_100_DEFAULT),
195 
197 };
198 
199 //
200 // public methods
201 //
202 
203 // init
205 {
206  // remember frame type
207  _frame_type = frame_type;
208 
209  // set update rate
211 
212  // load boot-up servo test cycles into counter to be consumed
214 
215  // ensure inputs are not passed through to servos on start-up
217 
218  // initialise radio passthrough for collective to middle
220 
221  // initialise Servo/PWM ranges and endpoints
222  if (!init_outputs()) {
223  // don't set initialised_ok
224  return;
225  }
226 
227  // calculate all scalars
229 
230  // record successful initialisation if what we setup was the desired frame_class
231  _flags.initialised_ok = (frame_class == MOTOR_FRAME_HELI);
232 }
233 
234 // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
236 {
237  _flags.initialised_ok = (frame_class == MOTOR_FRAME_HELI);
238 }
239 
240 // output_min - sets servos to neutral point with motors stopped
242 {
243  // move swash to mid
244  move_actuators(0.0f,0.0f,0.5f,0.0f);
245 
247 
248  // override limits flags
249  limit.roll_pitch = true;
250  limit.yaw = true;
251  limit.throttle_lower = true;
252  limit.throttle_upper = false;
253 }
254 
255 // output - sends commands to the servos
257 {
258  // update throttle filter
260 
261  if (_flags.armed) {
263  if (!_flags.interlock) {
265  } else {
267  }
268  } else {
269  output_disarmed();
270  }
271 };
272 
273 // sends commands to the motors
275 {
276  // if manual override active after arming, deactivate it and reinitialize servos
279  }
280 
282 
284 }
285 
286 // output_armed_zero_throttle - sends commands to the motors
288 {
289  // if manual override active after arming, deactivate it and reinitialize servos
292  }
293 
295 
297 }
298 
299 // output_disarmed - sends commands to the motors
301 {
302  if (_servo_test_cycle_counter > 0){
303  // perform boot-up servo test cycle if enabled
304  servo_test();
305  } else {
306  // manual override (i.e. when setting up swash)
307  switch (_servo_mode) {
309  // pass pilot commands straight through to swash
314  break;
316  // fixate mid collective
317  _roll_in = 0.0f;
318  _pitch_in = 0.0f;
320  _yaw_in = 0.0f;
321  break;
323  // fixate max collective
324  _roll_in = 0.0f;
325  _pitch_in = 0.0f;
327  _yaw_in = 1.0f;
328  break;
330  // fixate min collective
331  _roll_in = 0.0f;
332  _pitch_in = 0.0f;
334  _yaw_in = -1.0f;
335  break;
337  // use servo_test function from child classes
338  servo_test();
339  break;
340  default:
341  // no manual override
342  break;
343  }
344  }
345 
346  // ensure swash servo endpoints haven't been moved
347  init_outputs();
348 
349  // continuously recalculate scalars to allow setup
351 
352  // helicopters always run stabilizing flight controls
354 
356 }
357 
358 // parameter_check - check if helicopter specific parameters are sensible
359 bool AP_MotorsHeli::parameter_check(bool display_msg) const
360 {
361  // returns false if _rsc_setpoint is not higher than _rsc_critical as this would not allow rotor_runup_complete to ever return true
362  if (_rsc_critical >= _rsc_setpoint) {
363  if (display_msg) {
364  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_CRITICAL too large");
365  }
366  return false;
367  }
368 
369  // returns false if RSC Mode is not set to a valid control mode
371  if (display_msg) {
372  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_MODE invalid");
373  }
374  return false;
375  }
376 
377  // returns false if RSC Runup Time is less than Ramp time as this could cause undesired behaviour of rotor speed estimate
379  if (display_msg) {
380  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RUNUP_TIME too small");
381  }
382  return false;
383  }
384 
385  // returns false if idle output is higher than critical rotor speed as this could block runup_complete from going false
387  if (display_msg) {
388  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_IDLE too large");
389  }
390  return false;
391  }
392 
393  // all other cases parameters are OK
394  return true;
395 }
396 
397 // reset_swash_servo
399 {
400  servo->set_range(1000);
401 
402  // swash servos always use full endpoints as restricting them would lead to scaling errors
403  servo->set_output_min(1000);
404  servo->set_output_max(2000);
405 }
406 
407 // update the throttle input filter
409 {
411 
412  // constrain filtered throttle
413  if (_throttle_filter.get() < 0.0f) {
415  }
416  if (_throttle_filter.get() > 1.0f) {
418  }
419 }
420 
421 // reset_flight_controls - resets all controls and scalars to flight status
423 {
425  init_outputs();
427 }
428 
429 // convert input in -1 to +1 range to pwm output for swashplate servo. Special handling of trim is required
430 // to keep travel between the swashplate servos consistent. Swashplate servo travel range is fixed to 1000 pwm
431 // and therefore the input is multiplied by 500 to get PWM output.
433 {
434  int16_t ret;
435 
436  input = constrain_float(input, -1.0f, 1.0f);
437 
438  if (servo->get_reversed()) {
439  input = -input;
440  }
441 
442  ret = (int16_t (input * 500.0f) + servo->get_trim());
443 
444  return constrain_int16(ret, servo->get_output_min(), servo->get_output_max());
445 }
446 
447 
void reset(T value)
virtual void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out)=0
AP_Int8 _servo_test
AP_Int8 _rsc_runup_time
void set_output_max(uint16_t pwm)
Definition: SRV_Channel.h:156
#define AP_MOTORS_HELI_RSC_RUNUP_TIME
Definition: AP_MotorsHeli.h:42
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
motor_frame_type _frame_type
#define AP_MOTORS_HELI_RSC_THRCRV_75_DEFAULT
Definition: AP_MotorsHeli.h:37
#define AP_MOTORS_HELI_COLLECTIVE_MIN
Definition: AP_MotorsHeli.h:19
void set_range(uint16_t high)
float _collective_mid_pct
AP_Int8 _servo_mode
Interface definition for the various Ground Control System.
struct AP_Motors::AP_Motors_flags _flags
uint16_t get_output_max(void) const
Definition: SRV_Channel.h:164
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
struct AP_Motors::AP_Motors_limit limit
AP_Int8 _rsc_ramp_time
#define AP_MOTORS_HELI_COLLECTIVE_MAX
Definition: AP_MotorsHeli.h:20
GCS & gcs()
#define AP_MOTORS_HELI_RSC_THRCRV_100_DEFAULT
Definition: AP_MotorsHeli.h:38
int16_t calc_pwm_output_1to1_swash_servo(float input, const SRV_Channel *servo)
virtual void calculate_scalars()=0
virtual void servo_test()=0
#define AP_MOTORS_HELI_COLLECTIVE_MID
Definition: AP_MotorsHeli.h:21
uint8_t _servo_test_cycle_counter
AP_Int16 _rsc_setpoint
#define AP_MOTORS_HELI_RSC_THRCRV_0_DEFAULT
Definition: AP_MotorsHeli.h:34
void init(motor_frame_class frame_class, motor_frame_type frame_type)
AP_Int16 _rsc_idle_output
virtual bool parameter_check(bool display_msg) const
void reset_flight_controls()
uint16_t _loop_rate
#define AP_MOTORS_HELI_RSC_THRCRV_50_DEFAULT
Definition: AP_MotorsHeli.h:36
#define f(i)
virtual void calculate_armed_scalars()=0
AP_Int16 _rsc_critical
#define AP_MOTORS_HELI_LAND_COLLECTIVE_MIN
Definition: AP_MotorsHeli.h:24
void output_disarmed()
void reset_swash_servo(SRV_Channel *servo)
uint16_t get_output_min(void) const
Definition: SRV_Channel.h:161
AP_Int8 _rsc_mode
uint16_t _speed_hz
virtual void update_motor_control(RotorControlState state)=0
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
void output_armed_zero_throttle()
float _throttle_radio_passthrough
const T & get() const
float _pitch_radio_passthrough
LowPassFilterFloat _throttle_filter
uint16_t get_trim(void) const
Definition: SRV_Channel.h:167
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
static const struct AP_Param::GroupInfo var_info[]
void set_output_min(uint16_t pwm)
Definition: SRV_Channel.h:153
#define AP_MOTORS_HELI_SWASH_CYCLIC_MAX
Definition: AP_MotorsHeli.h:18
#define AP_MOTORS_HELI_RSC_IDLE_DEFAULT
Definition: AP_MotorsHeli.h:33
float _roll_radio_passthrough
bool get_reversed(void) const
Definition: SRV_Channel.h:148
void update_throttle_filter()
float _yaw_radio_passthrough
Motor control class for Traditional Heli.
#define AP_MOTORS_HELI_RSC_THRCRV_25_DEFAULT
Definition: AP_MotorsHeli.h:35
float get_throttle() const
#define AP_MOTORS_HELI_RSC_SETPOINT
Definition: AP_MotorsHeli.h:27
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define AP_MOTORS_HELI_RSC_CRITICAL
Definition: AP_MotorsHeli.h:30
float _throttle_in
virtual bool init_outputs()=0
void output_armed_stabilizing()
virtual void set_update_rate(uint16_t speed_hz)=0
#define AP_GROUPEND
Definition: AP_Param.h:121
#define AP_MOTORS_HELI_RSC_RAMP_TIME
Definition: AP_MotorsHeli.h:41
T apply(T sample, float dt)