APM:Libraries
AP_MotorsHeli_Dual.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>
18 
19 #include "AP_MotorsHeli_Dual.h"
20 
21 extern const AP_HAL::HAL& hal;
22 
25 
26  // @Param: SV1_POS
27  // @DisplayName: Servo 1 Position
28  // @Description: Angular location of swash servo #1
29  // @Range: -180 180
30  // @Units: deg
31  // @User: Standard
32  // @Increment: 1
34 
35  // @Param: SV2_POS
36  // @DisplayName: Servo 2 Position
37  // @Description: Angular location of swash servo #2
38  // @Range: -180 180
39  // @Units: deg
40  // @User: Standard
41  // @Increment: 1
43 
44  // @Param: SV3_POS
45  // @DisplayName: Servo 3 Position
46  // @Description: Angular location of swash servo #3
47  // @Range: -180 180
48  // @Units: deg
49  // @User: Standard
50  // @Increment: 1
52 
53  // @Param: SV4_POS
54  // @DisplayName: Servo 4 Position
55  // @Description: Angular location of swash servo #4
56  // @Range: -180 180
57  // @Units: deg
58  // @User: Standard
59  // @Increment: 1
61 
62  // @Param: SV5_POS
63  // @DisplayName: Servo 5 Position
64  // @Description: Angular location of swash servo #5
65  // @Range: -180 180
66  // @Units: deg
67  // @User: Standard
68  // @Increment: 1
70 
71  // @Param: SV6_POS
72  // @DisplayName: Servo 6 Position
73  // @Description: Angular location of swash servo #6
74  // @Range: -180 180
75  // @Units: deg
76  // @User: Standard
77  // @Increment: 1
79 
80  // @Param: PHANG1
81  // @DisplayName: Swashplate 1 Phase Angle Compensation
82  // @Description: Phase angle correction for rotor head. If pitching the swash forward induces a roll, this can be correct the problem
83  // @Range: -90 90
84  // @Units: deg
85  // @User: Advanced
86  // @Increment: 1
87  AP_GROUPINFO("PHANG1", 7, AP_MotorsHeli_Dual, _swash1_phase_angle, 0),
88 
89  // @Param: PHANG2
90  // @DisplayName: Swashplate 2 Phase Angle Compensation
91  // @Description: Phase angle correction for rotor head. If pitching the swash forward induces a roll, this can be correct the problem
92  // @Range: -90 90
93  // @Units: deg
94  // @User: Advanced
95  // @Increment: 1
96  AP_GROUPINFO("PHANG2", 8, AP_MotorsHeli_Dual, _swash2_phase_angle, 0),
97 
98  // @Param: DUAL_MODE
99  // @DisplayName: Dual Mode
100  // @Description: Sets the dual mode of the heli, either as tandem or as transverse.
101  // @Values: 0:Longitudinal, 1:Transverse
102  // @User: Standard
104 
105  // @Param: DCP_SCALER
106  // @DisplayName: Differential-Collective-Pitch Scaler
107  // @Description: Scaling factor applied to the differential-collective-pitch
108  // @Range: 0 1
109  // @User: Standard
110  AP_GROUPINFO("DCP_SCALER", 10, AP_MotorsHeli_Dual, _dcp_scaler, AP_MOTORS_HELI_DUAL_DCP_SCALER),
111 
112  // @Param: DCP_YAW
113  // @DisplayName: Differential-Collective-Pitch Yaw Mixing
114  // @Description: Feed-forward compensation to automatically add yaw input when differential collective pitch is applied.
115  // @Range: -10 10
116  // @Increment: 0.1
117  AP_GROUPINFO("DCP_YAW", 11, AP_MotorsHeli_Dual, _dcp_yaw_effect, 0),
118 
119  // @Param: YAW_SCALER
120  // @DisplayName: Scaler for yaw mixing
121  // @Description: Scaler for mixing yaw into roll or pitch.
122  // @Range: -10 10
123  // @Increment: 0.1
124  AP_GROUPINFO("YAW_SCALER", 12, AP_MotorsHeli_Dual, _yaw_scaler, 1.0f),
125 
126  // Indices 13-15 were used by RSC_PWM_MIN, RSC_PWM_MAX and RSC_PWM_REV and should not be used
127 
128  // @Param: COL2_MIN
129  // @DisplayName: Collective Pitch Minimum for rear swashplate
130  // @Description: Lowest possible servo position in PWM microseconds for the rear swashplate
131  // @Range: 1000 2000
132  // @Units: PWM
133  // @Increment: 1
134  // @User: Standard
135  AP_GROUPINFO("COL2_MIN", 16, AP_MotorsHeli_Dual, _collective2_min, AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN),
136 
137  // @Param: COL2_MAX
138  // @DisplayName: Collective Pitch Maximum for rear swashplate
139  // @Description: Highest possible servo position in PWM microseconds for the rear swashplate
140  // @Range: 1000 2000
141  // @Units: PWM
142  // @Increment: 1
143  // @User: Standard
144  AP_GROUPINFO("COL2_MAX", 17, AP_MotorsHeli_Dual, _collective2_max, AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX),
145 
146  // @Param: COL2_MID
147  // @DisplayName: Collective Pitch Mid-Point for rear swashplate
148  // @Description: Swash servo position in PWM microseconds corresponding to zero collective pitch for the rear swashplate (or zero lift for Asymmetrical blades)
149  // @Range: 1000 2000
150  // @Units: PWM
151  // @Increment: 1
152  // @User: Standard
153  AP_GROUPINFO("COL2_MID", 18, AP_MotorsHeli_Dual, _collective2_mid, AP_MOTORS_HELI_DUAL_COLLECTIVE2_MID),
154 
155  // @Param: COL_CTRL_DIR
156  // @DisplayName: Collective Control Direction
157  // @Description: Collective Control Direction - 0 for Normal. 1 for Reversed
158  // @Values: 0: Normal, 1: Reversed
159  // @User: Standard
160  AP_GROUPINFO("COL_CTRL_DIR", 19, AP_MotorsHeli_Dual, _collective_direction, AP_MOTORS_HELI_DUAL_COLLECTIVE_DIRECTION_NORMAL),
161 
163 };
164 
165 // set update rate to motors - a value in hertz
166 void AP_MotorsHeli_Dual::set_update_rate( uint16_t speed_hz )
167 {
168  // record requested speed
169  _speed_hz = speed_hz;
170 
171  // setup fast channels
172  uint32_t mask =
173  1U << AP_MOTORS_MOT_1 |
174  1U << AP_MOTORS_MOT_2 |
175  1U << AP_MOTORS_MOT_3 |
176  1U << AP_MOTORS_MOT_4 |
177  1U << AP_MOTORS_MOT_5 |
178  1U << AP_MOTORS_MOT_6;
179 
180  rc_set_freq(mask, _speed_hz);
181 }
182 
183 // init_outputs
185 {
186  if (!_flags.initialised_ok) {
195  return false;
196  }
197  }
198 
199  // reset swash servo range and endpoints
206 
207  // set rotor servo range
208  _rotor.init_servo();
209 
210  _flags.initialised_ok = true;
211 
212  return true;
213 }
214 
215 // output_test - spin a motor at the pwm value specified
216 // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
217 // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
218 void AP_MotorsHeli_Dual::output_test(uint8_t motor_seq, int16_t pwm)
219 {
220  // exit immediately if not armed
221  if (!armed()) {
222  return;
223  }
224 
225  // output to motors and servos
226  switch (motor_seq) {
227  case 1:
228  // swash servo 1
230  break;
231  case 2:
232  // swash servo 2
234  break;
235  case 3:
236  // swash servo 3
238  break;
239  case 4:
240  // swash servo 4
242  break;
243  case 5:
244  // swash servo 5
246  break;
247  case 6:
248  // swash servo 6
250  break;
251  case 7:
252  // main rotor
254  break;
255  default:
256  // do nothing
257  break;
258  }
259 }
260 
261 // set_desired_rotor_speed
263 {
264  _rotor.set_desired_speed(desired_speed);
265 }
266 
267 // calculate_armed_scalars
269 {
270  float thrcrv[5];
271  for (uint8_t i = 0; i < 5; i++) {
272  thrcrv[i]=_rsc_thrcrv[i]*0.001f;
273  }
278  _rotor.set_throttle_curve(thrcrv, (uint16_t)_rsc_slewrate.get());
279 }
280 
281 // calculate_scalars
283 {
284  // range check collective min, max and mid
288  }
289 
290 
291  // range check collective min, max and mid for rear swashplate
295  }
296 
299 
300  // calculate collective mid point as a number from 0 to 1000
303 
304  // calculate factors based on swash type and servo position
306 
307  // set mode of main rotor controller and trigger recalculation of scalars
308  _rotor.set_control_mode(static_cast<RotorControlMode>(_rsc_mode.get()));
310 }
311 
312 // calculate_swash_factors - calculate factors based on swash type and servo position
313 // To Do: support H3-140 swashplates in Heli Dual?
315 {
317  // roll factors
321 
325 
326  // pitch factors
330 
334 
335  // yaw factors
339 
343  } else { // AP_MOTORS_HELI_DUAL_MODE_TANDEM
344  // roll factors
348 
352 
353  // pitch factors
357 
361 
362  // yaw factors
366 
370  }
371 
372  // collective factors
373  _collectiveFactor[CH_1] = 1;
374  _collectiveFactor[CH_2] = 1;
375  _collectiveFactor[CH_3] = 1;
376 
377  _collectiveFactor[CH_4] = 1;
378  _collectiveFactor[CH_5] = 1;
379  _collectiveFactor[CH_6] = 1;
380 }
381 
382 // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
383 // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
385 {
386  // dual heli uses channels 1,2,3,4,5,6 and 8
387  return (1U << 0 | 1U << 1 | 1U << 2 | 1U << 3 | 1U << 4 | 1U << 5 | 1U << 6 | 1U << AP_MOTORS_HELI_DUAL_RSC);
388 }
389 
390 // update_motor_controls - sends commands to motor controllers
392 {
393  // Send state update to motors
394  _rotor.output(state);
395 
396  if (state == ROTOR_CONTROL_STOP) {
397  // set engine run enable aux output to not run position to kill engine when disarmed
399  } else {
400  // else if armed, set engine run enable output to run position
402  }
403 
404  // Check if rotors are run-up
406 }
407 
408 //
409 // move_actuators - moves swash plate to attitude of parameters passed in
410 // - expected ranges:
411 // roll : -1 ~ +1
412 // pitch: -1 ~ +1
413 // collective: 0 ~ 1
414 // yaw: -1 ~ +1
415 //
416 void AP_MotorsHeli_Dual::move_actuators(float roll_out, float pitch_out, float collective_in, float yaw_out)
417 {
418  // initialize limits flag
419  limit.roll_pitch = false;
420  limit.yaw = false;
421  limit.throttle_lower = false;
422  limit.throttle_upper = false;
423 
425  if (pitch_out < -_cyclic_max/4500.0f) {
426  pitch_out = -_cyclic_max/4500.0f;
427  limit.roll_pitch = true;
428  }
429 
430  if (pitch_out > _cyclic_max/4500.0f) {
431  pitch_out = _cyclic_max/4500.0f;
432  limit.roll_pitch = true;
433  }
434  } else {
435  if (roll_out < -_cyclic_max/4500.0f) {
436  roll_out = -_cyclic_max/4500.0f;
437  limit.roll_pitch = true;
438  }
439 
440  if (roll_out > _cyclic_max/4500.0f) {
441  roll_out = _cyclic_max/4500.0f;
442  limit.roll_pitch = true;
443  }
444  }
445 
447  collective_in = 1 - collective_in;
448  }
449 
450  float yaw_compensation = 0.0f;
451 
452  // if servo output not in manual mode, process pre-compensation factors
454  // add differential collective pitch yaw compensation
456  yaw_compensation = _dcp_yaw_effect * roll_out;
457  } else { // AP_MOTORS_HELI_DUAL_MODE_TANDEM
458  yaw_compensation = _dcp_yaw_effect * pitch_out;
459  }
460  yaw_out = yaw_out + yaw_compensation;
461  }
462 
463  // scale yaw and update limits
464  if (yaw_out < -_cyclic_max/4500.0f) {
465  yaw_out = -_cyclic_max/4500.0f;
466  limit.yaw = true;
467  }
468  if (yaw_out > _cyclic_max/4500.0f) {
469  yaw_out = _cyclic_max/4500.0f;
470  limit.yaw = true;
471  }
472 
473  // constrain collective input
474  float collective_out = collective_in;
475  if (collective_out <= 0.0f) {
476  collective_out = 0.0f;
477  limit.throttle_lower = true;
478  }
479  if (collective_out >= 1.0f) {
480  collective_out = 1.0f;
481  limit.throttle_upper = true;
482  }
483 
484  // Set rear collective to midpoint if required
485  float collective2_out = collective_out;
487  collective2_out = _collective2_mid_pct;
488  }
489 
490 
491  // ensure not below landed/landing collective
492  if (_heliflags.landing_collective && collective_out < (_land_collective_min*0.001f)) {
493  collective_out = _land_collective_min*0.001f;
494  limit.throttle_lower = true;
495  }
496 
497  // scale collective pitch for front swashplate (servos 1,2,3)
498  float collective_scaler = ((float)(_collective_max-_collective_min))*0.001f;
499  float collective_out_scaled = collective_out * collective_scaler + (_collective_min - 1000)*0.001f;
500 
501  // scale collective pitch for rear swashplate (servos 4,5,6)
502  float collective2_scaler = ((float)(_collective2_max-_collective2_min))*0.001f;
503  float collective2_out_scaled = collective2_out * collective2_scaler + (_collective2_min - 1000)*0.001f;
504 
505  // Collective control direction. Swash plates move up for negative collective pitch, down for positive collective pitch
507  collective_out_scaled = 1 - collective_out_scaled;
508  collective2_out_scaled = 1 - collective2_out_scaled;
509  }
510 
511  // feed power estimate into main rotor controller
512  // ToDo: add main rotor cyclic power?
513  _rotor.set_collective(fabsf(collective_out));
514 
515  // swashplate servos
516  float servo1_out = (_rollFactor[CH_1] * roll_out + _pitchFactor[CH_1] * pitch_out + _yawFactor[CH_1] * yaw_out)*0.45f + _collectiveFactor[CH_1] * collective_out_scaled;
517  float servo2_out = (_rollFactor[CH_2] * roll_out + _pitchFactor[CH_2] * pitch_out + _yawFactor[CH_2] * yaw_out)*0.45f + _collectiveFactor[CH_2] * collective_out_scaled;
518  float servo3_out = (_rollFactor[CH_3] * roll_out + _pitchFactor[CH_3] * pitch_out + _yawFactor[CH_3] * yaw_out)*0.45f + _collectiveFactor[CH_3] * collective_out_scaled;
519  float servo4_out = (_rollFactor[CH_4] * roll_out + _pitchFactor[CH_4] * pitch_out + _yawFactor[CH_4] * yaw_out)*0.45f + _collectiveFactor[CH_4] * collective2_out_scaled;
520  float servo5_out = (_rollFactor[CH_5] * roll_out + _pitchFactor[CH_5] * pitch_out + _yawFactor[CH_5] * yaw_out)*0.45f + _collectiveFactor[CH_5] * collective2_out_scaled;
521  float servo6_out = (_rollFactor[CH_6] * roll_out + _pitchFactor[CH_6] * pitch_out + _yawFactor[CH_6] * yaw_out)*0.45f + _collectiveFactor[CH_6] * collective2_out_scaled;
522 
523  // rescale from -1..1, so we can use the pwm calc that includes trim
524  servo1_out = 2*servo1_out - 1;
525  servo2_out = 2*servo2_out - 1;
526  servo3_out = 2*servo3_out - 1;
527  servo4_out = 2*servo4_out - 1;
528  servo5_out = 2*servo5_out - 1;
529  servo6_out = 2*servo6_out - 1;
530 
531  // actually move the servos
538 }
539 
540 
541 // servo_test - move servos through full range of movement
543 {
544  // this test cycle is equivalent to that of AP_MotorsHeli_Single, but excluding
545  // mixing of yaw, as that physical movement is represented by pitch and roll
546 
548 
549  if ((_servo_test_cycle_time >= 0.0f && _servo_test_cycle_time < 0.5f)|| // Tilt swash back
551  _pitch_test += (1.0f / (_loop_rate/2));
553  } else if ((_servo_test_cycle_time >= 0.5f && _servo_test_cycle_time < 4.5f)|| // Roll swash around
554  (_servo_test_cycle_time >= 6.5f && _servo_test_cycle_time < 10.5f)){
555  _oscillate_angle += M_PI / (2 * _loop_rate);
558  } else if ((_servo_test_cycle_time >= 4.5f && _servo_test_cycle_time < 5.0f)|| // Return swash to level
560  _pitch_test -= (1.0f / (_loop_rate/2));
562  } else if (_servo_test_cycle_time >= 5.0f && _servo_test_cycle_time < 6.0f){ // Raise swash to top
563  _collective_test = 1.0f;
565  } else if (_servo_test_cycle_time >= 11.0f && _servo_test_cycle_time < 12.0f){ // Lower swash to bottom
566  _collective_test = 0.0f;
568  } else { // reset cycle
569  _servo_test_cycle_time = 0.0f;
570  _oscillate_angle = 0.0f;
571  _collective_test = 0.0f;
572  _roll_test = 0.0f;
573  _pitch_test = 0.0f;
574  // decrement servo test cycle counter at the end of the cycle
575  if (_servo_test_cycle_counter > 0){
577  }
578  }
579 
580  // over-ride servo commands to move servos through defined ranges
581 
585 }
void reset(T value)
#define CH_3
Definition: RCOutput.h:13
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
AP_Int8 _rsc_runup_time
AP_Int16 _collective_max
#define AP_MOTORS_HELI_DUAL_MODE_TANDEM
float _rollFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
#define AP_MOTORS_HELI_DUAL_RSC
#define AP_MOTORS_HELI_DUAL_DCP_SCALER
#define AP_MOTORS_MOT_4
#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
void calculate_armed_scalars() override
AP_Int16 _collective_mid
float _collective_mid_pct
#define CH_6
Definition: RCOutput.h:16
AP_Int8 _servo_mode
void set_update_rate(uint16_t speed_hz) override
void set_desired_speed(float desired_speed)
SRV_Channel * _swash_servo_4
#define AP_MOTORS_MOT_1
struct AP_Motors::AP_Motors_flags _flags
void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override
#define AP_MOTORS_MOT_2
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
#define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN
struct AP_Motors::AP_Motors_limit limit
void calculate_roll_pitch_collective_factors() override
#define CH_5
Definition: RCOutput.h:15
#define AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE
void set_critical_speed(float critical_speed)
AP_Int8 _rsc_ramp_time
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
int16_t calc_pwm_output_1to1_swash_servo(float input, const SRV_Channel *servo)
void servo_test() override
struct AP_MotorsHeli::heliflags_type _heliflags
static uint16_t pwm
Definition: RCOutput.cpp:20
#define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX
#define AP_MOTORS_HELI_DUAL_SERVO3_POS
#define AP_MOTORS_HELI_DUAL_SERVO1_POS
float _collectiveFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
void set_idle_output(float idle_output)
static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
static const struct AP_Param::GroupInfo var_info[]
bool is_runup_complete() const
#define CH_4
Definition: RCOutput.h:14
AP_Int16 _rsc_slewrate
AP_MotorsHeli_RSC _rotor
uint8_t _servo_test_cycle_counter
SRV_Channel * _swash_servo_1
SRV_Channel * _swash_servo_3
bool armed() const
AP_Int16 _rsc_idle_output
void set_throttle_curve(float thrcrv[5], uint16_t slewrate)
void update_motor_control(RotorControlState state) override
uint16_t _loop_rate
float _pitchFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
these allow remapping of copter motors
Definition: SRV_Channel.h:77
#define f(i)
void set_control_mode(RotorControlMode mode)
AP_Int16 _rsc_critical
AP_Int16 _collective_min
void reset_swash_servo(SRV_Channel *servo)
static int state
Definition: Util.cpp:20
AP_Int8 _rsc_mode
#define CH_2
Definition: RCOutput.h:12
uint16_t _speed_hz
#define AP_MOTORS_MOT_6
#define AP_MOTORS_HELI_DUAL_COLLECTIVE_DIRECTION_REVERSED
#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
Motor control class for dual heli (tandem or transverse)
float _yawFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
#define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MID
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
SRV_Channel * _swash_servo_5
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz)
#define AP_MOTORS_HELI_DUAL_SERVO5_POS
AP_Int16 _land_collective_min
#define AP_MOTORS_MOT_5
void output_test(uint8_t motor_seq, int16_t pwm) override
uint16_t get_motor_mask() override
#define AP_MOTORS_HELI_DUAL_SERVO2_POS
SRV_Channel * _swash_servo_2
bool init_outputs() override
#define M_PI
Definition: definitions.h:10
void set_desired_rotor_speed(float desired_speed) override
void set_ramp_time(int8_t ramp_time)
#define AP_MOTORS_HELI_DUAL_COLLECTIVE_DIRECTION_NORMAL
#define AP_MOTORS_HELI_DUAL_SERVO6_POS
void set_collective(float collective)
#define AP_GROUPEND
Definition: AP_Param.h:121
#define AP_MOTORS_HELI_DUAL_SERVO4_POS
SRV_Channel * _swash_servo_6
void calculate_scalars() override