APM:Libraries
AP_MotorsHeli_RSC.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Common/AP_Common.h>
4 #include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
7 
8 // rotor controller states
13 };
14 
15 // rotor control modes
22 };
23 
25 public:
26  friend class AP_MotorsHeli_Single;
27  friend class AP_MotorsHeli_Dual;
28  friend class AP_MotorsHeli_Quad;
29 
31  uint8_t default_channel) :
32  _aux_fn(aux_fn),
33  _default_channel(default_channel)
34  {};
35 
36  // init_servo - servo initialization on start-up
37  void init_servo();
38 
39  // set_control_mode - sets control mode
41 
42  // set_critical_speed
43  void set_critical_speed(float critical_speed) { _critical_speed = critical_speed; }
44 
45  // get_critical_speed
46  float get_critical_speed() const { return _critical_speed; }
47 
48  // set_idle_output
49  float get_idle_output() { return _idle_output; }
50  void set_idle_output(float idle_output) { _idle_output = idle_output; }
51 
52  // get_desired_speed
53  float get_desired_speed() const { return _desired_speed; }
54 
55  // set_desired_speed
56  void set_desired_speed(float desired_speed) { _desired_speed = desired_speed; }
57 
58  // get_control_speed
59  float get_control_output() const { return _control_output; }
60 
61  // get_rotor_speed - return estimated or measured rotor speed
62  float get_rotor_speed() const;
63 
64  // is_runup_complete
65  bool is_runup_complete() const { return _runup_complete; }
66 
67  // set_ramp_time
68  void set_ramp_time(int8_t ramp_time) { _ramp_time = ramp_time; }
69 
70  // set_runup_time
71  void set_runup_time(int8_t runup_time) { _runup_time = runup_time; }
72 
73  // set_throttle_curve
74  void set_throttle_curve(float thrcrv[5], uint16_t slewrate);
75 
76  // set_collective. collective for throttle curve calculation
77  void set_collective(float collective) { _collective_in = collective; }
78 
79  // output - update value to send to ESC/Servo
81 
82 private:
83  uint64_t _last_update_us;
84 
85  // channel setup for aux function
88 
89  // internal variables
90  RotorControlMode _control_mode = ROTOR_CONTROL_MODE_DISABLED; // motor control mode, Passthrough or Setpoint
91  float _critical_speed = 0.0f; // rotor speed below which flight is not possible
92  float _idle_output = 0.0f; // motor output idle speed
93  float _desired_speed = 0.0f; // latest desired rotor speed from pilot
94  float _control_output = 0.0f; // latest logic controlled output
95  float _rotor_ramp_output = 0.0f; // scalar used to ramp rotor speed between _rsc_idle_output and full speed (0.0-1.0f)
96  float _rotor_runup_output = 0.0f; // scalar used to store status of rotor run-up time (0.0-1.0f)
97  int8_t _ramp_time = 0; // time in seconds for the output to the main rotor's ESC to reach full speed
98  int8_t _runup_time = 0; // time in seconds for the main rotor to reach full speed. Must be longer than _rsc_ramp_time
99  bool _runup_complete = false; // flag for determining if runup is complete
100  float _thrcrv_poly[4][4]; // spline polynomials for throttle curve interpolation
101  uint16_t _power_slewrate = 0; // slewrate for throttle (percentage per second)
102  float _collective_in; // collective in for throttle curve calculation, range 0-1.0f
103 
104  // update_rotor_ramp - slews rotor output scalar between 0 and 1, outputs float scalar to _rotor_ramp_output
105  void update_rotor_ramp(float rotor_ramp_input, float dt);
106 
107  // update_rotor_runup - function to slew rotor runup scalar, outputs float scalar to _rotor_runup_ouptut
108  void update_rotor_runup(float dt);
109 
110  // write_rsc - outputs pwm onto output rsc channel. servo_out parameter is of the range 0 ~ 1
111  void write_rsc(float servo_out);
112 
113  // calculate_desired_throttle - uses throttle curve and collective input to determine throttle setting
114  float calculate_desired_throttle(float collective_in);
115 };
RotorControlMode _control_mode
void set_desired_speed(float desired_speed)
void update_rotor_runup(float dt)
void set_critical_speed(float critical_speed)
float _thrcrv_poly[4][4]
RotorControlState
float calculate_desired_throttle(float collective_in)
void set_idle_output(float idle_output)
bool is_runup_complete() const
AP_MotorsHeli_RSC(SRV_Channel::Aux_servo_function_t aux_fn, uint8_t default_channel)
float get_desired_speed() const
SRV_Channel::Aux_servo_function_t _aux_fn
void update_rotor_ramp(float rotor_ramp_input, float dt)
void set_throttle_curve(float thrcrv[5], uint16_t slewrate)
RC_Channel manager, with EEPROM-backed storage of constants.
void set_control_mode(RotorControlMode mode)
float get_control_output() const
static int state
Definition: Util.cpp:20
float get_rotor_speed() const
void output(RotorControlState state)
float get_critical_speed() const
Common definitions and utility routines for the ArduPilot libraries.
void set_runup_time(int8_t runup_time)
void write_rsc(float servo_out)
RotorControlMode
void set_ramp_time(int8_t ramp_time)
void set_collective(float collective)