APM:Libraries
AP_MotorsHeli_Quad.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_Quad.h"
20 
21 extern const AP_HAL::HAL& hal;
22 
25 
26  // Indices 1-3 were used by RSC_PWM_MIN, RSC_PWM_MAX and RSC_PWM_REV and should not be used
27 
29 };
30 
31 // set update rate to motors - a value in hertz
32 void AP_MotorsHeli_Quad::set_update_rate( uint16_t speed_hz )
33 {
34  // record requested speed
35  _speed_hz = speed_hz;
36 
37  // setup fast channels
38  uint32_t mask = 0;
39  for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
40  mask |= 1U << (AP_MOTORS_MOT_1+i);
41  }
42 
43  rc_set_freq(mask, _speed_hz);
44 }
45 
46 // init_outputs
48 {
49  if (_flags.initialised_ok) {
50  return true;
51  }
52 
53  for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
55  if (!_servo[i]) {
56  return false;
57  }
58  }
59 
60  // set rotor servo range
62 
63  _flags.initialised_ok = true;
64 
65  return true;
66 }
67 
68 // output_test - spin a motor at the pwm value specified
69 // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
70 // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
71 void AP_MotorsHeli_Quad::output_test(uint8_t motor_seq, int16_t pwm)
72 {
73  // exit immediately if not armed
74  if (!armed()) {
75  return;
76  }
77 
78  // output to motors and servos
79  switch (motor_seq) {
81  rc_write(AP_MOTORS_MOT_1 + (motor_seq-1), pwm);
82  break;
84  // main rotor
86  break;
87  default:
88  // do nothing
89  break;
90  }
91 }
92 
93 // set_desired_rotor_speed
95 {
96  _rotor.set_desired_speed(desired_speed);
97 }
98 
99 // calculate_armed_scalars
101 {
102  float thrcrv[5];
103  for (uint8_t i = 0; i < 5; i++) {
104  thrcrv[i]=_rsc_thrcrv[i]*0.001f;
105  }
110  _rotor.set_throttle_curve(thrcrv, (uint16_t)_rsc_slewrate.get());
111 }
112 
113 // calculate_scalars
115 {
116  // range check collective min, max and mid
120  }
121 
123 
124  // calculate collective mid point as a number from 0 to 1000
126 
127  // calculate factors based on swash type and servo position
129 
130  // set mode of main rotor controller and trigger recalculation of scalars
131  _rotor.set_control_mode(static_cast<RotorControlMode>(_rsc_mode.get()));
133 }
134 
135 // calculate_swash_factors - calculate factors based on swash type and servo position
137 {
138  // assume X quad layout, with motors at 45, 135, 225 and 315 degrees
139  // order FrontRight, RearLeft, FrontLeft, RearLeft
140  const float angles[AP_MOTORS_HELI_QUAD_NUM_MOTORS] = { 45, 225, 315, 135 };
141  const bool x_clockwise[AP_MOTORS_HELI_QUAD_NUM_MOTORS] = { false, false, true, true };
142  const float cos45 = cosf(radians(45));
143 
144  for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
145  bool clockwise = x_clockwise[i];
147  // reverse yaw for H frame
148  clockwise = !clockwise;
149  }
150  _rollFactor[CH_1+i] = -0.5*sinf(radians(angles[i]))/cos45;
151  _pitchFactor[CH_1+i] = 0.5*cosf(radians(angles[i]))/cos45;
152  _yawFactor[CH_1+i] = clockwise?-0.5:0.5;
153  _collectiveFactor[CH_1+i] = 1;
154  }
155 }
156 
157 // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
158 // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
160 {
161  uint16_t mask = 0;
162  for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
163  mask |= 1U << (AP_MOTORS_MOT_1+i);
164  }
165  mask |= 1U << AP_MOTORS_HELI_QUAD_RSC;
166  return mask;
167 }
168 
169 // update_motor_controls - sends commands to motor controllers
171 {
172  // Send state update to motors
173  _rotor.output(state);
174 
175  if (state == ROTOR_CONTROL_STOP) {
176  // set engine run enable aux output to not run position to kill engine when disarmed
178  } else {
179  // else if armed, set engine run enable output to run position
181  }
182 
183  // Check if rotors are run-up
185 }
186 
187 //
188 // move_actuators - moves swash plate to attitude of parameters passed in
189 // - expected ranges:
190 // roll : -1 ~ +1
191 // pitch: -1 ~ +1
192 // collective: 0 ~ 1
193 // yaw: -1 ~ +1
194 //
195 void AP_MotorsHeli_Quad::move_actuators(float roll_out, float pitch_out, float collective_in, float yaw_out)
196 {
197  // initialize limits flag
198  limit.roll_pitch = false;
199  limit.yaw = false;
200  limit.throttle_lower = false;
201  limit.throttle_upper = false;
202 
203  // constrain collective input
204  float collective_out = collective_in;
205  if (collective_out <= 0.0f) {
206  collective_out = 0.0f;
207  limit.throttle_lower = true;
208  }
209  if (collective_out >= 1.0f) {
210  collective_out = 1.0f;
211  limit.throttle_upper = true;
212  }
213 
214  // ensure not below landed/landing collective
215  if (_heliflags.landing_collective && collective_out < (_land_collective_min*0.001f)) {
216  collective_out = _land_collective_min*0.001f;
217  limit.throttle_lower = true;
218  }
219 
220  float collective_range = (_collective_max - _collective_min)*0.001f;
221 
223  collective_out = 1 - collective_out;
224  }
225 
226  // feed power estimate into main rotor controller
227  _rotor.set_collective(fabsf(collective_out));
228 
229  // scale collective to -1 to 1
230  collective_out = collective_out*2-1;
231 
232  // reserve some collective for attitude control
233  collective_out *= collective_range;
234 
235  float out[AP_MOTORS_HELI_QUAD_NUM_MOTORS] {};
236 
237  for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
238  out[i] =
239  _rollFactor[CH_1+i] * roll_out +
240  _pitchFactor[CH_1+i] * pitch_out +
241  _collectiveFactor[CH_1+i] * collective_out;
242  }
243 
244  // see if we need to scale down yaw_out
245  for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
246  float y = _yawFactor[CH_1+i] * yaw_out;
247  if (out[i] < 0) {
248  // the slope of the yaw effect changes at zero collective
249  y = -y;
250  }
251  if (out[i] * (out[i] + y) < 0) {
252  // applying this yaw demand would change the sign of the
253  // collective, which means the yaw would not be applied
254  // evenly. We scale down the overall yaw demand to prevent
255  // it crossing over zero
256  float s = -(out[i] / y);
257  yaw_out *= s;
258  }
259  }
260 
261  // now apply the yaw correction
262  for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
263  float y = _yawFactor[CH_1+i] * yaw_out;
264  if (out[i] < 0) {
265  // the slope of the yaw effect changes at zero collective
266  y = -y;
267  }
268  out[i] += y;
269  }
270 
271  // move the servos
272  for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
274  }
275 }
276 
277 
278 // servo_test - move servos through full range of movement
280 {
281  // not implemented
282 }
AP_Int8 _rsc_runup_time
static SRV_Channel::Aux_servo_function_t get_motor_function(uint8_t channel)
Definition: SRV_Channel.h:414
uint16_t get_motor_mask() override
static const float angles[]
Definition: eulers.cpp:90
AP_Int16 _collective_max
void output_test(uint8_t motor_seq, int16_t pwm) override
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
motor_frame_type _frame_type
void set_update_rate(uint16_t speed_hz) override
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define AP_MOTORS_HELI_COLLECTIVE_MIN
Definition: AP_MotorsHeli.h:19
engine kill switch, used for gas airplanes and helicopters
Definition: SRV_Channel.h:74
#define CH_1
Definition: RCOutput.h:11
AP_Int16 _collective_mid
float _collective_mid_pct
void set_desired_speed(float desired_speed)
#define AP_MOTORS_MOT_1
struct AP_Motors::AP_Motors_flags _flags
struct AP_Motors::AP_Motors_limit limit
void set_critical_speed(float critical_speed)
AP_Int8 _rsc_ramp_time
static SRV_Channel * get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan=-1)
#define AP_MOTORS_HELI_COLLECTIVE_MAX
Definition: AP_MotorsHeli.h:20
RotorControlState
void update_motor_control(RotorControlState state) override
struct AP_MotorsHeli::heliflags_type _heliflags
static uint16_t pwm
Definition: RCOutput.cpp:20
float _rollFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
void calculate_scalars() override
void set_idle_output(float idle_output)
static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
bool is_runup_complete() const
AP_Int16 _rsc_slewrate
bool armed() const
AP_Int16 _rsc_idle_output
void calculate_roll_pitch_collective_factors() override
void set_throttle_curve(float thrcrv[5], uint16_t slewrate)
#define f(i)
void set_control_mode(RotorControlMode mode)
AP_Int16 _rsc_critical
AP_Int16 _collective_min
int16_t calc_pwm_output_1to1(float input, const SRV_Channel *servo)
float _pitchFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
static int state
Definition: Util.cpp:20
bool init_outputs() override
AP_Int8 _rsc_mode
uint16_t _speed_hz
float _yawFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
void output(RotorControlState state)
virtual void rc_write(uint8_t chan, uint16_t pwm)
void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override
AP_MotorsHeli_RSC _rotor
void set_runup_time(int8_t runup_time)
#define AP_MOTORS_HELI_QUAD_RSC
#define AP_NESTEDGROUPINFO(clazz, idx)
Definition: AP_Param.h:105
AP_Int16 _rsc_thrcrv[5]
static constexpr float radians(float deg)
Definition: AP_Math.h:158
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz)
AP_Int16 _land_collective_min
void set_desired_rotor_speed(float desired_speed) override
void calculate_armed_scalars() override
float _collectiveFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
void set_ramp_time(int8_t ramp_time)
Motor control class collective pitch quad helicopter (such as stingray)
void set_collective(float collective)
void servo_test() override
#define AP_GROUPEND
Definition: AP_Param.h:121
SRV_Channel * _servo[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
#define AP_MOTORS_HELI_QUAD_NUM_MOTORS
static const struct AP_Param::GroupInfo var_info[]