APM:Libraries
AP_MotorsHeli_RSC.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_RSC.h"
20 
21 extern const AP_HAL::HAL& hal;
22 
23 // init_servo - servo initialization on start-up
25 {
26  // setup RSC on specified channel by default
28 }
29 
30 // set_power_output_range
31 // TODO: Look at possibly calling this at a slower rate. Doesn't need to be called every cycle.
32 void AP_MotorsHeli_RSC::set_throttle_curve(float thrcrv[5], uint16_t slewrate)
33 {
34 
35  // Ensure user inputs are within parameter limits
36  for (uint8_t i = 0; i < 5; i++) {
37  thrcrv[i] = constrain_float(thrcrv[i], 0.0f, 1.0f);
38  }
39  // Calculate the spline polynomials for the throttle curve
40  splinterp5(thrcrv,_thrcrv_poly);
41 
42  _power_slewrate = slewrate;
43 }
44 
45 // output - update value to send to ESC/Servo
47 {
48  float dt;
49  uint64_t now = AP_HAL::micros64();
50  float last_control_output = _control_output;
51 
52  if (_last_update_us == 0) {
53  _last_update_us = now;
54  dt = 0.001f;
55  } else {
56  dt = 1.0e-6f * (now - _last_update_us);
57  _last_update_us = now;
58  }
59 
60  switch (state){
61  case ROTOR_CONTROL_STOP:
62  // set rotor ramp to decrease speed to zero, this happens instantly inside update_rotor_ramp()
63  update_rotor_ramp(0.0f, dt);
64 
65  // control output forced to zero
66  _control_output = 0.0f;
67  break;
68 
69  case ROTOR_CONTROL_IDLE:
70  // set rotor ramp to decrease speed to zero
71  update_rotor_ramp(0.0f, dt);
72 
73  // set rotor control speed to idle speed parameter, this happens instantly and ignore ramping
75  break;
76 
78  // set main rotor ramp to increase to full speed
79  update_rotor_ramp(1.0f, dt);
80 
82  // set control rotor speed to ramp slewed value between idle and desired speed
85  // throttle output from throttle curve based on collective position
86  float desired_throttle = calculate_desired_throttle(_collective_in);
87  _control_output = _idle_output + (_rotor_ramp_output * (desired_throttle - _idle_output));
88  }
89  break;
90  }
91 
92  // update rotor speed run-up estimate
94 
95  if (_power_slewrate > 0) {
96  // implement slew rate for throttle
97  float max_delta = dt * _power_slewrate * 0.01f;
98  _control_output = constrain_float(_control_output, last_control_output-max_delta, last_control_output+max_delta);
99  }
100 
101  // output to rsc servo
103 }
104 
105 // update_rotor_ramp - slews rotor output scalar between 0 and 1, outputs float scalar to _rotor_ramp_output
106 void AP_MotorsHeli_RSC::update_rotor_ramp(float rotor_ramp_input, float dt)
107 {
108  // sanity check ramp time
109  if (_ramp_time <= 0) {
110  _ramp_time = 1;
111  }
112 
113  // ramp output upwards towards target
114  if (_rotor_ramp_output < rotor_ramp_input) {
115  // allow control output to jump to estimated speed
118  }
119  // ramp up slowly to target
120  _rotor_ramp_output += (dt / _ramp_time);
121  if (_rotor_ramp_output > rotor_ramp_input) {
122  _rotor_ramp_output = rotor_ramp_input;
123  }
124  }else{
125  // ramping down happens instantly
126  _rotor_ramp_output = rotor_ramp_input;
127  }
128 }
129 
130 // update_rotor_runup - function to slew rotor runup scalar, outputs float scalar to _rotor_runup_ouptut
132 {
133  // sanity check runup time
134  if (_runup_time < _ramp_time) {
136  }
137  if (_runup_time <= 0 ) {
138  _runup_time = 1;
139  }
140 
141  // ramp speed estimate towards control out
142  float runup_increment = dt / _runup_time;
144  _rotor_runup_output += runup_increment;
147  }
148  }else{
149  _rotor_runup_output -= runup_increment;
152  }
153  }
154 
155  // update run-up complete flag
156 
157  // if control mode is disabled, then run-up complete always returns true
159  _runup_complete = true;
160  return;
161  }
162 
163  // if rotor ramp and runup are both at full speed, then run-up has been completed
164  if (!_runup_complete && (_rotor_ramp_output >= 1.0f) && (_rotor_runup_output >= 1.0f)) {
165  _runup_complete = true;
166  }
167  // if rotor speed is less than critical speed, then run-up is not complete
168  // this will prevent the case where the target rotor speed is less than critical speed
170  _runup_complete = false;
171  }
172 }
173 
174 // get_rotor_speed - gets rotor speed either as an estimate, or (ToDO) a measured value
176 {
177  // if no actual measured rotor speed is available, estimate speed based on rotor runup scalar.
178  return _rotor_runup_output;
179 }
180 
181 // write_rsc - outputs pwm onto output rsc channel
182 // servo_out parameter is of the range 0 ~ 1
183 void AP_MotorsHeli_RSC::write_rsc(float servo_out)
184 {
186  // do not do servo output to avoid conflicting with other output on the channel
187  // ToDo: We should probably use RC_Channel_Aux to avoid this problem
188  return;
189  } else {
190  SRV_Channels::set_output_scaled(_aux_fn, (uint16_t) (servo_out * 1000));
191  }
192 }
193 
194  // calculate_desired_throttle - uses throttle curve and collective input to determine throttle setting
196 {
197 
198  const float inpt = collective_in * 4.0f + 1.0f;
199  uint8_t idx = constrain_int16(int8_t(collective_in * 4), 0, 3);
200  const float a = inpt - (idx + 1.0f);
201  const float b = (idx + 1.0f) - inpt + 1.0f;
202  float throttle = _thrcrv_poly[idx][0] * a + _thrcrv_poly[idx][1] * b + _thrcrv_poly[idx][2] * (powf(a,3.0f) - a) / 6.0f + _thrcrv_poly[idx][3] * (powf(b,3.0f) - b) / 6.0f;
203 
204  throttle = constrain_float(throttle, 0.0f, 1.0f);
205  return throttle;
206 
207 }
208 
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
RotorControlMode _control_mode
static bool set_aux_channel_default(SRV_Channel::Aux_servo_function_t function, uint8_t channel)
void update_rotor_runup(float dt)
float _thrcrv_poly[4][4]
RotorControlState
float calculate_desired_throttle(float collective_in)
SRV_Channel::Aux_servo_function_t _aux_fn
void update_rotor_ramp(float rotor_ramp_input, float dt)
static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value)
void set_throttle_curve(float thrcrv[5], uint16_t slewrate)
#define f(i)
uint64_t micros64()
Definition: system.cpp:162
void splinterp5(const float x[5], float out[4][4])
Definition: spline5.cpp:27
static int state
Definition: Util.cpp:20
float get_rotor_speed() const
void output(RotorControlState state)
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
void write_rsc(float servo_out)