APM:Libraries
AP_MotorsTri.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_MotorsTri.cpp - ArduCopter motors library
18  * Code by RandyMackay. DIYDrones.com
19  *
20  */
21 #include <AP_HAL/AP_HAL.h>
22 #include <AP_Math/AP_Math.h>
23 #include <GCS_MAVLink/GCS.h>
24 #include "AP_MotorsTri.h"
25 
26 extern const AP_HAL::HAL& hal;
27 
28 // init
30 {
34 
35  // set update rate for the 3 motors (but not the servo on channel 7)
37 
38  // set the motor_enabled flag so that the ESCs can be calibrated like other frame types
42 
43  // find the yaw servo
45  if (!_yaw_servo) {
46  gcs().send_text(MAV_SEVERITY_ERROR, "MotorsTri: unable to setup yaw channel");
47  // don't set initialised_ok
48  return;
49  }
50 
51  // allow mapping of motor7
53 
54  // record successful initialisation if what we setup was the desired frame_class
55  _flags.initialised_ok = (frame_class == MOTOR_FRAME_TRI);
56 }
57 
58 // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
60 {
61  _flags.initialised_ok = (frame_class == MOTOR_FRAME_TRI);
62 }
63 
64 // set update rate to motors - a value in hertz
65 void AP_MotorsTri::set_update_rate( uint16_t speed_hz )
66 {
67  // record requested speed
68  _speed_hz = speed_hz;
69 
70  // set update rate for the 3 motors (but not the servo on channel 7)
71  uint32_t mask =
72  1U << AP_MOTORS_MOT_1 |
73  1U << AP_MOTORS_MOT_2 |
74  1U << AP_MOTORS_MOT_4;
75  rc_set_freq(mask, _speed_hz);
76 }
77 
79 {
80  switch (_spool_mode) {
81  case SHUT_DOWN:
82  // sends minimum values out to the motors
87  break;
88  case SPIN_WHEN_ARMED:
89  // sends output to motors when armed but not flying
94  break;
95  case SPOOL_UP:
96  case THROTTLE_UNLIMITED:
97  case SPOOL_DOWN:
98  // set motor output based on thrust requests
103  break;
104  }
105 }
106 
107 // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
108 // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
110 {
111  // tri copter uses channels 1,2,4 and 7
112  return rc_map_mask((1U << AP_MOTORS_MOT_1) |
113  (1U << AP_MOTORS_MOT_2) |
114  (1U << AP_MOTORS_MOT_4) |
115  (1U << AP_MOTORS_CH_TRI_YAW));
116 }
117 
118 // output_armed - sends commands to the motors
119 // includes new scaling stability patch
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 throttle_thrust_best_rpy; // throttle providing maximum roll, pitch and yaw range without climbing
128  float rpy_scale = 1.0f; // this is used to scale the roll, pitch and yaw to fit within the motor limits
129  float rpy_low = 0.0f; // lowest motor value
130  float rpy_high = 0.0f; // highest motor value
131  float thr_adj; // the difference between the pilot's desired throttle and throttle_thrust_best_rpy
132 
133  // sanity check YAW_SV_ANGLE parameter value to avoid divide by zero
135 
136  // apply voltage and air pressure compensation
137  const float compensation_gain = get_compensation_gain();
138  roll_thrust = _roll_in * compensation_gain;
139  pitch_thrust = _pitch_in * compensation_gain;
140  yaw_thrust = _yaw_in * compensation_gain * sinf(radians(_yaw_servo_angle_max_deg)); // we scale this so a thrust request of 1.0f will ask for full servo deflection at full rear throttle
141  throttle_thrust = get_throttle() * compensation_gain;
142  throttle_avg_max = _throttle_avg_max * compensation_gain;
143 
144  // calculate angle of yaw pivot
145  _pivot_angle = safe_asin(yaw_thrust);
147  limit.yaw = true;
149  }
150 
151  float pivot_thrust_max = cosf(_pivot_angle);
152  float thrust_max = 1.0f;
153 
154  // sanity check throttle is above zero and below current limited throttle
155  if (throttle_thrust <= 0.0f) {
156  throttle_thrust = 0.0f;
157  limit.throttle_lower = true;
158  }
159  if (throttle_thrust >= _throttle_thrust_max) {
160  throttle_thrust = _throttle_thrust_max;
161  limit.throttle_upper = true;
162  }
163 
164  throttle_avg_max = constrain_float(throttle_avg_max, throttle_thrust, _throttle_thrust_max);
165 
166  // The following mix may be offer less coupling between axis but needs testing
167  //_thrust_right = roll_thrust * -0.5f + pitch_thrust * 1.0f;
168  //_thrust_left = roll_thrust * 0.5f + pitch_thrust * 1.0f;
169  //_thrust_rear = 0;
170 
171  _thrust_right = roll_thrust * -0.5f + pitch_thrust * 0.5f;
172  _thrust_left = roll_thrust * 0.5f + pitch_thrust * 0.5f;
173  _thrust_rear = pitch_thrust * -0.5f;
174 
175  // calculate roll and pitch for each motor
176  // set rpy_low and rpy_high to the lowest and highest values of the motors
177 
178  // record lowest roll pitch command
179  rpy_low = MIN(_thrust_right,_thrust_left);
180  rpy_high = MAX(_thrust_right,_thrust_left);
181  if (rpy_low > _thrust_rear){
182  rpy_low = _thrust_rear;
183  }
184  // check to see if the rear motor will reach maximum thrust before the front two motors
185  if ((1.0f - rpy_high) > (pivot_thrust_max - _thrust_rear)){
186  thrust_max = pivot_thrust_max;
187  rpy_high = _thrust_rear;
188  }
189 
190  // calculate throttle that gives most possible room for yaw (range 1000 ~ 2000) which is the lower of:
191  // 1. 0.5f - (rpy_low+rpy_high)/2.0 - this would give the maximum possible room margin above the highest motor and below the lowest
192  // 2. the higher of:
193  // a) the pilot's throttle input
194  // b) the point _throttle_rpy_mix between the pilot's input throttle and hover-throttle
195  // Situation #2 ensure we never increase the throttle above hover throttle unless the pilot has commanded this.
196  // Situation #2b allows us to raise the throttle above what the pilot commanded but not so far that it would actually cause the copter to rise.
197  // We will choose #1 (the best throttle for yaw control) if that means reducing throttle to the motors (i.e. we favor reducing throttle *because* it provides better yaw control)
198  // We will choose #2 (a mix of pilot and hover throttle) only when the throttle is quite low. We favor reducing throttle instead of better yaw control because the pilot has commanded it
199 
200  // check everything fits
201  throttle_thrust_best_rpy = MIN(0.5f*thrust_max - (rpy_low+rpy_high)/2.0, throttle_avg_max);
202  if(is_zero(rpy_low)){
203  rpy_scale = 1.0f;
204  } else {
205  rpy_scale = constrain_float(-throttle_thrust_best_rpy/rpy_low, 0.0f, 1.0f);
206  }
207 
208  // calculate how close the motors can come to the desired throttle
209  thr_adj = throttle_thrust - throttle_thrust_best_rpy;
210  if(rpy_scale < 1.0f){
211  // Full range is being used by roll, pitch, and yaw.
212  limit.roll_pitch = true;
213  if (thr_adj > 0.0f){
214  limit.throttle_upper = true;
215  }
216  thr_adj = 0.0f;
217  }else{
218  if(thr_adj < -(throttle_thrust_best_rpy+rpy_low)){
219  // Throttle can't be reduced to desired value
220  thr_adj = -(throttle_thrust_best_rpy+rpy_low);
221  }else if(thr_adj > thrust_max - (throttle_thrust_best_rpy+rpy_high)){
222  // Throttle can't be increased to desired value
223  thr_adj = thrust_max - (throttle_thrust_best_rpy+rpy_high);
224  limit.throttle_upper = true;
225  }
226  }
227 
228  // add scaled roll, pitch, constrained yaw and throttle for each motor
229  _thrust_right = throttle_thrust_best_rpy+thr_adj + rpy_scale*_thrust_right;
230  _thrust_left = throttle_thrust_best_rpy+thr_adj + rpy_scale*_thrust_left;
231  _thrust_rear = throttle_thrust_best_rpy+thr_adj + rpy_scale*_thrust_rear;
232 
233  // scale pivot thrust to account for pivot angle
234  // we should not need to check for divide by zero as _pivot_angle is constrained to the 5deg ~ 80 deg range
235  _thrust_rear = _thrust_rear/cosf(_pivot_angle);
236 
237  // constrain all outputs to 0.0f to 1.0f
238  // test code should be run with these lines commented out as they should not do anything
239  _thrust_right = constrain_float(_thrust_right, 0.0f, 1.0f);
240  _thrust_left = constrain_float(_thrust_left, 0.0f, 1.0f);
241  _thrust_rear = constrain_float(_thrust_rear, 0.0f, 1.0f);
242 }
243 
244 // output_test - spin a motor at the pwm value specified
245 // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
246 // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
247 void AP_MotorsTri::output_test(uint8_t motor_seq, int16_t pwm)
248 {
249  // exit immediately if not armed
250  if (!armed()) {
251  return;
252  }
253 
254  // output to motors and servos
255  switch (motor_seq) {
256  case 1:
257  // front right motor
259  break;
260  case 2:
261  // back motor
263  break;
264  case 3:
265  // back servo
267  break;
268  case 4:
269  // front left motor
271  break;
272  default:
273  // do nothing
274  break;
275  }
276 }
277 
278 // calc_yaw_radio_output - calculate final radio output for yaw channel
279 int16_t AP_MotorsTri::calc_yaw_radio_output(float yaw_input, float yaw_input_max)
280 {
281  int16_t ret;
282 
283  if (_yaw_servo->get_reversed()) {
284  yaw_input = -yaw_input;
285  }
286 
287  if (yaw_input >= 0){
288  ret = (_yaw_servo->get_trim() + (yaw_input/yaw_input_max * (_yaw_servo->get_output_max() - _yaw_servo->get_trim())));
289  } else {
290  ret = (_yaw_servo->get_trim() + (yaw_input/yaw_input_max * (_yaw_servo->get_trim() - _yaw_servo->get_output_min())));
291  }
292 
293  return ret;
294 }
295 
296 /*
297  call vehicle supplied thrust compensation if set. This allows for
298  vehicle specific thrust compensation for motor arrangements such as
299  the forward motors tilting
300 */
302 {
304  // convert 3 thrust values into an array indexed by motor number
305  float thrust[4] { _thrust_right, _thrust_left, 0, _thrust_rear };
306 
307  // apply vehicle supplied compensation function
309 
310  // extract compensated thrust values
311  _thrust_right = thrust[0];
312  _thrust_left = thrust[1];
313  _thrust_rear = thrust[3];
314  }
315 }
316 
317 /*
318  override tricopter tail servo output in output_motor_mask
319  */
320 void AP_MotorsTri::output_motor_mask(float thrust, uint8_t mask)
321 {
322  // normal multicopter output
324 
325  // and override yaw servo
327 }
int16_t get_pwm_output_min() const
float _thrust_right
Definition: AP_MotorsTri.h:66
#define AP_MOTORS_MOT_4
virtual void output_test(uint8_t motor_seq, int16_t pwm)
Interface definition for the various Ground Control System.
#define AP_MOTORS_MOT_1
struct AP_Motors::AP_Motors_flags _flags
void output_armed_stabilizing()
#define AP_MOTORS_MOT_2
uint16_t get_output_max(void) const
Definition: SRV_Channel.h:164
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
struct AP_Motors::AP_Motors_limit limit
static SRV_Channel * get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan=-1)
GCS & gcs()
void thrust_compensation(void) override
static uint16_t pwm
Definition: RCOutput.cpp:20
#define AP_MOTORS_TRI_SERVO_RANGE_DEG_MIN
Definition: AP_MotorsTri.h:13
#define AP_MOTORS_TRI_SERVO_RANGE_DEG_MAX
Definition: AP_MotorsTri.h:14
#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
float _thrust_rear
Definition: AP_MotorsTri.h:67
bool armed() const
int16_t calc_yaw_radio_output(float yaw_input, float yaw_input_max)
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
SRV_Channel * _yaw_servo
Definition: AP_MotorsTri.h:64
float _pivot_angle
Definition: AP_MotorsTri.h:65
#define AP_MOTORS_CH_TRI_YAW
Definition: AP_MotorsTri.h:11
Motor control class for Tricopters.
void init(motor_frame_class frame_class, motor_frame_type frame_type)
uint16_t get_output_min(void) const
Definition: SRV_Channel.h:161
uint16_t _speed_hz
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
float _throttle_avg_max
float safe_asin(const T v)
Definition: AP_Math.cpp:43
virtual void rc_write(uint8_t chan, uint16_t pwm)
uint16_t get_trim(void) const
Definition: SRV_Channel.h:167
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
virtual uint16_t get_motor_mask()
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void add_motor_num(int8_t motor_num)
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz)
spool_up_down_mode _spool_mode
bool get_reversed(void) const
Definition: SRV_Channel.h:148
int16_t calc_spin_up_to_pwm() const
float _thrust_left
Definition: AP_MotorsTri.h:68
thrust_compensation_fn_t _thrust_compensation_callback
int16_t calc_thrust_to_pwm(float thrust_in) const
void output_motor_mask(float thrust, uint8_t mask) override
float get_throttle() const
virtual void output_to_motors()
virtual uint32_t rc_map_mask(uint32_t mask) const
void set_update_rate(uint16_t speed_hz)
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
virtual void output_motor_mask(float thrust, uint8_t mask)