APM:Libraries
AP_MotorsHeli_Single.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 #include <stdlib.h>
17 #include <AP_HAL/AP_HAL.h>
19 #include "AP_MotorsHeli_Single.h"
20 #include <GCS_MAVLink/GCS.h>
21 
22 extern const AP_HAL::HAL& hal;
23 
26 
27  // @Param: SV1_POS
28  // @DisplayName: Servo 1 Position
29  // @Description: Angular location of swash servo #1 - only used for H3 swash type
30  // @Range: -180 180
31  // @Units: deg
32  // @User: Standard
33  // @Increment: 1
35 
36  // @Param: SV2_POS
37  // @DisplayName: Servo 2 Position
38  // @Description: Angular location of swash servo #2 - only used for H3 swash type
39  // @Range: -180 180
40  // @Units: deg
41  // @User: Standard
42  // @Increment: 1
44 
45  // @Param: SV3_POS
46  // @DisplayName: Servo 3 Position
47  // @Description: Angular location of swash servo #3 - only used for H3 swash type
48  // @Range: -180 180
49  // @Units: deg
50  // @User: Standard
51  // @Increment: 1
53 
54  // @Param: TAIL_TYPE
55  // @DisplayName: Tail Type
56  // @Description: Tail type selection. Simpler yaw controller used if external gyro is selected
57  // @Values: 0:Servo only,1:Servo with ExtGyro,2:DirectDrive VarPitch,3:DirectDrive FixedPitch
58  // @User: Standard
60 
61  // @Param: SWASH_TYPE
62  // @DisplayName: Swash Type
63  // @Description: Swash Type Setting
64  // @Values: 0:H3 CCPM Adjustable, 1:H1 Straight Swash, 2:H3_140 CCPM
65  // @User: Standard
67 
68  // @Param: GYR_GAIN
69  // @DisplayName: External Gyro Gain
70  // @Description: PWM in microseconds sent to external gyro on ch7 when tail type is Servo w/ ExtGyro
71  // @Range: 0 1000
72  // @Units: PWM
73  // @Increment: 1
74  // @User: Standard
75  AP_GROUPINFO("GYR_GAIN", 6, AP_MotorsHeli_Single, _ext_gyro_gain_std, AP_MOTORS_HELI_SINGLE_EXT_GYRO_GAIN),
76 
77  // @Param: PHANG
78  // @DisplayName: Swashplate Phase Angle Compensation
79  // @Description: Only for H3 swashplate. If pitching the swash forward induces a roll, this can be correct the problem
80  // @Range: -30 30
81  // @Units: deg
82  // @User: Advanced
83  // @Increment: 1
84  AP_GROUPINFO("PHANG", 7, AP_MotorsHeli_Single, _phase_angle, 0),
85 
86  // @Param: COLYAW
87  // @DisplayName: Collective-Yaw Mixing
88  // @Description: Feed-forward compensation to automatically add rudder input when collective pitch is increased. Can be positive or negative depending on mechanics.
89  // @Range: -10 10
90  // @Increment: 0.1
91  // @User: Advanced
92  AP_GROUPINFO("COLYAW", 8, AP_MotorsHeli_Single, _collective_yaw_effect, 0),
93 
94  // @Param: FLYBAR_MODE
95  // @DisplayName: Flybar Mode Selector
96  // @Description: Flybar present or not. Affects attitude controller used during ACRO flight mode
97  // @Values: 0:NoFlybar,1:Flybar
98  // @User: Standard
99  AP_GROUPINFO("FLYBAR_MODE", 9, AP_MotorsHeli_Single, _flybar_mode, AP_MOTORS_HELI_NOFLYBAR),
100 
101  // @Param: TAIL_SPEED
102  // @DisplayName: Direct Drive VarPitch Tail ESC speed
103  // @Description: Direct Drive VarPitch Tail ESC speed in PWM microseconds. Only used when TailType is DirectDrive VarPitch
104  // @Range: 0 1000
105  // @Units: PWM
106  // @Increment: 1
107  // @User: Standard
108  AP_GROUPINFO("TAIL_SPEED", 10, AP_MotorsHeli_Single, _direct_drive_tailspeed, AP_MOTORS_HELI_SINGLE_DDVP_SPEED_DEFAULT),
109 
110  // @Param: GYR_GAIN_ACRO
111  // @DisplayName: External Gyro Gain for ACRO
112  // @Description: PWM in microseconds sent to external gyro on ch7 when tail type is Servo w/ ExtGyro. A value of zero means to use H_GYR_GAIN
113  // @Range: 0 1000
114  // @Units: PWM
115  // @Increment: 1
116  // @User: Standard
117  AP_GROUPINFO("GYR_GAIN_ACRO", 11, AP_MotorsHeli_Single, _ext_gyro_gain_acro, 0),
118 
119  // Indices 16-18 were used by RSC_PWM_MIN, RSC_PWM_MAX and RSC_PWM_REV and should not be used
120 
121  // @Param: COL_CTRL_DIR
122  // @DisplayName: Collective Control Direction
123  // @Description: Collective Control Direction - 0 for Normal. 1 for Reversed
124  // @Values: 0: Normal, 1: Reversed
125  // @User: Standard
126  AP_GROUPINFO("COL_CTRL_DIR", 19, AP_MotorsHeli_Single, _collective_direction, AP_MOTORS_HELI_SINGLE_COLLECTIVE_DIRECTION_NORMAL),
127 
128  // parameters up to and including 29 are reserved for tradheli
129 
131 };
132 
133 // set update rate to motors - a value in hertz
134 void AP_MotorsHeli_Single::set_update_rate( uint16_t speed_hz )
135 {
136  // record requested speed
137  _speed_hz = speed_hz;
138 
139  // setup fast channels
140  uint32_t mask =
141  1U << AP_MOTORS_MOT_1 |
142  1U << AP_MOTORS_MOT_2 |
143  1U << AP_MOTORS_MOT_3 |
144  1U << AP_MOTORS_MOT_4;
145  rc_set_freq(mask, _speed_hz);
146 }
147 
148 // init_outputs - initialise Servo/PWM ranges and endpoints
150 {
151  if (!_flags.initialised_ok) {
159  return false;
160  }
161  } else {
164  return false;
165  }
166  }
167  }
168 
169  // reset swash servo range and endpoints
173 
174  _yaw_servo->set_angle(4500);
175 
176  // set main rotor servo range
177  // tail rotor servo use range as set in vehicle code for rc7
179 
180  return true;
181 }
182 
183 // output_test - spin a motor at the pwm value specified
184 // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
185 // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
186 void AP_MotorsHeli_Single::output_test(uint8_t motor_seq, int16_t pwm)
187 {
188  // exit immediately if not armed
189  if (!armed()) {
190  return;
191  }
192 
193  // output to motors and servos
194  switch (motor_seq) {
195  case 1:
196  // swash servo 1
198  break;
199  case 2:
200  // swash servo 2
202  break;
203  case 3:
204  // swash servo 3
206  break;
207  case 4:
208  // external gyro & tail servo
210  if (_acro_tail && _ext_gyro_gain_acro > 0) {
212  } else {
214  }
215  }
217  break;
218  case 5:
219  // main rotor
221  break;
222  default:
223  // do nothing
224  break;
225  }
226 }
227 
228 // set_desired_rotor_speed
230 {
231  _main_rotor.set_desired_speed(desired_speed);
232 
233  // always send desired speed to tail rotor control, will do nothing if not DDVP not enabled
235 }
236 
237 // calculate_scalars - recalculates various scalers used.
239 {
240  float thrcrv[5];
241  for (uint8_t i = 0; i < 5; i++) {
242  thrcrv[i]=_rsc_thrcrv[i]*0.001f;
243  }
248  _main_rotor.set_throttle_curve(thrcrv, (uint16_t)_rsc_slewrate.get());
249 }
250 
251 
252 // calculate_scalars - recalculates various scalers used.
254 {
255  // range check collective min, max and mid
259  }
261 
262  // calculate collective mid point as a number from 0 to 1
264 
265  // calculate factors based on swash type and servo position
267 
268  // send setpoints to main rotor controller and trigger recalculation of scalars
269  _main_rotor.set_control_mode(static_cast<RotorControlMode>(_rsc_mode.get()));
271 
272  // send setpoints to DDVP rotor controller and trigger recalculation of scalars
279  } else {
285  }
286 }
287 
288 // CCPM Mixers - calculate mixing scale factors by swashplate type
290 {
291  if (_swash_type == AP_MOTORS_HELI_SINGLE_SWASH_H3) { //Three-Servo adjustable CCPM mixer factors
292  // aileron factors
296 
297  // elevator factors
301 
302  // collective factors
303  _collectiveFactor[CH_1] = 1;
304  _collectiveFactor[CH_2] = 1;
305  _collectiveFactor[CH_3] = 1;
306  } else if (_swash_type == AP_MOTORS_HELI_SINGLE_SWASH_H3_140) { //Three-Servo H3-140 CCPM mixer factors
307  // aileron factors
308  _rollFactor[CH_1] = 1;
309  _rollFactor[CH_2] = -1;
310  _rollFactor[CH_3] = 0;
311 
312  // elevator factors
313  _pitchFactor[CH_1] = 1;
314  _pitchFactor[CH_2] = 1;
315  _pitchFactor[CH_3] = -1;
316 
317  // collective factors
318  _collectiveFactor[CH_1] = 1;
319  _collectiveFactor[CH_2] = 1;
320  _collectiveFactor[CH_3] = 1;
321  } else { //H1 straight outputs, no mixing
322  // aileron factors
323  _rollFactor[CH_1] = 1;
324  _rollFactor[CH_2] = 0;
325  _rollFactor[CH_3] = 0;
326 
327  // elevator factors
328  _pitchFactor[CH_1] = 0;
329  _pitchFactor[CH_2] = 1;
330  _pitchFactor[CH_3] = 0;
331 
332  // collective factors
333  _collectiveFactor[CH_1] = 0;
334  _collectiveFactor[CH_2] = 0;
335  _collectiveFactor[CH_3] = 1;
336  }
337 }
338 
339 // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
340 // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
342 {
343  // heli uses channels 1,2,3,4,7 and 8
344  return rc_map_mask(1U << 0 | 1U << 1 | 1U << 2 | 1U << 3 | 1U << AP_MOTORS_HELI_SINGLE_AUX | 1U << AP_MOTORS_HELI_SINGLE_RSC);
345 }
346 
347 // update_motor_controls - sends commands to motor controllers
349 {
350  // Send state update to motors
351  _tail_rotor.output(state);
352  _main_rotor.output(state);
353 
354  if (state == ROTOR_CONTROL_STOP){
355  // set engine run enable aux output to not run position to kill engine when disarmed
357  } else {
358  // else if armed, set engine run enable output to run position
360  }
361 
362  // Check if both rotors are run-up, tail rotor controller always returns true if not enabled
364 }
365 
366 //
367 // move_actuators - moves swash plate and tail rotor
368 // - expected ranges:
369 // roll : -1 ~ +1
370 // pitch: -1 ~ +1
371 // collective: 0 ~ 1
372 // yaw: -1 ~ +1
373 //
374 void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out)
375 {
376  float yaw_offset = 0.0f;
377 
378  // initialize limits flag
379  limit.roll_pitch = false;
380  limit.yaw = false;
381  limit.throttle_lower = false;
382  limit.throttle_upper = false;
383 
385  coll_in = 1 - coll_in;
386  }
387 
388  // rescale roll_out and pitch_out into the min and max ranges to provide linear motion
389  // across the input range instead of stopping when the input hits the constrain value
390  // these calculations are based on an assumption of the user specified cyclic_max
391  // coming into this equation at 4500 or less
392  float total_out = norm(pitch_out, roll_out);
393 
394  if (total_out > (_cyclic_max/4500.0f)) {
395  float ratio = (float)(_cyclic_max/4500.0f) / total_out;
396  roll_out *= ratio;
397  pitch_out *= ratio;
398  limit.roll_pitch = true;
399  }
400 
401  // constrain collective input
402  float collective_out = coll_in;
403  if (collective_out <= 0.0f) {
404  collective_out = 0.0f;
405  limit.throttle_lower = true;
406  }
407  if (collective_out >= 1.0f) {
408  collective_out = 1.0f;
409  limit.throttle_upper = true;
410  }
411 
412  // ensure not below landed/landing collective
413  if (_heliflags.landing_collective && collective_out < (_land_collective_min*0.001f)) {
414  collective_out = (_land_collective_min*0.001f);
415  limit.throttle_lower = true;
416  }
417 
418  // if servo output not in manual mode, process pre-compensation factors
420  // rudder feed forward based on collective
421  // the feed-forward is not required when the motor is stopped or at idle, and thus not creating torque
422  // also not required if we are using external gyro
424  // sanity check collective_yaw_effect
426  // the 4.5 scaling factor is to bring the values in line with previous releases
427  yaw_offset = _collective_yaw_effect * fabsf(collective_out - _collective_mid_pct) / 4.5f;
428  }
429  } else {
430  yaw_offset = 0.0f;
431  }
432 
433  // feed power estimate into main rotor controller
434  // ToDo: include tail rotor power?
435  // ToDo: add main rotor cyclic power?
436  _main_rotor.set_collective(fabsf(collective_out));
437 
438  // scale collective pitch for swashplate servos
439  float collective_scalar = ((float)(_collective_max-_collective_min))*0.001f;
440  float collective_out_scaled = collective_out * collective_scalar + (_collective_min - 1000)*0.001f;
441 
442  // Collective control direction. Swash moves up for negative collective pitch, down for positive collective pitch
444  collective_out_scaled = 1 - collective_out_scaled;
445  }
446  float servo1_out = ((_rollFactor[CH_1] * roll_out) + (_pitchFactor[CH_1] * pitch_out))*0.45f + _collectiveFactor[CH_1] * collective_out_scaled;
447  float servo2_out = ((_rollFactor[CH_2] * roll_out) + (_pitchFactor[CH_2] * pitch_out))*0.45f + _collectiveFactor[CH_2] * collective_out_scaled;
449  servo1_out += 0.5f;
450  servo2_out += 0.5f;
451  }
452  float servo3_out = ((_rollFactor[CH_3] * roll_out) + (_pitchFactor[CH_3] * pitch_out))*0.45f + _collectiveFactor[CH_3] * collective_out_scaled;
453 
454  // rescale from -1..1, so we can use the pwm calc that includes trim
455  servo1_out = 2*servo1_out - 1;
456  servo2_out = 2*servo2_out - 1;
457  servo3_out = 2*servo3_out - 1;
458 
459  // actually move the servos
463 
464  // update the yaw rate using the tail rotor/servo
465  move_yaw(yaw_out + yaw_offset);
466 }
467 
468 // move_yaw
470 {
471  // sanity check yaw_out
472  if (yaw_out < -1.0f) {
473  yaw_out = -1.0f;
474  limit.yaw = true;
475  }
476  if (yaw_out > 1.0f) {
477  yaw_out = 1.0f;
478  limit.yaw = true;
479  }
480 
482  if (_main_rotor.get_desired_speed() > 0.0f && hal.util->get_soft_armed()) {
483  // constrain output so that motor never fully stops
484  yaw_out = constrain_float(yaw_out, -0.9f, 1.0f);
485  // output yaw servo to tail rsc
487  } else {
488  // output zero speed to tail rsc
490  }
491  } else {
493  }
495  // output gain to exernal gyro
496  if (_acro_tail && _ext_gyro_gain_acro > 0) {
498  } else {
500  }
501  }
502 }
503 
504 // write_aux - converts servo_out parameter value (0 to 1 range) to pwm and outputs to aux channel (ch7)
505 void AP_MotorsHeli_Single::write_aux(float servo_out)
506 {
507  if (_servo_aux) {
509  }
510 }
511 
512 // servo_test - move servos through full range of movement
514 {
516 
517  if ((_servo_test_cycle_time >= 0.0f && _servo_test_cycle_time < 0.5f)|| // Tilt swash back
519  _pitch_test += (1.0f / (_loop_rate / 2.0f));
521  _yaw_test = 0.5f * sinf(_oscillate_angle);
522  } else if ((_servo_test_cycle_time >= 0.5f && _servo_test_cycle_time < 4.5f)|| // Roll swash around
524  _oscillate_angle += M_PI / (2 * _loop_rate);
527  _yaw_test = sinf(_oscillate_angle);
528  } else if ((_servo_test_cycle_time >= 4.5f && _servo_test_cycle_time < 5.0f)|| // Return swash to level
530  _pitch_test -= (1.0f / (_loop_rate / 2.0f));
532  _yaw_test = 0.5f * sinf(_oscillate_angle);
533  } else if (_servo_test_cycle_time >= 5.0f && _servo_test_cycle_time < 6.0f){ // Raise swash to top
534  _collective_test = 1.0f;
536  _yaw_test = sinf(_oscillate_angle);
537  } else if (_servo_test_cycle_time >= 11.0f && _servo_test_cycle_time < 12.0f){ // Lower swash to bottom
538  _collective_test = 0.0f;
540  _yaw_test = sinf(_oscillate_angle);
541  } else { // reset cycle
542  _servo_test_cycle_time = 0.0f;
543  _oscillate_angle = 0.0f;
544  _collective_test = 0.0f;
545  _roll_test = 0.0f;
546  _pitch_test = 0.0f;
547  _yaw_test = 0.0f;
548  // decrement servo test cycle counter at the end of the cycle
549  if (_servo_test_cycle_counter > 0){
551  }
552  }
553 
554  // over-ride servo commands to move servos through defined ranges
558  _yaw_in = _yaw_test;
559 }
560 
561 // parameter_check - check if helicopter specific parameters are sensible
562 bool AP_MotorsHeli_Single::parameter_check(bool display_msg) const
563 {
564  // returns false if Phase Angle is outside of range
565  if ((_phase_angle > 30) || (_phase_angle < -30)){
566  if (display_msg) {
567  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_PHANG out of range");
568  }
569  return false;
570  }
571 
572  // returns false if Acro External Gyro Gain is outside of range
573  if ((_ext_gyro_gain_acro < 0) || (_ext_gyro_gain_acro > 1000)){
574  if (display_msg) {
575  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_GYR_GAIN_ACRO out of range");
576  }
577  return false;
578  }
579 
580  // returns false if Standard External Gyro Gain is outside of range
581  if ((_ext_gyro_gain_std < 0) || (_ext_gyro_gain_std > 1000)){
582  if (display_msg) {
583  gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_GYR_GAIN out of range");
584  }
585  return false;
586  }
587 
588  // check parent class parameters
589  return AP_MotorsHeli::parameter_check(display_msg);
590 }
void reset(T value)
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
#define AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO
#define CH_3
Definition: RCOutput.h:13
bool get_soft_armed() const
Definition: Util.h:15
#define AP_MOTORS_HELI_NOFLYBAR
Definition: AP_MotorsHeli.h:45
AP_Int8 _rsc_runup_time
AP_Int16 _collective_max
void calculate_roll_pitch_collective_factors() override
#define AP_MOTORS_HELI_SINGLE_AUX
#define AP_MOTORS_HELI_SINGLE_DDVP_SPEED_DEFAULT
AP_MotorsHeli_RSC _main_rotor
#define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
float _rollFactor[AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS]
#define AP_MOTORS_MOT_4
void set_angle(int16_t angle)
#define AP_MOTORS_HELI_COLLECTIVE_MIN
Definition: AP_MotorsHeli.h:19
engine kill switch, used for gas airplanes and helicopters
Definition: SRV_Channel.h:74
#define CH_1
Definition: RCOutput.h:11
AP_Int16 _collective_mid
float _collective_mid_pct
AP_Int8 _servo_mode
#define AP_MOTORS_HELI_SINGLE_SERVO3_POS
void set_desired_speed(float desired_speed)
Interface definition for the various Ground Control System.
#define AP_MOTORS_MOT_1
struct AP_Motors::AP_Motors_flags _flags
#define AP_MOTORS_MOT_2
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
void set_desired_rotor_speed(float desired_speed) override
struct AP_Motors::AP_Motors_limit limit
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void set_critical_speed(float critical_speed)
AP_Int8 _rsc_ramp_time
AP_HAL::Util * util
Definition: HAL.h:115
static SRV_Channel * get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan=-1)
#define AP_MOTORS_HELI_COLLECTIVE_MAX
Definition: AP_MotorsHeli.h:20
RotorControlState
GCS & gcs()
int16_t calc_pwm_output_1to1_swash_servo(float input, const SRV_Channel *servo)
struct AP_MotorsHeli::heliflags_type _heliflags
void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override
static uint16_t pwm
Definition: RCOutput.cpp:20
#define AP_MOTORS_HELI_SINGLE_RSC
int16_t calc_pwm_output_0to1(float input, const SRV_Channel *servo)
AP_MotorsHeli_RSC _tail_rotor
void set_idle_output(float idle_output)
static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
#define AP_MOTORS_HELI_SINGLE_SERVO1_POS
bool is_runup_complete() const
#define CH_4
Definition: RCOutput.h:14
AP_Int16 _rsc_slewrate
#define AP_MOTORS_HELI_SINGLE_COLLECTIVE_DIRECTION_REVERSED
uint8_t _servo_test_cycle_counter
#define AP_MOTORS_HELI_SINGLE_SWASH_H3_140
float get_desired_speed() const
bool armed() const
AP_Int16 _rsc_idle_output
virtual bool parameter_check(bool display_msg) const
float _pitchFactor[AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS]
void set_throttle_curve(float thrcrv[5], uint16_t slewrate)
float _collectiveFactor[AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS]
uint16_t _loop_rate
these allow remapping of copter motors
Definition: SRV_Channel.h:77
#define f(i)
#define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH
void set_control_mode(RotorControlMode mode)
void output_test(uint8_t motor_seq, int16_t pwm) override
#define AP_MOTORS_HELI_SINGLE_EXT_GYRO_GAIN
AP_Int16 _rsc_critical
float get_control_output() const
#define AP_MOTORS_HELI_SINGLE_SWASH_H3
AP_Int16 _collective_min
int16_t calc_pwm_output_1to1(float input, const SRV_Channel *servo)
void reset_swash_servo(SRV_Channel *servo)
static int state
Definition: Util.cpp:20
void move_yaw(float yaw_out)
AP_Int8 _rsc_mode
#define AP_MOTORS_HELI_SINGLE_SWASH_H1
#define CH_2
Definition: RCOutput.h:12
uint16_t _speed_hz
#define AP_MOTORS_HELI_SINGLE_COLLECTIVE_DIRECTION_NORMAL
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
#define AP_MOTORS_MOT_3
void output(RotorControlState state)
virtual void rc_write(uint8_t chan, uint16_t pwm)
AP_Int16 _cyclic_max
LowPassFilterFloat _throttle_filter
bool parameter_check(bool display_msg) const override
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
void write_aux(float servo_out)
void set_runup_time(int8_t runup_time)
#define AP_NESTEDGROUPINFO(clazz, idx)
Definition: AP_Param.h:105
AP_Int16 _rsc_thrcrv[5]
static constexpr float radians(float deg)
Definition: AP_Math.h:158
static const struct AP_Param::GroupInfo var_info[]
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz)
void calculate_scalars() override
AP_Int16 _land_collective_min
uint16_t get_motor_mask() override
#define AP_MOTORS_HELI_SINGLE_COLYAW_RANGE
void set_update_rate(uint16_t speed_hz) override
#define M_PI
Definition: definitions.h:10
void calculate_armed_scalars() override
virtual uint32_t rc_map_mask(uint32_t mask) const
#define CH_7
Definition: RCOutput.h:17
void set_ramp_time(int8_t ramp_time)
#define AP_MOTORS_HELI_SINGLE_SERVO2_POS
void update_motor_control(RotorControlState state) override
void set_collective(float collective)
Motor control class for traditional heli.
#define AP_GROUPEND
Definition: AP_Param.h:121
#define AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO