2013-10-02 06:59:04 -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/>.
|
|
|
|
*/
|
|
|
|
|
2015-08-11 03:28:44 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
2013-10-02 06:59:04 -03:00
|
|
|
#include "AP_MotorsSingle.h"
|
2017-01-03 05:56:57 -04:00
|
|
|
#include <GCS_MAVLink/GCS.h>
|
2023-01-24 17:39:44 -04:00
|
|
|
#include <SRV_Channel/SRV_Channel.h>
|
2013-10-02 06:59:04 -03:00
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
// init
|
2016-12-14 01:46:42 -04:00
|
|
|
void AP_MotorsSingle::init(motor_frame_class frame_class, motor_frame_type frame_type)
|
2013-10-02 06:59:04 -03:00
|
|
|
{
|
2018-05-20 22:37:38 -03:00
|
|
|
// make sure 6 output channels are mapped
|
2019-04-19 21:59:40 -03:00
|
|
|
for (uint8_t i = 0; i < 6; i++) {
|
|
|
|
add_motor_num(CH_1 + i);
|
2018-05-20 22:37:38 -03:00
|
|
|
}
|
2013-10-02 06:59:04 -03:00
|
|
|
|
2014-02-07 09:03:22 -04:00
|
|
|
// set the motor_enabled flag so that the main ESC can be calibrated like other frame types
|
2016-01-20 00:43:57 -04:00
|
|
|
motor_enabled[AP_MOTORS_MOT_5] = true;
|
|
|
|
motor_enabled[AP_MOTORS_MOT_6] = true;
|
2014-02-07 09:03:22 -04:00
|
|
|
|
2018-05-20 22:37:38 -03:00
|
|
|
// setup actuator scaling
|
2019-04-19 21:59:40 -03:00
|
|
|
for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
|
2018-05-20 22:37:38 -03:00
|
|
|
SRV_Channels::set_angle(SRV_Channels::get_motor_function(i), AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
2017-01-03 05:56:57 -04:00
|
|
|
}
|
2016-12-14 01:46:42 -04:00
|
|
|
|
2020-12-24 17:17:37 -04:00
|
|
|
_mav_type = MAV_TYPE_COAXIAL;
|
|
|
|
|
2016-12-14 01:46:42 -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_SINGLE);
|
2016-12-14 01:46:42 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
|
|
|
|
void AP_MotorsSingle::set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
|
|
|
|
{
|
2017-01-03 05:56:57 -04:00
|
|
|
// nothing to do
|
2013-10-02 06:59:04 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// set update rate to motors - a value in hertz
|
2019-04-19 21:59:40 -03:00
|
|
|
void AP_MotorsSingle::set_update_rate(uint16_t speed_hz)
|
2013-10-02 06:59:04 -03:00
|
|
|
{
|
|
|
|
// record requested speed
|
|
|
|
_speed_hz = speed_hz;
|
|
|
|
|
2017-01-09 03:31:56 -04:00
|
|
|
uint32_t mask =
|
2016-01-20 00:43:57 -04:00
|
|
|
1U << AP_MOTORS_MOT_5 |
|
|
|
|
1U << AP_MOTORS_MOT_6 ;
|
2017-01-09 03:31:56 -04:00
|
|
|
rc_set_freq(mask, _speed_hz);
|
2013-10-02 06:59:04 -03:00
|
|
|
}
|
|
|
|
|
2016-01-20 00:48:49 -04:00
|
|
|
void AP_MotorsSingle::output_to_motors()
|
|
|
|
{
|
2019-05-03 02:27:09 -03:00
|
|
|
if (!initialised_ok()) {
|
2017-01-03 05:56:57 -04:00
|
|
|
return;
|
|
|
|
}
|
2019-04-09 09:15:45 -03:00
|
|
|
switch (_spool_state) {
|
|
|
|
case SpoolState::SHUT_DOWN:
|
2016-01-20 00:48:49 -04:00
|
|
|
// sends minimum values out to the motors
|
2018-05-20 22:37:38 -03:00
|
|
|
rc_write_angle(AP_MOTORS_MOT_1, _roll_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
|
|
|
rc_write_angle(AP_MOTORS_MOT_2, _pitch_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
|
|
|
rc_write_angle(AP_MOTORS_MOT_3, -_roll_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
|
|
|
rc_write_angle(AP_MOTORS_MOT_4, -_pitch_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
2018-11-30 10:34:14 -04:00
|
|
|
rc_write(AP_MOTORS_MOT_5, output_to_pwm(0));
|
|
|
|
rc_write(AP_MOTORS_MOT_6, output_to_pwm(0));
|
2016-01-20 00:48:49 -04:00
|
|
|
break;
|
2019-04-09 09:15:45 -03:00
|
|
|
case SpoolState::GROUND_IDLE:
|
2016-01-20 00:48:49 -04:00
|
|
|
// sends output to motors when armed but not flying
|
2019-04-19 21:59:40 -03:00
|
|
|
for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
|
|
|
|
rc_write_angle(AP_MOTORS_MOT_1 + i, _spin_up_ratio * _actuator_out[i] * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
2018-05-20 22:37:38 -03:00
|
|
|
}
|
2023-01-27 16:18:52 -04:00
|
|
|
set_actuator_with_slew(_actuator[AP_MOTORS_MOT_5], actuator_spin_up_to_ground_idle());
|
|
|
|
set_actuator_with_slew(_actuator[AP_MOTORS_MOT_6], actuator_spin_up_to_ground_idle());
|
|
|
|
rc_write(AP_MOTORS_MOT_5, output_to_pwm(_actuator[AP_MOTORS_MOT_5]));
|
|
|
|
rc_write(AP_MOTORS_MOT_6, output_to_pwm(_actuator[AP_MOTORS_MOT_6]));
|
2016-01-20 00:48:49 -04:00
|
|
|
break;
|
2019-04-09 09:15:45 -03:00
|
|
|
case SpoolState::SPOOLING_UP:
|
|
|
|
case SpoolState::THROTTLE_UNLIMITED:
|
|
|
|
case SpoolState::SPOOLING_DOWN:
|
2016-01-20 00:48:49 -04:00
|
|
|
// set motor output based on thrust requests
|
2019-04-19 21:59:40 -03:00
|
|
|
for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
|
|
|
|
rc_write_angle(AP_MOTORS_MOT_1 + i, _actuator_out[i] * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
2018-05-20 22:37:38 -03:00
|
|
|
}
|
2023-01-30 21:54:00 -04:00
|
|
|
set_actuator_with_slew(_actuator[AP_MOTORS_MOT_5], thr_lin.thrust_to_actuator(_thrust_out));
|
|
|
|
set_actuator_with_slew(_actuator[AP_MOTORS_MOT_6], thr_lin.thrust_to_actuator(_thrust_out));
|
2023-01-27 16:18:52 -04:00
|
|
|
rc_write(AP_MOTORS_MOT_5, output_to_pwm(_actuator[AP_MOTORS_MOT_5]));
|
|
|
|
rc_write(AP_MOTORS_MOT_6, output_to_pwm(_actuator[AP_MOTORS_MOT_6]));
|
2016-01-20 00:48:49 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-07-26 04:28:10 -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
|
2021-12-10 12:45:20 -04:00
|
|
|
uint32_t AP_MotorsSingle::get_motor_mask()
|
2014-07-26 04:28:10 -03:00
|
|
|
{
|
2018-08-24 02:39:19 -03:00
|
|
|
uint32_t motor_mask =
|
2016-01-20 00:43:57 -04:00
|
|
|
1U << AP_MOTORS_MOT_5 |
|
|
|
|
1U << AP_MOTORS_MOT_6;
|
2018-08-24 02:39:19 -03:00
|
|
|
|
2021-12-10 12:45:20 -04:00
|
|
|
uint32_t mask = motor_mask_to_srv_channel_mask(motor_mask);
|
2018-08-24 02:39:19 -03:00
|
|
|
|
|
|
|
// add parent's mask
|
|
|
|
mask |= AP_MotorsMulticopter::get_motor_mask();
|
|
|
|
|
|
|
|
return mask;
|
2014-07-26 04:28:10 -03:00
|
|
|
}
|
|
|
|
|
2015-04-02 17:54:15 -03:00
|
|
|
// sends commands to the motors
|
|
|
|
void AP_MotorsSingle::output_armed_stabilizing()
|
2013-10-02 06:59:04 -03:00
|
|
|
{
|
2016-01-20 00:25:35 -04: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
|
2018-01-14 21:31:31 -04:00
|
|
|
float throttle_avg_max; // throttle thrust average maximum value, 0.0 - 1.0
|
2019-04-19 21:59:40 -03:00
|
|
|
float thrust_min_rpy; // the minimum throttle setting that will not limit the roll and pitch output
|
2016-01-20 00:25:35 -04:00
|
|
|
float thr_adj; // the difference between the pilot's desired throttle and throttle_thrust_best_rpy
|
2019-04-19 21:59:40 -03:00
|
|
|
float rp_scale = 1.0f; // this is used to scale the roll, pitch and yaw to fit within the motor limits
|
2016-01-20 00:25:35 -04:00
|
|
|
float actuator_allowed = 0.0f; // amount of yaw we can fit in
|
|
|
|
float actuator[NUM_ACTUATORS]; // combined roll, pitch and yaw thrusts for each actuator
|
|
|
|
float actuator_max = 0.0f; // maximum actuator value
|
|
|
|
|
|
|
|
// 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;
|
|
|
|
pitch_thrust = (_pitch_in + _pitch_in_ff) * compensation_gain;
|
|
|
|
yaw_thrust = (_yaw_in + _yaw_in_ff) * compensation_gain;
|
2018-01-24 03:42:10 -04:00
|
|
|
throttle_thrust = get_throttle() * compensation_gain;
|
|
|
|
throttle_avg_max = _throttle_avg_max * compensation_gain;
|
2016-01-20 00:25:35 -04:00
|
|
|
|
|
|
|
// sanity check throttle is above zero and below current limited throttle
|
|
|
|
if (throttle_thrust <= 0.0f) {
|
|
|
|
throttle_thrust = 0.0f;
|
2016-02-11 02:05:48 -04:00
|
|
|
limit.throttle_lower = true;
|
|
|
|
}
|
2016-01-20 00:25:35 -04:00
|
|
|
if (throttle_thrust >= _throttle_thrust_max) {
|
|
|
|
throttle_thrust = _throttle_thrust_max;
|
2014-10-04 11:29:02 -03:00
|
|
|
limit.throttle_upper = true;
|
|
|
|
}
|
2016-03-21 11:21:19 -03:00
|
|
|
|
2018-01-14 21:31:31 -04:00
|
|
|
throttle_avg_max = constrain_float(throttle_avg_max, throttle_thrust, _throttle_thrust_max);
|
2013-10-02 06:59:04 -03:00
|
|
|
|
2016-02-11 02:05:48 -04:00
|
|
|
float rp_thrust_max = MAX(fabsf(roll_thrust), fabsf(pitch_thrust));
|
|
|
|
|
2016-01-20 00:25:35 -04:00
|
|
|
// calculate how much roll and pitch must be scaled to leave enough range for the minimum yaw
|
2016-06-09 03:50:31 -03:00
|
|
|
if (is_zero(rp_thrust_max)) {
|
|
|
|
rp_scale = 1.0f;
|
2016-01-20 00:25:35 -04:00
|
|
|
} else {
|
2022-03-11 13:35:05 -04:00
|
|
|
rp_scale = constrain_float((1.0f - MIN(fabsf(yaw_thrust), (float) _yaw_headroom * 0.001f)) / rp_thrust_max, 0.0f, 1.0f);
|
2016-06-09 03:50:31 -03:00
|
|
|
if (rp_scale < 1.0f) {
|
2019-07-27 02:37:31 -03:00
|
|
|
limit.roll = true;
|
|
|
|
limit.pitch = true;
|
2016-02-11 02:05:48 -04:00
|
|
|
}
|
2016-01-20 00:25:35 -04:00
|
|
|
}
|
2016-02-11 02:05:48 -04:00
|
|
|
|
2016-06-09 03:50:31 -03:00
|
|
|
actuator_allowed = 1.0f - rp_scale * rp_thrust_max;
|
2016-02-11 02:05:48 -04:00
|
|
|
if (fabsf(yaw_thrust) > actuator_allowed) {
|
2016-01-20 00:25:35 -04:00
|
|
|
yaw_thrust = constrain_float(yaw_thrust, -actuator_allowed, actuator_allowed);
|
|
|
|
limit.yaw = true;
|
|
|
|
}
|
2013-10-02 06:59:04 -03:00
|
|
|
|
2016-01-20 00:25:35 -04:00
|
|
|
// combine roll, pitch and yaw on each actuator
|
2014-02-09 04:49:52 -04:00
|
|
|
// front servo
|
2016-06-09 03:50:31 -03:00
|
|
|
actuator[0] = rp_scale * roll_thrust - yaw_thrust;
|
2014-02-09 04:49:52 -04:00
|
|
|
// right servo
|
2016-06-09 03:50:31 -03:00
|
|
|
actuator[1] = rp_scale * pitch_thrust - yaw_thrust;
|
2014-02-09 04:49:52 -04:00
|
|
|
// rear servo
|
2016-06-09 03:50:31 -03:00
|
|
|
actuator[2] = -rp_scale * roll_thrust - yaw_thrust;
|
2014-02-09 04:49:52 -04:00
|
|
|
// left servo
|
2016-06-09 03:50:31 -03:00
|
|
|
actuator[3] = -rp_scale * pitch_thrust - yaw_thrust;
|
2016-01-20 00:25:35 -04:00
|
|
|
|
|
|
|
// calculate the minimum thrust that doesn't limit the roll, pitch and yaw forces
|
2016-06-09 03:50:31 -03:00
|
|
|
thrust_min_rpy = MAX(MAX(fabsf(actuator[0]), fabsf(actuator[1])), MAX(fabsf(actuator[2]), fabsf(actuator[3])));
|
2016-01-20 00:25:35 -04:00
|
|
|
|
2018-01-14 21:31:31 -04:00
|
|
|
thr_adj = throttle_thrust - throttle_avg_max;
|
|
|
|
if (thr_adj < (thrust_min_rpy - throttle_avg_max)) {
|
2016-01-20 00:25:35 -04:00
|
|
|
// Throttle can't be reduced to the desired level because this would mean roll or pitch control
|
|
|
|
// would not be able to reach the desired level because of lack of thrust.
|
2018-01-14 21:31:31 -04:00
|
|
|
thr_adj = MIN(thrust_min_rpy, throttle_avg_max) - throttle_avg_max;
|
2016-01-20 00:25:35 -04:00
|
|
|
}
|
2013-10-02 06:59:04 -03:00
|
|
|
|
2016-01-20 00:25:35 -04:00
|
|
|
// calculate the throttle setting for the lift fan
|
2018-01-14 21:31:31 -04:00
|
|
|
_thrust_out = throttle_avg_max + thr_adj;
|
2019-07-10 04:26:12 -03:00
|
|
|
// compensation_gain can never be zero
|
|
|
|
_throttle_out = _thrust_out / compensation_gain;
|
2016-01-20 00:25:35 -04:00
|
|
|
|
2016-02-11 02:05:48 -04:00
|
|
|
if (is_zero(_thrust_out)) {
|
2019-07-27 02:37:31 -03:00
|
|
|
limit.roll = true;
|
|
|
|
limit.pitch = true;
|
2016-01-20 00:25:35 -04:00
|
|
|
limit.yaw = true;
|
2016-06-29 08:56:33 -03:00
|
|
|
}
|
2016-05-28 09:39:42 -03:00
|
|
|
|
2016-06-29 08:56:33 -03:00
|
|
|
// limit thrust out for calculation of actuator gains
|
2019-04-19 21:59:40 -03:00
|
|
|
float thrust_out_actuator = constrain_float(MAX(_throttle_hover * 0.5f, _thrust_out), 0.5f, 1.0f);
|
2016-05-28 09:39:42 -03:00
|
|
|
|
2016-06-29 08:56:33 -03:00
|
|
|
// calculate the maximum allowed actuator output and maximum requested actuator output
|
2019-04-19 21:59:40 -03:00
|
|
|
for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
|
2016-06-29 08:56:33 -03:00
|
|
|
if (actuator_max > fabsf(actuator[i])) {
|
|
|
|
actuator_max = fabsf(actuator[i]);
|
2016-01-20 00:25:35 -04:00
|
|
|
}
|
|
|
|
}
|
2016-06-29 08:56:33 -03:00
|
|
|
if (actuator_max > thrust_out_actuator && !is_zero(actuator_max)) {
|
|
|
|
// roll, pitch and yaw request can not be achieved at full servo defection
|
|
|
|
// reduce roll, pitch and yaw to reduce the requested defection to maximum
|
2019-07-27 02:37:31 -03:00
|
|
|
limit.roll = true;
|
|
|
|
limit.pitch = true;
|
2016-06-29 08:56:33 -03:00
|
|
|
limit.yaw = true;
|
2019-04-19 21:59:40 -03:00
|
|
|
rp_scale = thrust_out_actuator / actuator_max;
|
2016-06-29 08:56:33 -03:00
|
|
|
} else {
|
|
|
|
rp_scale = 1.0f;
|
|
|
|
}
|
|
|
|
|
|
|
|
// force of a lifting surface is approximately equal to the angle of attack times the airflow velocity squared
|
|
|
|
// static thrust is proportional to the airflow velocity squared
|
|
|
|
// therefore the torque of the roll and pitch actuators should be approximately proportional to
|
|
|
|
// the angle of attack multiplied by the static thrust.
|
2019-04-19 21:59:40 -03:00
|
|
|
for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
|
|
|
|
_actuator_out[i] = constrain_float(rp_scale * actuator[i] / thrust_out_actuator, -1.0f, 1.0f);
|
2016-06-29 08:56:33 -03:00
|
|
|
}
|
2013-10-02 06:59:04 -03:00
|
|
|
}
|
|
|
|
|
2018-04-27 13:22:07 -03:00
|
|
|
// output_test_seq - spin a motor at the pwm value specified
|
2014-04-28 04:30:02 -03:00
|
|
|
// 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_MotorsSingle::_output_test_seq(uint8_t motor_seq, int16_t pwm)
|
2013-10-02 06:59:04 -03:00
|
|
|
{
|
2014-04-28 04:30:02 -03:00
|
|
|
// output to motors and servos
|
|
|
|
switch (motor_seq) {
|
|
|
|
case 1:
|
|
|
|
// flap servo 1
|
2016-01-04 01:56:54 -04:00
|
|
|
rc_write(AP_MOTORS_MOT_1, pwm);
|
2014-04-28 04:30:02 -03:00
|
|
|
break;
|
|
|
|
case 2:
|
|
|
|
// flap servo 2
|
2016-01-04 01:56:54 -04:00
|
|
|
rc_write(AP_MOTORS_MOT_2, pwm);
|
2014-04-28 04:30:02 -03:00
|
|
|
break;
|
|
|
|
case 3:
|
|
|
|
// flap servo 3
|
2016-01-04 01:56:54 -04:00
|
|
|
rc_write(AP_MOTORS_MOT_3, pwm);
|
2014-04-28 04:30:02 -03:00
|
|
|
break;
|
|
|
|
case 4:
|
|
|
|
// flap servo 4
|
2016-01-04 01:56:54 -04:00
|
|
|
rc_write(AP_MOTORS_MOT_4, pwm);
|
2014-04-28 04:30:02 -03:00
|
|
|
break;
|
|
|
|
case 5:
|
2016-01-20 00:43:57 -04:00
|
|
|
// spin motor 1
|
|
|
|
rc_write(AP_MOTORS_MOT_5, pwm);
|
|
|
|
break;
|
|
|
|
case 6:
|
|
|
|
// spin motor 2
|
|
|
|
rc_write(AP_MOTORS_MOT_6, pwm);
|
2014-04-28 04:30:02 -03:00
|
|
|
break;
|
|
|
|
default:
|
|
|
|
// do nothing
|
|
|
|
break;
|
|
|
|
}
|
2013-10-02 06:59:04 -03:00
|
|
|
}
|