APM:Libraries
AP_MotorsHeli_Dual.h
Go to the documentation of this file.
1 
5 #ifndef __AP_MOTORS_HELI_DUAL_H__
6 #define __AP_MOTORS_HELI_DUAL_H__
7 
8 #include <AP_Common/AP_Common.h>
9 #include <AP_Math/AP_Math.h>
10 #include <RC_Channel/RC_Channel.h>
11 
12 #include "AP_MotorsHeli.h"
13 #include "AP_MotorsHeli_RSC.h"
14 
15 // servo position defaults
16 #define AP_MOTORS_HELI_DUAL_SERVO1_POS -60
17 #define AP_MOTORS_HELI_DUAL_SERVO2_POS 60
18 #define AP_MOTORS_HELI_DUAL_SERVO3_POS 180
19 #define AP_MOTORS_HELI_DUAL_SERVO4_POS -60
20 #define AP_MOTORS_HELI_DUAL_SERVO5_POS 60
21 #define AP_MOTORS_HELI_DUAL_SERVO6_POS 180
22 
23 // collective control direction definitions
24 #define AP_MOTORS_HELI_DUAL_COLLECTIVE_DIRECTION_NORMAL 0
25 #define AP_MOTORS_HELI_DUAL_COLLECTIVE_DIRECTION_REVERSED 1
26 
27 // rsc function output channel
28 #define AP_MOTORS_HELI_DUAL_RSC CH_8
29 
30 // tandem modes
31 #define AP_MOTORS_HELI_DUAL_MODE_TANDEM 0 // tandem mode (rotors front and aft)
32 #define AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE 1 // transverse mode (rotors side by side)
33 
34 // default differential-collective-pitch scaler
35 #define AP_MOTORS_HELI_DUAL_DCP_SCALER 0.25f
36 
37 // maximum number of swashplate servos
38 #define AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS 6
39 
40 // default collective min, max and midpoints for the rear swashplate
41 #define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN 1250
42 #define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX 1750
43 #define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MID 1500
44 
47 public:
48  // constructor
49  AP_MotorsHeli_Dual(uint16_t loop_rate,
50  uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) :
51  AP_MotorsHeli(loop_rate, speed_hz),
53  {
55  };
56 
57 
58  // set_update_rate - set update rate to motors
59  void set_update_rate( uint16_t speed_hz ) override;
60 
61  // output_test - spin a motor at the pwm value specified
62  void output_test(uint8_t motor_seq, int16_t pwm) override;
63 
64  // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000
65  void set_desired_rotor_speed(float desired_speed) override;
66 
67  // get_estimated_rotor_speed - gets estimated rotor speed as a number from 0 ~ 1000
68  float get_main_rotor_speed() const override { return _rotor.get_rotor_speed(); }
69 
70  // get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1000
71  float get_desired_rotor_speed() const override { return _rotor.get_rotor_speed(); }
72 
73  // rotor_speed_above_critical - return true if rotor speed is above that critical for flight
75 
76  // calculate_scalars - recalculates various scalars used
77  void calculate_scalars() override;
78 
79  // calculate_armed_scalars - recalculates scalars that can change while armed
80  void calculate_armed_scalars() override;
81 
82  // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
83  uint16_t get_motor_mask() override;
84 
85  // has_flybar - returns true if we have a mechical flybar
86  bool has_flybar() const override { return AP_MOTORS_HELI_NOFLYBAR; }
87 
88  // supports_yaw_passthrought - returns true if we support yaw passthrough
89  bool supports_yaw_passthrough() const override { return false; }
90 
91  // servo_test - move servos through full range of movement
92  void servo_test() override;
93 
94  // var_info for holding Parameter information
95  static const struct AP_Param::GroupInfo var_info[];
96 
97 protected:
98 
99  // init_outputs
100  bool init_outputs () override;
101 
102  // update_motor_controls - sends commands to motor controllers
104 
105  // calculate_roll_pitch_collective_factors - calculate factors based on swash type and servo position
107 
108  // move_actuators - moves swash plate to attitude of parameters passed in
109  void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override;
110 
111  // objects we depend upon
112  AP_MotorsHeli_RSC _rotor; // main rotor controller
113 
114  // internal variables
115  float _oscillate_angle = 0.0f; // cyclic oscillation angle, used by servo_test function
116  float _servo_test_cycle_time = 0.0f; // cycle time tracker, used by servo_test function
117  float _collective_test = 0.0f; // over-ride for collective output, used by servo_test function
118  float _roll_test = 0.0f; // over-ride for roll output, used by servo_test function
119  float _pitch_test = 0.0f; // over-ride for pitch output, used by servo_test function
120 
121  // parameters
122  AP_Int16 _collective2_min; // Lowest possible servo position for the rear swashplate
123  AP_Int16 _collective2_max; // Highest possible servo position for the rear swashplate
124  AP_Int16 _collective2_mid; // Swash servo position corresponding to zero collective pitch for the rear swashplate (or zero lift for Asymmetrical blades)
125  AP_Int16 _servo1_pos; // angular location of swash servo #1
126  AP_Int16 _servo2_pos; // angular location of swash servo #2
127  AP_Int16 _servo3_pos; // angular location of swash servo #3
128  AP_Int16 _servo4_pos; // angular location of swash servo #4
129  AP_Int16 _servo5_pos; // angular location of swash servo #5
130  AP_Int16 _servo6_pos; // angular location of swash servo #6
131  AP_Int8 _collective_direction; // Collective control direction, normal or reversed
132  AP_Int16 _swash1_phase_angle; // phase angle correction for 1st swash.
133  AP_Int16 _swash2_phase_angle; // phase angle correction for 2nd swash.
134  AP_Int8 _dual_mode; // which dual mode the heli is
135  AP_Float _dcp_scaler; // scaling factor applied to the differential-collective-pitch
136  AP_Float _dcp_yaw_effect; // feed-forward compensation to automatically add yaw input when differential collective pitch is applied.
137  AP_Float _yaw_scaler; // scaling factor applied to the yaw mixing
138 
145 
146  // internal variables
147  float _collective2_mid_pct = 0.0f; // collective mid parameter value for rear swashplate converted to 0 ~ 1 range
152 };
153 
154 #endif // AP_MotorsHeli_Dual
#define AP_MOTORS_HELI_NOFLYBAR
Definition: AP_MotorsHeli.h:45
float _rollFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
float get_main_rotor_speed() const override
#define AP_MOTORS_HELI_DUAL_RSC
void calculate_armed_scalars() override
void set_update_rate(uint16_t speed_hz) override
SRV_Channel * _swash_servo_4
void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override
void calculate_roll_pitch_collective_factors() override
bool rotor_speed_above_critical() const override
RotorControlState
void servo_test() override
static uint16_t pwm
Definition: RCOutput.cpp:20
bool has_flybar() const override
float _collectiveFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
static const struct AP_Param::GroupInfo var_info[]
AP_MotorsHeli_RSC _rotor
SRV_Channel * _swash_servo_1
SRV_Channel * _swash_servo_3
void update_motor_control(RotorControlState state) override
RC_Channel manager, with EEPROM-backed storage of constants.
float _pitchFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
static int state
Definition: Util.cpp:20
float get_rotor_speed() const
AP_MotorsHeli_Dual(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_HELI_SPEED_DEFAULT)
#define AP_MOTORS_HELI_SPEED_DEFAULT
Definition: AP_MotorsHeli.h:15
bool supports_yaw_passthrough() const override
float get_critical_speed() const
Common definitions and utility routines for the ArduPilot libraries.
float _yawFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
SRV_Channel * _swash_servo_5
#define AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS
Motor control class for Traditional Heli.
void output_test(uint8_t motor_seq, int16_t pwm) override
uint16_t get_motor_mask() override
SRV_Channel * _swash_servo_2
bool init_outputs() override
void set_desired_rotor_speed(float desired_speed) override
float get_desired_rotor_speed() const override
SRV_Channel * _swash_servo_6
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
void calculate_scalars() override