2017-02-10 01:26:12 -04: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/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
/*
|
2018-10-21 14:54:30 -03:00
|
|
|
* AP_MotorsTailsitter.cpp - ArduCopter motors library for tailsitters and bicopters
|
2017-02-10 01:26:12 -04:00
|
|
|
*
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include "AP_MotorsTailsitter.h"
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
2023-01-24 17:39:44 -04:00
|
|
|
#include <SRV_Channel/SRV_Channel.h>
|
2017-02-10 01:26:12 -04:00
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
#define SERVO_OUTPUT_RANGE 4500
|
|
|
|
|
|
|
|
// init
|
|
|
|
void AP_MotorsTailsitter::init(motor_frame_class frame_class, motor_frame_type frame_type)
|
|
|
|
{
|
2018-12-19 00:17:47 -04:00
|
|
|
// setup default motor and servo mappings
|
2021-11-14 15:16:22 -04:00
|
|
|
_has_diff_thrust = SRV_Channels::function_assigned(SRV_Channel::k_throttleRight) || SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft);
|
2018-10-21 14:54:30 -03:00
|
|
|
|
2018-12-19 00:17:47 -04:00
|
|
|
// right throttle defaults to servo output 1
|
|
|
|
SRV_Channels::set_aux_channel_default(SRV_Channel::k_throttleRight, CH_1);
|
|
|
|
|
|
|
|
// left throttle defaults to servo output 2
|
|
|
|
SRV_Channels::set_aux_channel_default(SRV_Channel::k_throttleLeft, CH_2);
|
|
|
|
|
|
|
|
// right servo defaults to servo output 3
|
|
|
|
SRV_Channels::set_aux_channel_default(SRV_Channel::k_tiltMotorRight, CH_3);
|
|
|
|
SRV_Channels::set_angle(SRV_Channel::k_tiltMotorRight, SERVO_OUTPUT_RANGE);
|
|
|
|
|
|
|
|
// left servo defaults to servo output 4
|
|
|
|
SRV_Channels::set_aux_channel_default(SRV_Channel::k_tiltMotorLeft, CH_4);
|
|
|
|
SRV_Channels::set_angle(SRV_Channel::k_tiltMotorLeft, SERVO_OUTPUT_RANGE);
|
2018-10-21 14:54:30 -03:00
|
|
|
|
2021-11-14 15:16:22 -04:00
|
|
|
_mav_type = MAV_TYPE_VTOL_DUOROTOR;
|
2020-12-24 17:17:37 -04:00
|
|
|
|
2017-02-10 01:26:12 -04:00
|
|
|
// record successful initialisation if what we setup was the desired frame_class
|
2019-05-03 02:27:09 -03:00
|
|
|
set_initialised_ok(frame_class == MOTOR_FRAME_TAILSITTER);
|
2017-02-10 01:26:12 -04:00
|
|
|
}
|
|
|
|
|
2017-04-10 01:51:00 -03:00
|
|
|
|
|
|
|
/// Constructor
|
2022-12-06 21:03:36 -04:00
|
|
|
AP_MotorsTailsitter::AP_MotorsTailsitter(uint16_t speed_hz) :
|
|
|
|
AP_MotorsMulticopter(speed_hz)
|
2017-04-10 01:51:00 -03:00
|
|
|
{
|
2018-12-19 00:17:47 -04:00
|
|
|
set_update_rate(speed_hz);
|
2017-04-10 01:51:00 -03:00
|
|
|
}
|
|
|
|
|
2018-10-21 14:54:30 -03:00
|
|
|
|
|
|
|
// set update rate to motors - a value in hertz
|
2018-12-19 00:15:47 -04:00
|
|
|
void AP_MotorsTailsitter::set_update_rate(uint16_t speed_hz)
|
2018-10-21 14:54:30 -03:00
|
|
|
{
|
|
|
|
// record requested speed
|
|
|
|
_speed_hz = speed_hz;
|
|
|
|
|
2018-12-19 00:17:47 -04:00
|
|
|
SRV_Channels::set_rc_frequency(SRV_Channel::k_throttleLeft, speed_hz);
|
|
|
|
SRV_Channels::set_rc_frequency(SRV_Channel::k_throttleRight, speed_hz);
|
2018-10-21 14:54:30 -03:00
|
|
|
}
|
|
|
|
|
2017-02-10 01:26:12 -04:00
|
|
|
void AP_MotorsTailsitter::output_to_motors()
|
|
|
|
{
|
2019-05-03 02:27:09 -03:00
|
|
|
if (!initialised_ok()) {
|
2017-02-10 01:26:12 -04:00
|
|
|
return;
|
|
|
|
}
|
2018-10-21 14:54:30 -03:00
|
|
|
|
2019-04-09 09:15:45 -03:00
|
|
|
switch (_spool_state) {
|
|
|
|
case SpoolState::SHUT_DOWN:
|
2021-03-15 15:41:10 -03:00
|
|
|
_actuator[0] = 0.0f;
|
|
|
|
_actuator[1] = 0.0f;
|
|
|
|
_actuator[2] = 0.0f;
|
2021-11-14 15:16:22 -04:00
|
|
|
_external_min_throttle = 0.0;
|
2017-02-10 01:26:12 -04:00
|
|
|
break;
|
2019-04-09 09:15:45 -03:00
|
|
|
case SpoolState::GROUND_IDLE:
|
2021-03-15 15:41:10 -03:00
|
|
|
set_actuator_with_slew(_actuator[0], actuator_spin_up_to_ground_idle());
|
2019-01-21 07:13:00 -04:00
|
|
|
set_actuator_with_slew(_actuator[1], actuator_spin_up_to_ground_idle());
|
2021-03-15 15:41:10 -03:00
|
|
|
set_actuator_with_slew(_actuator[2], actuator_spin_up_to_ground_idle());
|
2021-11-14 15:16:22 -04:00
|
|
|
_external_min_throttle = 0.0;
|
2017-02-10 01:26:12 -04:00
|
|
|
break;
|
2019-04-09 09:15:45 -03:00
|
|
|
case SpoolState::SPOOLING_UP:
|
|
|
|
case SpoolState::THROTTLE_UNLIMITED:
|
|
|
|
case SpoolState::SPOOLING_DOWN:
|
2023-01-30 21:54:00 -04:00
|
|
|
set_actuator_with_slew(_actuator[0], thr_lin.thrust_to_actuator(_thrust_left));
|
|
|
|
set_actuator_with_slew(_actuator[1], thr_lin.thrust_to_actuator(_thrust_right));
|
|
|
|
set_actuator_with_slew(_actuator[2], thr_lin.thrust_to_actuator(_throttle));
|
2017-02-10 01:26:12 -04:00
|
|
|
break;
|
|
|
|
}
|
2017-02-12 21:26:59 -04:00
|
|
|
|
2021-03-15 15:41:10 -03:00
|
|
|
SRV_Channels::set_output_pwm(SRV_Channel::k_throttleLeft, output_to_pwm(_actuator[0]));
|
|
|
|
SRV_Channels::set_output_pwm(SRV_Channel::k_throttleRight, output_to_pwm(_actuator[1]));
|
|
|
|
|
|
|
|
// use set scaled to allow a different PWM range on plane forward throttle, throttle range is 0 to 100
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, _actuator[2]*100);
|
|
|
|
|
2018-12-20 07:51:57 -04:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft, _tilt_left*SERVO_OUTPUT_RANGE);
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRight, _tilt_right*SERVO_OUTPUT_RANGE);
|
2018-10-21 14:54:30 -03:00
|
|
|
|
2017-02-10 01:26:12 -04:00
|
|
|
}
|
|
|
|
|
2018-12-19 00:17:47 -04:00
|
|
|
// get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
|
2018-10-21 14:54:30 -03:00
|
|
|
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
|
2021-12-10 12:45:20 -04:00
|
|
|
uint32_t AP_MotorsTailsitter::get_motor_mask()
|
2018-10-21 14:54:30 -03:00
|
|
|
{
|
2018-12-19 00:17:47 -04:00
|
|
|
uint32_t motor_mask = 0;
|
|
|
|
uint8_t chan;
|
|
|
|
if (SRV_Channels::find_channel(SRV_Channel::k_throttleLeft, chan)) {
|
|
|
|
motor_mask |= 1U << chan;
|
|
|
|
}
|
|
|
|
if (SRV_Channels::find_channel(SRV_Channel::k_throttleRight, chan)) {
|
|
|
|
motor_mask |= 1U << chan;
|
|
|
|
}
|
2018-10-21 14:54:30 -03:00
|
|
|
|
|
|
|
// add parent's mask
|
2018-12-19 00:17:47 -04:00
|
|
|
motor_mask |= AP_MotorsMulticopter::get_motor_mask();
|
2018-10-21 14:54:30 -03:00
|
|
|
|
2018-12-19 00:17:47 -04:00
|
|
|
return motor_mask;
|
2018-10-21 14:54:30 -03:00
|
|
|
}
|
|
|
|
|
2017-02-10 01:26:12 -04:00
|
|
|
// calculate outputs to the motors
|
|
|
|
void AP_MotorsTailsitter::output_armed_stabilizing()
|
|
|
|
{
|
2018-10-21 14:54:30 -03:00
|
|
|
float roll_thrust; // roll thrust input value, +/- 1.0
|
|
|
|
float pitch_thrust; // pitch thrust input value, +/- 1.0
|
|
|
|
float yaw_thrust; // yaw thrust input value, +/- 1.0
|
|
|
|
float throttle_thrust; // throttle thrust input value, 0.0 - 1.0
|
|
|
|
float thrust_max; // highest motor value
|
2021-11-14 15:16:22 -04:00
|
|
|
float thrust_min; // lowest motor value
|
2018-10-21 14:54:30 -03:00
|
|
|
float thr_adj = 0.0f; // the difference between the pilot's desired throttle and throttle_thrust_best_rpy
|
|
|
|
|
|
|
|
// apply voltage and air pressure compensation
|
2023-01-30 21:54:00 -04:00
|
|
|
const float compensation_gain = thr_lin.get_compensation_gain();
|
2019-06-27 06:32:30 -03:00
|
|
|
roll_thrust = (_roll_in + _roll_in_ff) * compensation_gain;
|
2020-11-05 10:30:19 -04:00
|
|
|
pitch_thrust = _pitch_in + _pitch_in_ff;
|
|
|
|
yaw_thrust = _yaw_in + _yaw_in_ff;
|
2018-10-21 14:54:30 -03:00
|
|
|
throttle_thrust = get_throttle() * compensation_gain;
|
2021-11-14 15:16:22 -04:00
|
|
|
const float max_boost_throttle = _throttle_avg_max * compensation_gain;
|
|
|
|
|
|
|
|
// never boost above max, derived from throttle mix params
|
|
|
|
const float min_throttle_out = MIN(_external_min_throttle, max_boost_throttle);
|
|
|
|
const float max_throttle_out = _throttle_thrust_max * compensation_gain;
|
2018-10-21 14:54:30 -03:00
|
|
|
|
2021-11-14 15:16:22 -04:00
|
|
|
// sanity check throttle is above min and below current limited throttle
|
|
|
|
if (throttle_thrust <= min_throttle_out) {
|
|
|
|
throttle_thrust = min_throttle_out;
|
2017-02-10 01:26:12 -04:00
|
|
|
limit.throttle_lower = true;
|
|
|
|
}
|
2021-11-14 15:16:22 -04:00
|
|
|
if (throttle_thrust >= max_throttle_out) {
|
|
|
|
throttle_thrust = max_throttle_out;
|
2017-02-10 01:26:12 -04:00
|
|
|
limit.throttle_upper = true;
|
|
|
|
}
|
|
|
|
|
2021-11-14 15:16:22 -04:00
|
|
|
if (roll_thrust >= 1.0) {
|
|
|
|
// cannot split motor outputs by more than 1
|
|
|
|
roll_thrust = 1;
|
|
|
|
limit.roll = true;
|
|
|
|
}
|
|
|
|
|
2018-12-19 00:15:47 -04:00
|
|
|
// calculate left and right throttle outputs
|
2019-04-19 21:59:40 -03:00
|
|
|
_thrust_left = throttle_thrust + roll_thrust * 0.5f;
|
|
|
|
_thrust_right = throttle_thrust - roll_thrust * 0.5f;
|
2018-10-21 14:54:30 -03:00
|
|
|
|
|
|
|
thrust_max = MAX(_thrust_right,_thrust_left);
|
2021-11-14 15:16:22 -04:00
|
|
|
thrust_min = MIN(_thrust_right,_thrust_left);
|
2018-10-21 14:54:30 -03:00
|
|
|
if (thrust_max > 1.0f) {
|
2021-11-14 15:16:22 -04:00
|
|
|
// if max thrust is more than one reduce average throttle
|
2018-10-21 14:54:30 -03:00
|
|
|
thr_adj = 1.0f - thrust_max;
|
|
|
|
limit.throttle_upper = true;
|
2021-11-14 15:16:22 -04:00
|
|
|
} else if (thrust_min < 0.0) {
|
|
|
|
// if min thrust is less than 0 increase average throttle
|
|
|
|
// but never above max boost
|
|
|
|
thr_adj = -thrust_min;
|
|
|
|
if ((throttle_thrust + thr_adj) > max_boost_throttle) {
|
|
|
|
thr_adj = MAX(max_boost_throttle - throttle_thrust, 0.0);
|
|
|
|
// in this case we throw away some roll output, it will be uneven
|
|
|
|
// constraining the lower motor more than the upper
|
|
|
|
// this unbalances torque, but motor torque should have significantly less control power than tilts / control surfaces
|
|
|
|
// so its worth keeping the higher roll control power at a minor cost to yaw
|
|
|
|
limit.roll = true;
|
|
|
|
}
|
|
|
|
limit.throttle_lower = true;
|
2018-10-21 14:54:30 -03:00
|
|
|
}
|
|
|
|
|
2018-12-19 00:15:47 -04:00
|
|
|
// Add adjustment to reduce average throttle
|
2018-10-21 14:54:30 -03:00
|
|
|
_thrust_left = constrain_float(_thrust_left + thr_adj, 0.0f, 1.0f);
|
|
|
|
_thrust_right = constrain_float(_thrust_right + thr_adj, 0.0f, 1.0f);
|
2021-11-02 16:01:28 -03:00
|
|
|
|
|
|
|
_throttle = throttle_thrust;
|
|
|
|
|
2019-07-10 04:26:12 -03:00
|
|
|
// compensation_gain can never be zero
|
2021-11-14 15:16:22 -04:00
|
|
|
// ensure accurate representation of average throttle output, this value is used for notch tracking and control surface scaling
|
|
|
|
if (_has_diff_thrust) {
|
|
|
|
_throttle_out = (throttle_thrust + thr_adj) / compensation_gain;
|
|
|
|
} else {
|
|
|
|
_throttle_out = throttle_thrust / compensation_gain;
|
|
|
|
}
|
2018-10-21 14:54:30 -03:00
|
|
|
|
|
|
|
// thrust vectoring
|
|
|
|
_tilt_left = pitch_thrust - yaw_thrust;
|
|
|
|
_tilt_right = pitch_thrust + yaw_thrust;
|
2017-02-10 01:26:12 -04:00
|
|
|
}
|
|
|
|
|
2018-10-21 14:54:30 -03:00
|
|
|
// output_test_seq - 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
|
2022-01-27 11:37:06 -04:00
|
|
|
void AP_MotorsTailsitter::_output_test_seq(uint8_t motor_seq, int16_t pwm)
|
2018-10-21 14:54:30 -03:00
|
|
|
{
|
|
|
|
// output to motors and servos
|
|
|
|
switch (motor_seq) {
|
|
|
|
case 1:
|
2018-12-19 00:17:47 -04:00
|
|
|
// right throttle
|
|
|
|
SRV_Channels::set_output_pwm(SRV_Channel::k_throttleRight, pwm);
|
2018-10-21 14:54:30 -03:00
|
|
|
break;
|
|
|
|
case 2:
|
2018-12-19 00:17:47 -04:00
|
|
|
// right tilt servo
|
|
|
|
SRV_Channels::set_output_pwm(SRV_Channel::k_tiltMotorRight, pwm);
|
2018-10-21 14:54:30 -03:00
|
|
|
break;
|
|
|
|
case 3:
|
2018-12-19 00:17:47 -04:00
|
|
|
// left throttle
|
|
|
|
SRV_Channels::set_output_pwm(SRV_Channel::k_throttleLeft, pwm);
|
2018-10-21 14:54:30 -03:00
|
|
|
break;
|
|
|
|
case 4:
|
2018-12-19 00:17:47 -04:00
|
|
|
// left tilt servo
|
|
|
|
SRV_Channels::set_output_pwm(SRV_Channel::k_tiltMotorLeft, pwm);
|
2018-10-21 14:54:30 -03:00
|
|
|
break;
|
|
|
|
default:
|
|
|
|
// do nothing
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|