APM:Libraries
AP_MotorsSingle.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 /*
17  * AP_MotorsSingle.cpp - ArduCopter motors library
18  * Code by RandyMackay. DIYDrones.com
19  *
20  */
21 
22 #include <AP_HAL/AP_HAL.h>
23 #include <AP_Math/AP_Math.h>
24 #include "AP_MotorsSingle.h"
25 #include <GCS_MAVLink/GCS.h>
26 
27 extern const AP_HAL::HAL& hal;
28 
29 
30 // init
32 {
33  // make sure 6 output channels are mapped
34  for (uint8_t i=0; i<6; i++) {
36  }
37 
38  // set the motor_enabled flag so that the main ESC can be calibrated like other frame types
41 
42  // setup actuator scaling
43  for (uint8_t i=0; i<NUM_ACTUATORS; i++) {
45  }
46 
47  // record successful initialisation if what we setup was the desired frame_class
48  _flags.initialised_ok = (frame_class == MOTOR_FRAME_SINGLE);
49 }
50 
51 // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
53 {
54  // nothing to do
55 }
56 
57 // set update rate to motors - a value in hertz
58 void AP_MotorsSingle::set_update_rate( uint16_t speed_hz )
59 {
60  // record requested speed
61  _speed_hz = speed_hz;
62 
63  uint32_t mask =
64  1U << AP_MOTORS_MOT_5 |
65  1U << AP_MOTORS_MOT_6 ;
66  rc_set_freq(mask, _speed_hz);
67 }
68 
70 {
71  if (!_flags.initialised_ok) {
72  return;
73  }
74  switch (_spool_mode) {
75  case SHUT_DOWN:
76  // sends minimum values out to the motors
78  rc_write_angle(AP_MOTORS_MOT_2, _pitch_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
79  rc_write_angle(AP_MOTORS_MOT_3, -_roll_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
80  rc_write_angle(AP_MOTORS_MOT_4, -_pitch_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
83  break;
84  case SPIN_WHEN_ARMED:
85  // sends output to motors when armed but not flying
86  for (uint8_t i=0; i<NUM_ACTUATORS; i++) {
87  rc_write_angle(AP_MOTORS_MOT_1+i, _spin_up_ratio * _actuator_out[i] * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
88  }
91  break;
92  case SPOOL_UP:
93  case THROTTLE_UNLIMITED:
94  case SPOOL_DOWN:
95  // set motor output based on thrust requests
96  for (uint8_t i=0; i<NUM_ACTUATORS; i++) {
97  rc_write_angle(AP_MOTORS_MOT_1+i, _actuator_out[i] * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
98  }
101  break;
102  }
103 }
104 
105 // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
106 // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
108 {
109  uint32_t mask =
110  1U << AP_MOTORS_MOT_1 |
111  1U << AP_MOTORS_MOT_2 |
112  1U << AP_MOTORS_MOT_3 |
113  1U << AP_MOTORS_MOT_4 |
114  1U << AP_MOTORS_MOT_5 |
115  1U << AP_MOTORS_MOT_6;
116  return rc_map_mask(mask);
117 }
118 
119 // sends commands to the motors
121 {
122  float roll_thrust; // roll thrust input value, +/- 1.0
123  float pitch_thrust; // pitch thrust input value, +/- 1.0
124  float yaw_thrust; // yaw thrust input value, +/- 1.0
125  float throttle_thrust; // throttle thrust input value, 0.0 - 1.0
126  float throttle_avg_max; // throttle thrust average maximum value, 0.0 - 1.0
127  float thrust_min_rpy; // the minimum throttle setting that will not limit the roll and pitch output
128  float thr_adj; // the difference between the pilot's desired throttle and throttle_thrust_best_rpy
129  float rp_scale = 1.0f; // this is used to scale the roll, pitch and yaw to fit within the motor limits
130  float actuator_allowed = 0.0f; // amount of yaw we can fit in
131  float actuator[NUM_ACTUATORS]; // combined roll, pitch and yaw thrusts for each actuator
132  float actuator_max = 0.0f; // maximum actuator value
133 
134  // apply voltage and air pressure compensation
135  const float compensation_gain = get_compensation_gain();
136  roll_thrust = _roll_in * compensation_gain;
137  pitch_thrust = _pitch_in * compensation_gain;
138  yaw_thrust = _yaw_in * compensation_gain;
139  throttle_thrust = get_throttle() * compensation_gain;
140  throttle_avg_max = _throttle_avg_max * compensation_gain;
141 
142  // sanity check throttle is above zero and below current limited throttle
143  if (throttle_thrust <= 0.0f) {
144  throttle_thrust = 0.0f;
145  limit.throttle_lower = true;
146  }
147  if (throttle_thrust >= _throttle_thrust_max) {
148  throttle_thrust = _throttle_thrust_max;
149  limit.throttle_upper = true;
150  }
151 
152  throttle_avg_max = constrain_float(throttle_avg_max, throttle_thrust, _throttle_thrust_max);
153 
154  float rp_thrust_max = MAX(fabsf(roll_thrust), fabsf(pitch_thrust));
155 
156  // calculate how much roll and pitch must be scaled to leave enough range for the minimum yaw
157  if (is_zero(rp_thrust_max)) {
158  rp_scale = 1.0f;
159  } else {
160  rp_scale = constrain_float((1.0f - MIN(fabsf(yaw_thrust), (float)_yaw_headroom/1000.0f)) / rp_thrust_max, 0.0f, 1.0f);
161  if (rp_scale < 1.0f) {
162  limit.roll_pitch = true;
163  }
164  }
165 
166  actuator_allowed = 1.0f - rp_scale * rp_thrust_max;
167  if (fabsf(yaw_thrust) > actuator_allowed) {
168  yaw_thrust = constrain_float(yaw_thrust, -actuator_allowed, actuator_allowed);
169  limit.yaw = true;
170  }
171 
172  // combine roll, pitch and yaw on each actuator
173  // front servo
174 
175  actuator[0] = rp_scale * roll_thrust - yaw_thrust;
176  // right servo
177  actuator[1] = rp_scale * pitch_thrust - yaw_thrust;
178  // rear servo
179  actuator[2] = -rp_scale * roll_thrust - yaw_thrust;
180  // left servo
181  actuator[3] = -rp_scale * pitch_thrust - yaw_thrust;
182 
183  // calculate the minimum thrust that doesn't limit the roll, pitch and yaw forces
184  thrust_min_rpy = MAX(MAX(fabsf(actuator[0]), fabsf(actuator[1])), MAX(fabsf(actuator[2]), fabsf(actuator[3])));
185 
186  thr_adj = throttle_thrust - throttle_avg_max;
187  if (thr_adj < (thrust_min_rpy - throttle_avg_max)) {
188  // Throttle can't be reduced to the desired level because this would mean roll or pitch control
189  // would not be able to reach the desired level because of lack of thrust.
190  thr_adj = MIN(thrust_min_rpy, throttle_avg_max) - throttle_avg_max;
191  }
192 
193  // calculate the throttle setting for the lift fan
194  _thrust_out = throttle_avg_max + thr_adj;
195 
196  if (is_zero(_thrust_out)) {
197  limit.roll_pitch = true;
198  limit.yaw = true;
199  }
200 
201  // limit thrust out for calculation of actuator gains
202  float thrust_out_actuator = constrain_float(MAX(_throttle_hover*0.5f,_thrust_out), 0.5f, 1.0f);
203 
204  // calculate the maximum allowed actuator output and maximum requested actuator output
205  for (uint8_t i=0; i<NUM_ACTUATORS; i++) {
206  if (actuator_max > fabsf(actuator[i])) {
207  actuator_max = fabsf(actuator[i]);
208  }
209  }
210  if (actuator_max > thrust_out_actuator && !is_zero(actuator_max)) {
211  // roll, pitch and yaw request can not be achieved at full servo defection
212  // reduce roll, pitch and yaw to reduce the requested defection to maximum
213  limit.roll_pitch = true;
214  limit.yaw = true;
215  rp_scale = thrust_out_actuator/actuator_max;
216  } else {
217  rp_scale = 1.0f;
218  }
219 
220  // force of a lifting surface is approximately equal to the angle of attack times the airflow velocity squared
221  // static thrust is proportional to the airflow velocity squared
222  // therefore the torque of the roll and pitch actuators should be approximately proportional to
223  // the angle of attack multiplied by the static thrust.
224  for (uint8_t i=0; i<NUM_ACTUATORS; i++) {
225  _actuator_out[i] = constrain_float(rp_scale*actuator[i]/thrust_out_actuator, -1.0f, 1.0f);
226  }
227 }
228 
229 // output_test - spin a motor at the pwm value specified
230 // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
231 // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
232 void AP_MotorsSingle::output_test(uint8_t motor_seq, int16_t pwm)
233 {
234  // exit immediately if not armed
235  if (!armed()) {
236  return;
237  }
238 
239  // output to motors and servos
240  switch (motor_seq) {
241  case 1:
242  // flap servo 1
244  break;
245  case 2:
246  // flap servo 2
248  break;
249  case 3:
250  // flap servo 3
252  break;
253  case 4:
254  // flap servo 4
256  break;
257  case 5:
258  // spin motor 1
260  break;
261  case 6:
262  // spin motor 2
264  break;
265  default:
266  // do nothing
267  break;
268  }
269 }
static void set_angle(SRV_Channel::Aux_servo_function_t function, uint16_t angle)
int16_t get_pwm_output_min() const
static SRV_Channel::Aux_servo_function_t get_motor_function(uint8_t channel)
Definition: SRV_Channel.h:414
virtual void rc_write_angle(uint8_t chan, int16_t angle_cd)
void set_update_rate(uint16_t speed_hz)
#define AP_MOTORS_SINGLE_SERVO_INPUT_RANGE
#define AP_MOTORS_MOT_4
#define NUM_ACTUATORS
Definition: AP_MotorsCoax.h:14
#define CH_1
Definition: RCOutput.h:11
Interface definition for the various Ground Control System.
#define AP_MOTORS_MOT_1
struct AP_Motors::AP_Motors_flags _flags
void output_armed_stabilizing()
virtual void output_test(uint8_t motor_seq, int16_t pwm)
#define AP_MOTORS_MOT_2
virtual uint16_t get_motor_mask()
struct AP_Motors::AP_Motors_limit limit
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
static uint16_t pwm
Definition: RCOutput.cpp:20
#define MIN(a, b)
Definition: usb_conf.h:215
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
virtual void output_to_motors()
bool armed() const
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
uint16_t _speed_hz
#define AP_MOTORS_MOT_6
#define AP_MOTORS_MOT_3
float _throttle_avg_max
virtual void rc_write(uint8_t chan, uint16_t pwm)
float _pitch_radio_passthrough
float _actuator_out[NUM_ACTUATORS]
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
void add_motor_num(int8_t motor_num)
void init(motor_frame_class frame_class, motor_frame_type frame_type)
Motor and Servo control class for Singlecopters.
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz)
float _roll_radio_passthrough
spool_up_down_mode _spool_mode
#define AP_MOTORS_MOT_5
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 calc_spin_up_to_pwm() const
int16_t calc_thrust_to_pwm(float thrust_in) const
float get_throttle() const
virtual uint32_t rc_map_mask(uint32_t mask) const