APM:Libraries
AP_MotorsHeli_Single.h
Go to the documentation of this file.
1 #pragma once
4 
5 #include <AP_Common/AP_Common.h>
6 #include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
8 #include "AP_MotorsHeli.h"
9 #include "AP_MotorsHeli_RSC.h"
10 
11 // rsc and aux function output channels
12 #define AP_MOTORS_HELI_SINGLE_RSC CH_8
13 #define AP_MOTORS_HELI_SINGLE_AUX CH_7
14 
15 // servo position defaults
16 #define AP_MOTORS_HELI_SINGLE_SERVO1_POS -60
17 #define AP_MOTORS_HELI_SINGLE_SERVO2_POS 60
18 #define AP_MOTORS_HELI_SINGLE_SERVO3_POS 180
19 
20 // swash type definitions
21 #define AP_MOTORS_HELI_SINGLE_SWASH_H3 0
22 #define AP_MOTORS_HELI_SINGLE_SWASH_H1 1
23 #define AP_MOTORS_HELI_SINGLE_SWASH_H3_140 2
24 
25 // collective control direction definitions
26 #define AP_MOTORS_HELI_SINGLE_COLLECTIVE_DIRECTION_NORMAL 0
27 #define AP_MOTORS_HELI_SINGLE_COLLECTIVE_DIRECTION_REVERSED 1
28 
29 // tail types
30 #define AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO 0
31 #define AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO 1
32 #define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH 2
33 #define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH 3
34 
35 // direct-drive variable pitch defaults
36 #define AP_MOTORS_HELI_SINGLE_DDVP_SPEED_DEFAULT 500
37 
38 // default external gyro gain
39 #define AP_MOTORS_HELI_SINGLE_EXT_GYRO_GAIN 350
40 
41 // COLYAW parameter min and max values
42 #define AP_MOTORS_HELI_SINGLE_COLYAW_RANGE 10.0f
43 
44 // maximum number of swashplate servos
45 #define AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS 3
46 
49 public:
50  // constructor
51  AP_MotorsHeli_Single(uint16_t loop_rate,
52  uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) :
53  AP_MotorsHeli(loop_rate, speed_hz),
56  {
58  };
59 
60  // set update rate to motors - a value in hertz
61  void set_update_rate(uint16_t speed_hz) override;
62 
63  // output_test - spin a motor at the pwm value specified
64  // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
65  // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
66  void output_test(uint8_t motor_seq, int16_t pwm) override;
67 
68  // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1
69  void set_desired_rotor_speed(float desired_speed) override;
70 
71  // get_main_rotor_speed - gets estimated or measured main rotor speed
72  float get_main_rotor_speed() const override { return _main_rotor.get_rotor_speed(); }
73 
74  // get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1
75  float get_desired_rotor_speed() const override { return _main_rotor.get_desired_speed(); }
76 
77  // rotor_speed_above_critical - return true if rotor speed is above that critical for flight
79 
80  // calculate_scalars - recalculates various scalars used
81  void calculate_scalars() override;
82 
83  // calculate_armed_scalars - recalculates scalars that can change while armed
84  void calculate_armed_scalars() override;
85 
86  // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
87  // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
88  uint16_t get_motor_mask() override;
89 
90  // ext_gyro_gain - set external gyro gain in range 0 ~ 1
91  void ext_gyro_gain(float gain) override { _ext_gyro_gain_std = gain * 1000.0f; }
92 
93  // has_flybar - returns true if we have a mechical flybar
94  bool has_flybar() const override { return _flybar_mode; }
95 
96  // supports_yaw_passthrought - returns true if we support yaw passthrough
98 
99  void set_acro_tail(bool set) override { _acro_tail = set; }
100 
101  // parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
102  bool parameter_check(bool display_msg) const override;
103 
104  // var_info
105  static const struct AP_Param::GroupInfo var_info[];
106 
107 protected:
108 
109  // init_outputs - initialise Servo/PWM ranges and endpoints
110  bool init_outputs() override;
111 
112  // update_motor_controls - sends commands to motor controllers
114 
115  // calculate_roll_pitch_collective_factors - calculate factors based on swash type and servo position
117 
118  // heli_move_actuators - moves swash plate and tail rotor
119  void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override;
120 
121  // move_yaw - moves the yaw servo
122  void move_yaw(float yaw_out);
123 
124  // write_aux - converts servo_out parameter value (0 to 1 range) to pwm and outputs to aux channel (ch7)
125  void write_aux(float servo_out);
126 
127  // servo_test - move servos through full range of movement
128  void servo_test() override;
129 
130  // external objects we depend upon
133 
134  // internal variables
135  float _oscillate_angle = 0.0f; // cyclic oscillation angle, used by servo_test function
136  float _servo_test_cycle_time = 0.0f; // cycle time tracker, used by servo_test function
137  float _collective_test = 0.0f; // over-ride for collective output, used by servo_test function
138  float _roll_test = 0.0f; // over-ride for roll output, used by servo_test function
139  float _pitch_test = 0.0f; // over-ride for pitch output, used by servo_test function
140  float _yaw_test = 0.0f; // over-ride for yaw output, used by servo_test function
141 
142  // parameters
143  AP_Int16 _servo1_pos; // Angular location of swash servo #1
144  AP_Int16 _servo2_pos; // Angular location of swash servo #2
145  AP_Int16 _servo3_pos; // Angular location of swash servo #3
146  AP_Int8 _collective_direction; // Collective control direction, normal or reversed
147  AP_Int16 _tail_type; // Tail type used: Servo, Servo with external gyro, direct drive variable pitch or direct drive fixed pitch
148  AP_Int8 _swash_type; // Swash Type Setting
149  AP_Int16 _ext_gyro_gain_std; // PWM sent to external gyro on ch7 when tail type is Servo w/ ExtGyro
150  AP_Int16 _ext_gyro_gain_acro; // PWM sent to external gyro on ch7 when tail type is Servo w/ ExtGyro in ACRO
151  AP_Int16 _phase_angle; // Phase angle correction for rotor head. If pitching the swash forward induces a roll, this can be correct the problem
152  AP_Float _collective_yaw_effect; // Feed-forward compensation to automatically add rudder input when collective pitch is increased. Can be positive or negative depending on mechanics.
153  AP_Int8 _flybar_mode; // Flybar present or not. Affects attitude controller used during ACRO flight mode
154  AP_Int16 _direct_drive_tailspeed; // Direct Drive VarPitch Tail ESC speed (0 ~ 1000)
155 
161 
162  bool _acro_tail = false;
166 };
#define AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO
void calculate_roll_pitch_collective_factors() override
#define AP_MOTORS_HELI_SINGLE_AUX
AP_MotorsHeli_RSC _main_rotor
float _rollFactor[AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS]
bool rotor_speed_above_critical() const override
#define AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS
void set_desired_rotor_speed(float desired_speed) override
void ext_gyro_gain(float gain) override
RotorControlState
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
AP_MotorsHeli_RSC _tail_rotor
float get_desired_speed() const
float _pitchFactor[AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS]
float _collectiveFactor[AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS]
AP_MotorsHeli_Single(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_HELI_SPEED_DEFAULT)
void output_test(uint8_t motor_seq, int16_t pwm) override
static int state
Definition: Util.cpp:20
float get_rotor_speed() const
void move_yaw(float yaw_out)
#define AP_MOTORS_HELI_SPEED_DEFAULT
Definition: AP_MotorsHeli.h:15
bool has_flybar() const override
float get_critical_speed() const
bool parameter_check(bool display_msg) const override
Common definitions and utility routines for the ArduPilot libraries.
void write_aux(float servo_out)
bool supports_yaw_passthrough() const override
static const struct AP_Param::GroupInfo var_info[]
void calculate_scalars() override
Motor control class for Traditional Heli.
uint16_t get_motor_mask() override
void set_update_rate(uint16_t speed_hz) override
void calculate_armed_scalars() override
void set_acro_tail(bool set) override
void update_motor_control(RotorControlState state) override
float get_main_rotor_speed() const override
float get_desired_rotor_speed() const override
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214