2013-05-29 20:51:34 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
2012-04-02 05:26:37 -03:00
|
|
|
/*
|
2012-08-17 03:20:26 -03:00
|
|
|
* AP_MotorsTri.cpp - ArduCopter motors library
|
|
|
|
* Code by RandyMackay. DIYDrones.com
|
|
|
|
*
|
|
|
|
*/
|
2012-10-26 20:59:07 -03:00
|
|
|
#include <AP_HAL.h>
|
|
|
|
#include <AP_Math.h>
|
2012-04-02 05:26:37 -03:00
|
|
|
#include "AP_MotorsTri.h"
|
|
|
|
|
2012-10-26 20:59:07 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2015-05-14 22:00:46 -03:00
|
|
|
const AP_Param::GroupInfo AP_MotorsTri::var_info[] PROGMEM = {
|
|
|
|
// variables from parent vehicle
|
2015-07-15 04:58:43 -03:00
|
|
|
AP_NESTEDGROUPINFO(AP_MotorsMulticopter, 0),
|
2015-05-14 22:00:46 -03:00
|
|
|
|
2015-07-02 18:15:09 -03:00
|
|
|
// parameters 1 ~ 29 were reserved for tradheli
|
2015-05-25 08:20:53 -03:00
|
|
|
// parameters 30 ~ 39 reserved for tricopter
|
|
|
|
// parameters 40 ~ 49 for single copter and coax copter (these have identical parameter files)
|
|
|
|
|
2015-05-14 22:00:46 -03:00
|
|
|
// @Param: YAW_SV_REV
|
|
|
|
// @DisplayName: Yaw Servo Reverse
|
2015-05-25 08:20:53 -03:00
|
|
|
// @Description: Yaw servo reversing. Set to 1 for normal (forward) operation. Set to -1 to reverse this channel.
|
|
|
|
// @Values: -1:Reversed,1:Normal
|
2015-05-14 22:00:46 -03:00
|
|
|
// @User: Standard
|
2015-05-25 08:20:53 -03:00
|
|
|
AP_GROUPINFO("YAW_SV_REV", 31, AP_MotorsTri, _yaw_servo_reverse, 1),
|
2015-05-14 22:00:46 -03:00
|
|
|
|
|
|
|
// @Param: YAW_SV_TRIM
|
|
|
|
// @DisplayName: Yaw Servo Trim/Center
|
|
|
|
// @Description: Trim or center position of yaw servo
|
|
|
|
// @Range: 1250 1750
|
|
|
|
// @Units: PWM
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Standard
|
2015-05-25 08:20:53 -03:00
|
|
|
AP_GROUPINFO("YAW_SV_TRIM", 32, AP_MotorsTri, _yaw_servo_trim, 1500),
|
2015-05-14 22:00:46 -03:00
|
|
|
|
|
|
|
// @Param: YAW_SV_MIN
|
|
|
|
// @DisplayName: Yaw Servo Min Position
|
|
|
|
// @Description: Minimum angle limit of yaw servo
|
|
|
|
// @Range: 1000 1400
|
|
|
|
// @Units: PWM
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Standard
|
2015-05-25 08:20:53 -03:00
|
|
|
AP_GROUPINFO("YAW_SV_MIN", 33, AP_MotorsTri, _yaw_servo_min, 1250),
|
2015-05-14 22:00:46 -03:00
|
|
|
|
|
|
|
// @Param: YAW_SV_MAX
|
|
|
|
// @DisplayName: Yaw Servo Max Position
|
|
|
|
// @Description: Maximum angle limit of yaw servo
|
|
|
|
// @Range: 1600 2000
|
|
|
|
// @Units: PWM
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Standard
|
2015-05-25 08:20:53 -03:00
|
|
|
AP_GROUPINFO("YAW_SV_MAX", 34, AP_MotorsTri, _yaw_servo_max, 1750),
|
2015-05-14 22:00:46 -03:00
|
|
|
|
|
|
|
|
|
|
|
AP_GROUPEND
|
|
|
|
};
|
|
|
|
|
2012-04-02 05:26:37 -03:00
|
|
|
// init
|
|
|
|
void AP_MotorsTri::Init()
|
|
|
|
{
|
2012-08-17 03:20:26 -03:00
|
|
|
// set update rate for the 3 motors (but not the servo on channel 7)
|
|
|
|
set_update_rate(_speed_hz);
|
2013-05-19 05:28:39 -03:00
|
|
|
|
|
|
|
// set the motor_enabled flag so that the ESCs can be calibrated like other frame types
|
|
|
|
motor_enabled[AP_MOTORS_MOT_1] = true;
|
|
|
|
motor_enabled[AP_MOTORS_MOT_2] = true;
|
|
|
|
motor_enabled[AP_MOTORS_MOT_4] = true;
|
2014-02-07 09:02:31 -04:00
|
|
|
|
|
|
|
// disable CH7 from being used as an aux output (i.e. for camera gimbal, etc)
|
|
|
|
RC_Channel_aux::disable_aux_channel(AP_MOTORS_CH_TRI_YAW);
|
2012-04-02 05:26:37 -03:00
|
|
|
}
|
|
|
|
|
2012-09-13 09:31:13 -03:00
|
|
|
// set update rate to motors - a value in hertz
|
2012-04-02 05:26:37 -03:00
|
|
|
void AP_MotorsTri::set_update_rate( uint16_t speed_hz )
|
|
|
|
{
|
2012-08-17 03:20:26 -03:00
|
|
|
// record requested speed
|
|
|
|
_speed_hz = speed_hz;
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:26 -03:00
|
|
|
// set update rate for the 3 motors (but not the servo on channel 7)
|
2013-01-10 00:52:46 -04:00
|
|
|
uint32_t mask =
|
2014-02-10 02:59:02 -04:00
|
|
|
1U << pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]) |
|
|
|
|
1U << pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]) |
|
|
|
|
1U << pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]);
|
2013-01-10 00:52:46 -04:00
|
|
|
hal.rcout->set_freq(mask, _speed_hz);
|
2012-04-02 05:26:37 -03:00
|
|
|
}
|
|
|
|
|
2012-08-17 03:20:26 -03:00
|
|
|
// enable - starts allowing signals to be sent to motors
|
2012-04-02 05:26:37 -03:00
|
|
|
void AP_MotorsTri::enable()
|
|
|
|
{
|
2012-08-17 03:20:26 -03:00
|
|
|
// enable output channels
|
2014-02-10 02:59:02 -04:00
|
|
|
hal.rcout->enable_ch(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]));
|
|
|
|
hal.rcout->enable_ch(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]));
|
|
|
|
hal.rcout->enable_ch(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]));
|
2012-10-26 20:59:07 -03:00
|
|
|
hal.rcout->enable_ch(AP_MOTORS_CH_TRI_YAW);
|
2012-04-02 05:26:37 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// output_min - sends minimum values out to the motors
|
|
|
|
void AP_MotorsTri::output_min()
|
|
|
|
{
|
2013-09-12 14:36:58 -03:00
|
|
|
// set lower limit flag
|
|
|
|
limit.throttle_lower = true;
|
2013-11-27 08:57:32 -04:00
|
|
|
|
2012-08-17 03:20:26 -03:00
|
|
|
// send minimum value to each motor
|
2015-05-14 22:00:46 -03:00
|
|
|
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), _throttle_radio_min);
|
|
|
|
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), _throttle_radio_min);
|
|
|
|
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), _throttle_radio_min);
|
|
|
|
hal.rcout->write(AP_MOTORS_CH_TRI_YAW, _yaw_servo_trim);
|
2012-04-02 05:26:37 -03:00
|
|
|
}
|
|
|
|
|
2014-07-26 04:27:39 -03:00
|
|
|
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
|
|
|
|
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
|
|
|
|
uint16_t AP_MotorsTri::get_motor_mask()
|
|
|
|
{
|
2015-05-25 10:26:48 -03:00
|
|
|
// tri copter uses channels 1,2,4 and 7
|
2015-04-05 20:25:27 -03:00
|
|
|
return (1U << pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1])) |
|
|
|
|
(1U << pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2])) |
|
|
|
|
(1U << pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4])) |
|
|
|
|
(1U << AP_MOTORS_CH_TRI_YAW);
|
2014-07-26 04:27:39 -03:00
|
|
|
}
|
|
|
|
|
2015-04-02 17:54:15 -03:00
|
|
|
void AP_MotorsTri::output_armed_not_stabilizing()
|
2012-04-02 05:26:37 -03:00
|
|
|
{
|
2015-05-14 22:00:46 -03:00
|
|
|
int16_t throttle_radio_output; // total throttle pwm value, summed onto throttle channel minimum, typically ~1100-1900
|
|
|
|
int16_t out_min = _throttle_radio_min + _min_throttle;
|
|
|
|
int16_t out_max = _throttle_radio_max;
|
2014-02-09 04:48:10 -04:00
|
|
|
int16_t motor_out[AP_MOTORS_MOT_4+1];
|
2012-08-17 03:20:26 -03:00
|
|
|
|
2015-04-02 17:54:15 -03:00
|
|
|
// initialize limits flags
|
|
|
|
limit.roll_pitch = true;
|
|
|
|
limit.yaw = true;
|
2013-09-12 14:36:58 -03:00
|
|
|
limit.throttle_lower = false;
|
2015-04-02 17:54:15 -03:00
|
|
|
limit.throttle_upper = false;
|
|
|
|
|
2015-07-20 05:06:09 -03:00
|
|
|
int16_t thr_in_min = rel_pwm_to_thr_range(_spin_when_armed_ramped);
|
|
|
|
if (_throttle_control_input <= thr_in_min) {
|
|
|
|
_throttle_control_input = thr_in_min;
|
2015-04-02 17:54:15 -03:00
|
|
|
limit.throttle_lower = true;
|
|
|
|
}
|
|
|
|
|
2015-05-14 22:00:46 -03:00
|
|
|
if (_throttle_control_input >= _hover_out) {
|
|
|
|
_throttle_control_input = _hover_out;
|
2015-04-02 17:54:15 -03:00
|
|
|
limit.throttle_upper = true;
|
|
|
|
}
|
|
|
|
|
2015-05-14 22:00:46 -03:00
|
|
|
throttle_radio_output = calc_throttle_radio_output();
|
2015-04-02 17:54:15 -03:00
|
|
|
|
2015-05-14 22:00:46 -03:00
|
|
|
motor_out[AP_MOTORS_MOT_1] = throttle_radio_output;
|
|
|
|
motor_out[AP_MOTORS_MOT_2] = throttle_radio_output;
|
|
|
|
motor_out[AP_MOTORS_MOT_4] = throttle_radio_output;
|
2015-04-02 17:54:15 -03:00
|
|
|
|
2015-05-14 22:00:46 -03:00
|
|
|
if(throttle_radio_output >= out_min) {
|
2015-04-02 17:54:15 -03:00
|
|
|
// adjust for thrust curve and voltage scaling
|
|
|
|
motor_out[AP_MOTORS_MOT_1] = apply_thrust_curve_and_volt_scaling(motor_out[AP_MOTORS_MOT_1], out_min, out_max);
|
|
|
|
motor_out[AP_MOTORS_MOT_2] = apply_thrust_curve_and_volt_scaling(motor_out[AP_MOTORS_MOT_2], out_min, out_max);
|
|
|
|
motor_out[AP_MOTORS_MOT_4] = apply_thrust_curve_and_volt_scaling(motor_out[AP_MOTORS_MOT_4], out_min, out_max);
|
|
|
|
}
|
|
|
|
|
|
|
|
// send output to each motor
|
|
|
|
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), motor_out[AP_MOTORS_MOT_1]);
|
|
|
|
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), motor_out[AP_MOTORS_MOT_2]);
|
|
|
|
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), motor_out[AP_MOTORS_MOT_4]);
|
|
|
|
|
2015-05-14 22:00:46 -03:00
|
|
|
// send centering signal to yaw servo
|
|
|
|
hal.rcout->write(AP_MOTORS_CH_TRI_YAW, _yaw_servo_trim);
|
2015-04-02 17:54:15 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// sends commands to the motors
|
|
|
|
// TODO pull code that is common to output_armed_not_stabilizing into helper functions
|
|
|
|
void AP_MotorsTri::output_armed_stabilizing()
|
|
|
|
{
|
2015-05-14 22:00:46 -03:00
|
|
|
int16_t roll_pwm; // roll pwm value, initially calculated by calc_roll_pwm() but may be modified after, +/- 400
|
|
|
|
int16_t pitch_pwm; // pitch pwm value, initially calculated by calc_roll_pwm() but may be modified after, +/- 400
|
|
|
|
int16_t throttle_radio_output; // total throttle pwm value, summed onto throttle channel minimum, typically ~1100-1900
|
|
|
|
int16_t yaw_radio_output; // final yaw pwm value sent to motors, typically ~1100-1900
|
|
|
|
int16_t out_min = _throttle_radio_min + _min_throttle;
|
|
|
|
int16_t out_max = _throttle_radio_max;
|
2015-04-02 17:54:15 -03:00
|
|
|
int16_t motor_out[AP_MOTORS_MOT_4+1];
|
|
|
|
|
|
|
|
// initialize limits flags
|
|
|
|
limit.roll_pitch = false;
|
|
|
|
limit.yaw = false;
|
|
|
|
limit.throttle_lower = false;
|
|
|
|
limit.throttle_upper = false;
|
2013-09-12 14:36:58 -03:00
|
|
|
|
2012-08-17 03:20:26 -03:00
|
|
|
// Throttle is 0 to 1000 only
|
2015-07-20 05:06:09 -03:00
|
|
|
int16_t thr_in_min = rel_pwm_to_thr_range(_min_throttle);
|
|
|
|
if (_throttle_control_input <= thr_in_min) {
|
|
|
|
_throttle_control_input = thr_in_min;
|
2014-10-04 11:27:11 -03:00
|
|
|
limit.throttle_lower = true;
|
|
|
|
}
|
2015-05-14 22:00:46 -03:00
|
|
|
if (_throttle_control_input >= _max_throttle) {
|
|
|
|
_throttle_control_input = _max_throttle;
|
2014-10-04 11:27:11 -03:00
|
|
|
limit.throttle_upper = true;
|
|
|
|
}
|
2012-08-17 03:20:26 -03:00
|
|
|
|
2015-01-21 07:16:34 -04:00
|
|
|
// tricopters limit throttle to 80%
|
|
|
|
// To-Do: implement improved stability patch and remove this limit
|
2015-05-14 22:00:46 -03:00
|
|
|
if (_throttle_control_input > 800) {
|
|
|
|
_throttle_control_input = 800;
|
2015-01-21 07:16:34 -04:00
|
|
|
limit.throttle_upper = true;
|
|
|
|
}
|
|
|
|
|
2015-05-14 22:00:46 -03:00
|
|
|
roll_pwm = calc_roll_pwm();
|
|
|
|
pitch_pwm = calc_pitch_pwm();
|
|
|
|
throttle_radio_output = calc_throttle_radio_output();
|
|
|
|
yaw_radio_output = calc_yaw_radio_output();
|
2012-08-17 03:20:26 -03:00
|
|
|
|
|
|
|
// if we are not sending a throttle output, we cut the motors
|
2015-05-14 22:00:46 -03:00
|
|
|
if( is_zero(_throttle_control_input) ) {
|
2013-07-16 00:46:34 -03:00
|
|
|
// range check spin_when_armed
|
2013-10-20 02:51:35 -03:00
|
|
|
if (_spin_when_armed_ramped < 0) {
|
|
|
|
_spin_when_armed_ramped = 0;
|
2013-07-16 00:46:34 -03:00
|
|
|
}
|
2013-10-20 02:51:35 -03:00
|
|
|
if (_spin_when_armed_ramped > _min_throttle) {
|
|
|
|
_spin_when_armed_ramped = _min_throttle;
|
2013-07-16 03:25:57 -03:00
|
|
|
}
|
2015-05-14 22:00:46 -03:00
|
|
|
motor_out[AP_MOTORS_MOT_1] = _throttle_radio_min + _spin_when_armed_ramped;
|
|
|
|
motor_out[AP_MOTORS_MOT_2] = _throttle_radio_min + _spin_when_armed_ramped;
|
|
|
|
motor_out[AP_MOTORS_MOT_4] = _throttle_radio_min + _spin_when_armed_ramped;
|
2013-09-12 14:36:58 -03:00
|
|
|
|
2013-07-16 00:46:34 -03:00
|
|
|
}else{
|
2015-05-14 22:00:46 -03:00
|
|
|
int16_t roll_out = (float)(roll_pwm * 0.866f);
|
|
|
|
int16_t pitch_out = pitch_pwm / 2;
|
2013-07-16 00:46:34 -03:00
|
|
|
|
2013-09-12 14:36:58 -03:00
|
|
|
// check if throttle is below limit
|
2015-05-14 22:00:46 -03:00
|
|
|
if (_throttle_control_input <= _min_throttle) {
|
2013-09-12 14:36:58 -03:00
|
|
|
limit.throttle_lower = true;
|
2015-05-14 22:00:46 -03:00
|
|
|
_throttle_control_input = _min_throttle;
|
|
|
|
throttle_radio_output = calc_throttle_radio_output();
|
2013-09-12 14:36:58 -03:00
|
|
|
}
|
2015-04-02 17:54:15 -03:00
|
|
|
|
|
|
|
// TODO: set limits.roll_pitch and limits.yaw
|
|
|
|
|
2013-07-16 00:46:34 -03:00
|
|
|
//left front
|
2015-05-14 22:00:46 -03:00
|
|
|
motor_out[AP_MOTORS_MOT_2] = throttle_radio_output + roll_out + pitch_out;
|
2013-07-16 00:46:34 -03:00
|
|
|
//right front
|
2015-05-14 22:00:46 -03:00
|
|
|
motor_out[AP_MOTORS_MOT_1] = throttle_radio_output - roll_out + pitch_out;
|
2013-07-16 00:46:34 -03:00
|
|
|
// rear
|
2015-05-14 22:00:46 -03:00
|
|
|
motor_out[AP_MOTORS_MOT_4] = throttle_radio_output - pitch_pwm;
|
2013-07-16 00:46:34 -03:00
|
|
|
|
|
|
|
// Tridge's stability patch
|
|
|
|
if(motor_out[AP_MOTORS_MOT_1] > out_max) {
|
2013-09-12 14:39:40 -03:00
|
|
|
motor_out[AP_MOTORS_MOT_2] -= (motor_out[AP_MOTORS_MOT_1] - out_max);
|
|
|
|
motor_out[AP_MOTORS_MOT_4] -= (motor_out[AP_MOTORS_MOT_1] - out_max);
|
2013-07-16 00:46:34 -03:00
|
|
|
motor_out[AP_MOTORS_MOT_1] = out_max;
|
|
|
|
}
|
|
|
|
|
|
|
|
if(motor_out[AP_MOTORS_MOT_2] > out_max) {
|
2013-09-12 14:39:40 -03:00
|
|
|
motor_out[AP_MOTORS_MOT_1] -= (motor_out[AP_MOTORS_MOT_2] - out_max);
|
|
|
|
motor_out[AP_MOTORS_MOT_4] -= (motor_out[AP_MOTORS_MOT_2] - out_max);
|
2013-07-16 00:46:34 -03:00
|
|
|
motor_out[AP_MOTORS_MOT_2] = out_max;
|
|
|
|
}
|
|
|
|
|
|
|
|
if(motor_out[AP_MOTORS_MOT_4] > out_max) {
|
2013-09-12 14:39:40 -03:00
|
|
|
motor_out[AP_MOTORS_MOT_1] -= (motor_out[AP_MOTORS_MOT_4] - out_max);
|
|
|
|
motor_out[AP_MOTORS_MOT_2] -= (motor_out[AP_MOTORS_MOT_4] - out_max);
|
2013-07-16 00:46:34 -03:00
|
|
|
motor_out[AP_MOTORS_MOT_4] = out_max;
|
|
|
|
}
|
|
|
|
|
2015-02-21 04:33:37 -04:00
|
|
|
// adjust for thrust curve and voltage scaling
|
|
|
|
motor_out[AP_MOTORS_MOT_1] = apply_thrust_curve_and_volt_scaling(motor_out[AP_MOTORS_MOT_1], out_min, out_max);
|
|
|
|
motor_out[AP_MOTORS_MOT_2] = apply_thrust_curve_and_volt_scaling(motor_out[AP_MOTORS_MOT_2], out_min, out_max);
|
|
|
|
motor_out[AP_MOTORS_MOT_4] = apply_thrust_curve_and_volt_scaling(motor_out[AP_MOTORS_MOT_4], out_min, out_max);
|
2013-07-16 00:46:34 -03:00
|
|
|
|
|
|
|
// ensure motors don't drop below a minimum value and stop
|
|
|
|
motor_out[AP_MOTORS_MOT_1] = max(motor_out[AP_MOTORS_MOT_1], out_min);
|
|
|
|
motor_out[AP_MOTORS_MOT_2] = max(motor_out[AP_MOTORS_MOT_2], out_min);
|
|
|
|
motor_out[AP_MOTORS_MOT_4] = max(motor_out[AP_MOTORS_MOT_4], out_min);
|
2012-08-17 03:20:26 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// send output to each motor
|
2014-02-10 02:59:02 -04:00
|
|
|
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), motor_out[AP_MOTORS_MOT_1]);
|
|
|
|
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), motor_out[AP_MOTORS_MOT_2]);
|
|
|
|
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), motor_out[AP_MOTORS_MOT_4]);
|
2012-08-17 03:20:26 -03:00
|
|
|
|
2015-05-14 22:00:46 -03:00
|
|
|
// send out to yaw command to tail servo
|
|
|
|
hal.rcout->write(AP_MOTORS_CH_TRI_YAW, yaw_radio_output);
|
2012-04-02 05:26:37 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// output_disarmed - sends commands to the motors
|
|
|
|
void AP_MotorsTri::output_disarmed()
|
|
|
|
{
|
2012-08-17 03:20:26 -03:00
|
|
|
// Send minimum values to all motors
|
|
|
|
output_min();
|
2012-04-02 05:26:37 -03:00
|
|
|
}
|
|
|
|
|
2014-04-28 04:30:26 -03:00
|
|
|
// output_test - spin a motor at the pwm value specified
|
|
|
|
// motor_seq is the motor's sequence number from 1 to the number of motors on the frame
|
|
|
|
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
|
|
|
|
void AP_MotorsTri::output_test(uint8_t motor_seq, int16_t pwm)
|
2012-04-02 05:26:37 -03:00
|
|
|
{
|
2014-04-28 04:30:26 -03:00
|
|
|
// exit immediately if not armed
|
2015-04-02 17:54:15 -03:00
|
|
|
if (!armed()) {
|
2014-04-28 04:30:26 -03:00
|
|
|
return;
|
|
|
|
}
|
2012-10-26 20:59:07 -03:00
|
|
|
|
2014-04-28 04:30:26 -03:00
|
|
|
// output to motors and servos
|
|
|
|
switch (motor_seq) {
|
|
|
|
case 1:
|
|
|
|
// front right motor
|
|
|
|
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), pwm);
|
|
|
|
break;
|
|
|
|
case 2:
|
|
|
|
// back motor
|
|
|
|
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), pwm);
|
|
|
|
break;
|
|
|
|
case 3:
|
|
|
|
// back servo
|
2015-04-05 20:25:27 -03:00
|
|
|
hal.rcout->write(AP_MOTORS_CH_TRI_YAW, pwm);
|
2014-04-28 04:30:26 -03:00
|
|
|
break;
|
|
|
|
case 4:
|
|
|
|
// front left motor
|
|
|
|
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), pwm);
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
// do nothing
|
|
|
|
break;
|
|
|
|
}
|
2012-10-26 20:59:07 -03:00
|
|
|
}
|
2015-05-14 22:00:46 -03:00
|
|
|
|
|
|
|
// calc_yaw_radio_output - calculate final radio output for yaw channel
|
|
|
|
int16_t AP_MotorsTri::calc_yaw_radio_output()
|
|
|
|
{
|
|
|
|
int16_t ret;
|
|
|
|
|
2015-05-25 08:20:53 -03:00
|
|
|
if (_yaw_servo_reverse < 0) {
|
2015-05-14 22:00:46 -03:00
|
|
|
if (_yaw_control_input >= 0){
|
|
|
|
ret = (_yaw_servo_trim - (_yaw_control_input/4500 * (_yaw_servo_trim - _yaw_servo_min)));
|
|
|
|
} else {
|
|
|
|
ret = (_yaw_servo_trim - (_yaw_control_input/4500 * (_yaw_servo_max - _yaw_servo_trim)));
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
if (_yaw_control_input >= 0){
|
|
|
|
ret = ((_yaw_control_input/4500 * (_yaw_servo_max - _yaw_servo_trim)) + _yaw_servo_trim);
|
|
|
|
} else {
|
|
|
|
ret = ((_yaw_control_input/4500 * (_yaw_servo_trim - _yaw_servo_min)) + _yaw_servo_trim);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
return ret;
|
|
|
|
}
|