APM:Libraries
AP_MotorsHeli.h
Go to the documentation of this file.
1 #pragma once
4 
5 #include <inttypes.h>
6 
7 #include <AP_Common/AP_Common.h>
8 #include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
11 #include "AP_Motors_Class.h"
12 #include "AP_MotorsHeli_RSC.h"
13 
14 // servo output rates
15 #define AP_MOTORS_HELI_SPEED_DEFAULT 125 // default servo update rate for helicopters
16 
17 // default swash min and max angles and positions
18 #define AP_MOTORS_HELI_SWASH_CYCLIC_MAX 2500
19 #define AP_MOTORS_HELI_COLLECTIVE_MIN 1250
20 #define AP_MOTORS_HELI_COLLECTIVE_MAX 1750
21 #define AP_MOTORS_HELI_COLLECTIVE_MID 1500
22 
23 // swash min while landed or landing (as a number from 0 ~ 1000
24 #define AP_MOTORS_HELI_LAND_COLLECTIVE_MIN 0
25 
26 // default main rotor speed (ch8 out) as a number from 0 ~ 1000
27 #define AP_MOTORS_HELI_RSC_SETPOINT 700
28 
29 // default main rotor critical speed
30 #define AP_MOTORS_HELI_RSC_CRITICAL 500
31 
32 // RSC output defaults
33 #define AP_MOTORS_HELI_RSC_IDLE_DEFAULT 0
34 #define AP_MOTORS_HELI_RSC_THRCRV_0_DEFAULT 250
35 #define AP_MOTORS_HELI_RSC_THRCRV_25_DEFAULT 320
36 #define AP_MOTORS_HELI_RSC_THRCRV_50_DEFAULT 380
37 #define AP_MOTORS_HELI_RSC_THRCRV_75_DEFAULT 500
38 #define AP_MOTORS_HELI_RSC_THRCRV_100_DEFAULT 1000
39 
40 // default main rotor ramp up time in seconds
41 #define AP_MOTORS_HELI_RSC_RAMP_TIME 1 // 1 second to ramp output to main rotor ESC to setpoint
42 #define AP_MOTORS_HELI_RSC_RUNUP_TIME 10 // 10 seconds for rotor to reach full speed
43 
44 // flybar types
45 #define AP_MOTORS_HELI_NOFLYBAR 0
46 
47 class AP_HeliControls;
48 
50 class AP_MotorsHeli : public AP_Motors {
51 public:
52 
54  AP_MotorsHeli( uint16_t loop_rate,
55  uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) :
56  AP_Motors(loop_rate, speed_hz)
57  {
59 
60  // initialise flags
63  };
64 
65  // init
66  void init(motor_frame_class frame_class, motor_frame_type frame_type);
67 
68  // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
69  void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type);
70 
71  // set update rate to motors - a value in hertz
72  virtual void set_update_rate( uint16_t speed_hz ) = 0;
73 
74  // output_min - sets servos to neutral point with motors stopped
75  void output_min();
76 
77  // output_test - spin a motor at the pwm value specified
78  // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
79  // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
80  virtual void output_test(uint8_t motor_seq, int16_t pwm) = 0;
81 
82  //
83  // heli specific methods
84  //
85 
86  // parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
87  virtual bool parameter_check(bool display_msg) const;
88 
89  // has_flybar - returns true if we have a mechical flybar
90  virtual bool has_flybar() const { return AP_MOTORS_HELI_NOFLYBAR; }
91 
92  // set_collective_for_landing - limits collective from going too low if we know we are landed
93  void set_collective_for_landing(bool landing) { _heliflags.landing_collective = landing; }
94 
95  // set_inverted_flight - enables/disables inverted flight
96  void set_inverted_flight(bool inverted) { _heliflags.inverted_flight = inverted; }
97 
98  // get_rsc_mode - gets the rotor speed control method (AP_MOTORS_HELI_RSC_MODE_CH8_PASSTHROUGH or AP_MOTORS_HELI_RSC_MODE_SETPOINT)
99  uint8_t get_rsc_mode() const { return _rsc_mode; }
100 
101  // get_rsc_setpoint - gets contents of _rsc_setpoint parameter (0~1)
102  float get_rsc_setpoint() const { return _rsc_setpoint / 1000.0f; }
103 
104  // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1
105  virtual void set_desired_rotor_speed(float desired_speed) = 0;
106 
107  // get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1
108  virtual float get_desired_rotor_speed() const = 0;
109 
110  // get_main_rotor_speed - gets estimated or measured main rotor speed
111  virtual float get_main_rotor_speed() const = 0;
112 
113  // return true if the main rotor is up to speed
115 
116  // rotor_speed_above_critical - return true if rotor speed is above that critical for flight
117  virtual bool rotor_speed_above_critical() const = 0;
118 
119  // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
120  // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
121  virtual uint16_t get_motor_mask() = 0;
122 
123  virtual void set_acro_tail(bool set) {}
124 
125  // ext_gyro_gain - set external gyro gain in range 0 ~ 1
126  virtual void ext_gyro_gain(float gain) {}
127 
128  // output - sends commands to the motors
129  void output();
130 
131  // supports_yaw_passthrough
132  virtual bool supports_yaw_passthrough() const { return false; }
133 
134  float get_throttle_hover() const { return 0.5f; }
135 
136  // var_info for holding Parameter information
137  static const struct AP_Param::GroupInfo var_info[];
138 
139 protected:
140 
141  // manual servo modes (used for setup)
149  };
150 
151  // output - sends commands to the motors
154  void output_disarmed();
155 
156  // update_motor_controls - sends commands to motor controllers
157  virtual void update_motor_control(RotorControlState state) = 0;
158 
159  // reset_flight_controls - resets all controls and scalars to flight status
160  void reset_flight_controls();
161 
162  // update the throttle input filter
163  void update_throttle_filter();
164 
165  // move_actuators - moves swash plate and tail rotor
166  virtual void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) = 0;
167 
168  // reset_swash_servo - free up swash servo for maximum movement
169  void reset_swash_servo(SRV_Channel *servo);
170 
171  // init_outputs - initialise Servo/PWM ranges and endpoints
172  virtual bool init_outputs() = 0;
173 
174  // calculate_armed_scalars - must be implemented by child classes
175  virtual void calculate_armed_scalars() = 0;
176 
177  // calculate_scalars - must be implemented by child classes
178  virtual void calculate_scalars() = 0;
179 
180  // calculate_roll_pitch_collective_factors - calculate factors based on swash type and servo position
181  virtual void calculate_roll_pitch_collective_factors() = 0;
182 
183  // servo_test - move servos through full range of movement
184  // to be overloaded by child classes, different vehicle types would have different movement patterns
185  virtual void servo_test() = 0;
186 
187  // convert input in -1 to +1 range to pwm output for swashplate servos. . Special handling of trim is required
188  // to keep travel between the swashplate servos consistent.
189  int16_t calc_pwm_output_1to1_swash_servo(float input, const SRV_Channel *servo);
190 
191  // flags bitmask
192  struct heliflags_type {
193  uint8_t landing_collective : 1; // true if collective is setup for landing which has much higher minimum
194  uint8_t rotor_runup_complete : 1; // true if the rotors have had enough time to wind up
195  uint8_t inverted_flight : 1; // true for inverted flight
196  } _heliflags;
197 
198  // parameters
199  AP_Int16 _cyclic_max; // Maximum cyclic angle of the swash plate in centi-degrees
200  AP_Int16 _collective_min; // Lowest possible servo position for the swashplate
201  AP_Int16 _collective_max; // Highest possible servo position for the swashplate
202  AP_Int16 _collective_mid; // Swash servo position corresponding to zero collective pitch (or zero lift for Asymmetrical blades)
203  AP_Int8 _servo_mode; // Pass radio inputs directly to servos during set-up through mission planner
204  AP_Int16 _rsc_setpoint; // rotor speed when RSC mode is set to is enabledv
205  AP_Int8 _rsc_mode; // Which main rotor ESC control mode is active
206  AP_Int8 _rsc_ramp_time; // Time in seconds for the output to the main rotor's ESC to reach setpoint
207  AP_Int8 _rsc_runup_time; // Time in seconds for the main rotor to reach full speed. Must be longer than _rsc_ramp_time
208  AP_Int16 _land_collective_min; // Minimum collective when landed or landing
209  AP_Int16 _rsc_critical; // Rotor speed below which flight is not possible
210  AP_Int16 _rsc_idle_output; // Rotor control output while at idle
211  AP_Int16 _rsc_thrcrv[5]; // throttle value sent to throttle servo at 0, 25, 50, 75 and 100 percent collective
212  AP_Int16 _rsc_slewrate; // throttle slew rate (percentage per second)
213  AP_Int8 _servo_test; // sets number of cycles to test servo movement on bootup
214 
215  // internal variables
216  float _collective_mid_pct = 0.0f; // collective mid parameter value converted to 0 ~ 1 range
217  uint8_t _servo_test_cycle_counter = 0; // number of test cycles left to run after bootup
218 
220 };
virtual void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out)=0
AP_Int8 _servo_test
#define AP_MOTORS_HELI_NOFLYBAR
Definition: AP_MotorsHeli.h:45
AP_Int8 _rsc_runup_time
AP_Int16 _collective_max
virtual float get_main_rotor_speed() const =0
float get_throttle_hover() const
float get_rsc_setpoint() const
virtual void calculate_roll_pitch_collective_factors()=0
virtual bool supports_yaw_passthrough() const
motor_frame_type _frame_type
AP_Int16 _collective_mid
float _collective_mid_pct
AP_Int8 _servo_mode
AP_Int8 _rsc_ramp_time
RotorControlState
void set_inverted_flight(bool inverted)
Definition: AP_MotorsHeli.h:96
int16_t calc_pwm_output_1to1_swash_servo(float input, const SRV_Channel *servo)
virtual void calculate_scalars()=0
struct AP_MotorsHeli::heliflags_type _heliflags
static uint16_t pwm
Definition: RCOutput.cpp:20
virtual void servo_test()=0
AP_Int16 _rsc_slewrate
virtual uint16_t get_motor_mask()=0
uint8_t _servo_test_cycle_counter
AP_Int16 _rsc_setpoint
virtual float get_desired_rotor_speed() const =0
virtual void set_desired_rotor_speed(float desired_speed)=0
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
AP_MotorsHeli(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_HELI_SPEED_DEFAULT)
Constructor.
Definition: AP_MotorsHeli.h:54
void reset_flight_controls()
RC_Channel manager, with EEPROM-backed storage of constants.
virtual bool rotor_speed_above_critical() const =0
bool rotor_runup_complete() const
virtual void calculate_armed_scalars()=0
AP_Int16 _rsc_critical
void output_disarmed()
void set_collective_for_landing(bool landing)
Definition: AP_MotorsHeli.h:93
AP_Int16 _collective_min
void reset_swash_servo(SRV_Channel *servo)
static int state
Definition: Util.cpp:20
AP_Int8 _rsc_mode
virtual void update_motor_control(RotorControlState state)=0
#define AP_MOTORS_HELI_SPEED_DEFAULT
Definition: AP_MotorsHeli.h:15
virtual void ext_gyro_gain(float gain)
uint8_t get_rsc_mode() const
Definition: AP_MotorsHeli.h:99
void output_armed_zero_throttle()
AP_Int16 _cyclic_max
Common definitions and utility routines for the ArduPilot libraries.
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
static const struct AP_Param::GroupInfo var_info[]
AP_Int16 _rsc_thrcrv[5]
void update_throttle_filter()
AP_Int16 _land_collective_min
virtual void set_acro_tail(bool set)
virtual void output_test(uint8_t motor_seq, int16_t pwm)=0
virtual bool has_flybar() const
Definition: AP_MotorsHeli.h:90
virtual bool init_outputs()=0
void output_armed_stabilizing()
virtual void set_update_rate(uint16_t speed_hz)=0
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214