2016-05-01 05:07:52 -03:00
|
|
|
#include "Plane.h"
|
|
|
|
|
|
|
|
/*
|
|
|
|
control code for tiltrotors and tiltwings. Enabled by setting
|
|
|
|
Q_TILT_MASK to a non-zero value
|
|
|
|
*/
|
|
|
|
|
|
|
|
|
2017-02-24 06:05:27 -04:00
|
|
|
/*
|
|
|
|
calculate maximum tilt change as a proportion from 0 to 1 of tilt
|
|
|
|
*/
|
|
|
|
float QuadPlane::tilt_max_change(bool up)
|
|
|
|
{
|
|
|
|
float rate;
|
|
|
|
if (up || tilt.max_rate_down_dps <= 0) {
|
|
|
|
rate = tilt.max_rate_up_dps;
|
|
|
|
} else {
|
|
|
|
rate = tilt.max_rate_down_dps;
|
|
|
|
}
|
2017-04-16 22:31:57 -03:00
|
|
|
if (tilt.tilt_type != TILT_TYPE_BINARY && !up) {
|
2017-04-23 00:46:08 -03:00
|
|
|
bool fast_tilt = false;
|
2019-01-15 13:46:13 -04:00
|
|
|
if (plane.control_mode == &plane.mode_manual) {
|
2017-04-23 00:46:08 -03:00
|
|
|
fast_tilt = true;
|
|
|
|
}
|
|
|
|
if (hal.util->get_soft_armed() && !in_vtol_mode() && !assisted_flight) {
|
|
|
|
fast_tilt = true;
|
|
|
|
}
|
|
|
|
if (fast_tilt) {
|
2017-04-16 22:31:57 -03:00
|
|
|
// allow a minimum of 90 DPS in manual or if we are not
|
|
|
|
// stabilising, to give fast control
|
|
|
|
rate = MAX(rate, 90);
|
|
|
|
}
|
2017-02-24 06:05:27 -04:00
|
|
|
}
|
|
|
|
return rate * plane.G_Dt / 90.0f;
|
|
|
|
}
|
|
|
|
|
2016-05-01 05:07:52 -03:00
|
|
|
/*
|
|
|
|
output a slew limited tiltrotor angle. tilt is from 0 to 1
|
|
|
|
*/
|
|
|
|
void QuadPlane::tiltrotor_slew(float newtilt)
|
|
|
|
{
|
2017-02-24 06:05:27 -04:00
|
|
|
float max_change = tilt_max_change(newtilt<tilt.current_tilt);
|
2016-05-01 05:07:52 -03:00
|
|
|
tilt.current_tilt = constrain_float(newtilt, tilt.current_tilt-max_change, tilt.current_tilt+max_change);
|
2016-05-01 20:33:54 -03:00
|
|
|
|
2016-05-01 05:07:52 -03:00
|
|
|
// translate to 0..1000 range and output
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_motor_tilt, 1000 * tilt.current_tilt);
|
2016-05-01 05:07:52 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
2016-07-03 09:02:38 -03:00
|
|
|
update motor tilt for continuous tilt servos
|
2016-05-01 05:07:52 -03:00
|
|
|
*/
|
2016-07-03 09:02:38 -03:00
|
|
|
void QuadPlane::tiltrotor_continuous_update(void)
|
2016-05-01 05:07:52 -03:00
|
|
|
{
|
2016-05-01 20:33:54 -03:00
|
|
|
// default to inactive
|
|
|
|
tilt.motors_active = false;
|
|
|
|
|
2016-05-01 05:07:52 -03:00
|
|
|
// the maximum rate of throttle change
|
2017-02-24 06:05:27 -04:00
|
|
|
float max_change;
|
2016-05-01 05:07:52 -03:00
|
|
|
|
2017-04-23 01:04:57 -03:00
|
|
|
if (!in_vtol_mode() && (!hal.util->get_soft_armed() || !assisted_flight)) {
|
2016-05-01 05:07:52 -03:00
|
|
|
// we are in pure fixed wing mode. Move the tiltable motors all the way forward and run them as
|
|
|
|
// a forward motor
|
|
|
|
tiltrotor_slew(1);
|
|
|
|
|
2017-02-24 06:05:27 -04:00
|
|
|
max_change = tilt_max_change(false);
|
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
float new_throttle = constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)*0.01, 0, 1);
|
2016-05-01 05:07:52 -03:00
|
|
|
if (tilt.current_tilt < 1) {
|
|
|
|
tilt.current_throttle = constrain_float(new_throttle,
|
|
|
|
tilt.current_throttle-max_change,
|
|
|
|
tilt.current_throttle+max_change);
|
|
|
|
} else {
|
|
|
|
tilt.current_throttle = new_throttle;
|
|
|
|
}
|
|
|
|
if (!hal.util->get_soft_armed()) {
|
|
|
|
tilt.current_throttle = 0;
|
|
|
|
} else {
|
2020-01-19 12:46:36 -04:00
|
|
|
// prevent motor shutdown
|
|
|
|
tilt.motors_active = true;
|
|
|
|
}
|
|
|
|
if (!motor_test.running) {
|
2016-07-03 19:46:21 -03:00
|
|
|
// the motors are all the way forward, start using them for fwd thrust
|
|
|
|
uint8_t mask = is_zero(tilt.current_throttle)?0:(uint8_t)tilt.tilt_mask.get();
|
2018-12-29 11:42:53 -04:00
|
|
|
motors->output_motor_mask(tilt.current_throttle, mask, plane.rudder_dt);
|
2016-05-01 05:07:52 -03:00
|
|
|
}
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// remember the throttle level we're using for VTOL flight
|
2017-02-24 06:05:27 -04:00
|
|
|
float motors_throttle = motors->get_throttle();
|
|
|
|
max_change = tilt_max_change(motors_throttle<tilt.current_throttle);
|
|
|
|
tilt.current_throttle = constrain_float(motors_throttle,
|
2016-05-01 05:07:52 -03:00
|
|
|
tilt.current_throttle-max_change,
|
|
|
|
tilt.current_throttle+max_change);
|
2020-06-09 19:05:07 -03:00
|
|
|
|
2016-05-01 05:07:52 -03:00
|
|
|
/*
|
|
|
|
we are in a VTOL mode. We need to work out how much tilt is
|
2020-06-09 19:05:07 -03:00
|
|
|
needed. There are 4 strategies we will use:
|
2016-05-01 05:07:52 -03:00
|
|
|
|
2020-06-09 19:05:07 -03:00
|
|
|
1) without manual forward throttle control, the angle will be set to zero
|
|
|
|
in QAUTOTUNE QACRO, QSTABILIZE and QHOVER. This
|
2016-05-01 05:07:52 -03:00
|
|
|
enables these modes to be used as a safe recovery mode.
|
|
|
|
|
2020-06-09 19:05:07 -03:00
|
|
|
2) with manual forward throttle control we will set the angle based on
|
|
|
|
the demanded forward throttle via RC input.
|
|
|
|
|
|
|
|
3) in fixed wing assisted flight or velocity controlled modes we
|
2016-05-01 05:07:52 -03:00
|
|
|
will set the angle based on the demanded forward throttle,
|
|
|
|
with a maximum tilt given by Q_TILT_MAX. This relies on
|
2020-06-09 19:05:07 -03:00
|
|
|
Q_VFWD_GAIN being set.
|
2016-05-01 05:07:52 -03:00
|
|
|
|
2020-06-09 19:05:07 -03:00
|
|
|
4) if we are in TRANSITION_TIMER mode then we are transitioning
|
2016-05-01 05:07:52 -03:00
|
|
|
to forward flight and should put the rotors all the way forward
|
|
|
|
*/
|
2020-06-09 19:05:07 -03:00
|
|
|
|
|
|
|
if (plane.control_mode == &plane.mode_qautotune) {
|
2016-05-01 05:07:52 -03:00
|
|
|
tiltrotor_slew(0);
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2020-06-09 19:05:07 -03:00
|
|
|
// if not in assisted flight and in QACRO, QSTABILIZE or QHOVER mode
|
|
|
|
if (!assisted_flight &&
|
|
|
|
(plane.control_mode == &plane.mode_qacro ||
|
|
|
|
plane.control_mode == &plane.mode_qstabilize ||
|
|
|
|
plane.control_mode == &plane.mode_qhover)) {
|
|
|
|
if (rc_fwd_thr_ch == nullptr) {
|
|
|
|
// no manual throttle control, set angle to zero
|
|
|
|
tiltrotor_slew(0);
|
|
|
|
} else {
|
|
|
|
// manual control of forward throttle
|
|
|
|
float settilt = .01f * forward_throttle_pct();
|
|
|
|
tiltrotor_slew(settilt);
|
|
|
|
}
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2016-05-01 05:07:52 -03:00
|
|
|
if (assisted_flight &&
|
|
|
|
transition_state >= TRANSITION_TIMER) {
|
|
|
|
// we are transitioning to fixed wing - tilt the motors all
|
|
|
|
// the way forward
|
|
|
|
tiltrotor_slew(1);
|
|
|
|
} else {
|
2016-05-01 20:33:54 -03:00
|
|
|
// until we have completed the transition we limit the tilt to
|
|
|
|
// Q_TILT_MAX. Anything above 50% throttle gets
|
|
|
|
// Q_TILT_MAX. Below 50% throttle we decrease linearly. This
|
|
|
|
// relies heavily on Q_VFWD_GAIN being set appropriately.
|
2016-10-22 07:27:57 -03:00
|
|
|
float settilt = constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) / 50.0f, 0, 1);
|
2016-05-01 05:07:52 -03:00
|
|
|
tiltrotor_slew(settilt * tilt.max_angle_deg / 90.0f);
|
|
|
|
}
|
|
|
|
}
|
2016-05-08 20:11:11 -03:00
|
|
|
|
|
|
|
|
2016-07-03 09:02:38 -03:00
|
|
|
/*
|
|
|
|
output a slew limited tiltrotor angle. tilt is 0 or 1
|
|
|
|
*/
|
|
|
|
void QuadPlane::tiltrotor_binary_slew(bool forward)
|
|
|
|
{
|
2019-05-01 19:44:00 -03:00
|
|
|
// The servo output is binary, not slew rate limited
|
2017-01-22 18:29:51 -04:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_motor_tilt, forward?1000:0);
|
2016-07-03 09:02:38 -03:00
|
|
|
|
2019-05-01 19:44:00 -03:00
|
|
|
// rate limiting current_tilt has the effect of delaying throttle in tiltrotor_binary_update
|
2017-02-24 06:05:27 -04:00
|
|
|
float max_change = tilt_max_change(!forward);
|
2016-07-03 09:02:38 -03:00
|
|
|
if (forward) {
|
|
|
|
tilt.current_tilt = constrain_float(tilt.current_tilt+max_change, 0, 1);
|
|
|
|
} else {
|
|
|
|
tilt.current_tilt = constrain_float(tilt.current_tilt-max_change, 0, 1);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
update motor tilt for binary tilt servos
|
|
|
|
*/
|
|
|
|
void QuadPlane::tiltrotor_binary_update(void)
|
|
|
|
{
|
|
|
|
// motors always active
|
|
|
|
tilt.motors_active = true;
|
|
|
|
|
|
|
|
if (!in_vtol_mode()) {
|
|
|
|
// we are in pure fixed wing mode. Move the tiltable motors
|
|
|
|
// all the way forward and run them as a forward motor
|
|
|
|
tiltrotor_binary_slew(true);
|
|
|
|
|
2017-01-22 18:29:51 -04:00
|
|
|
float new_throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)*0.01f;
|
2016-07-03 09:02:38 -03:00
|
|
|
if (tilt.current_tilt >= 1) {
|
2016-07-03 19:46:21 -03:00
|
|
|
uint8_t mask = is_zero(new_throttle)?0:(uint8_t)tilt.tilt_mask.get();
|
2016-07-03 09:02:38 -03:00
|
|
|
// the motors are all the way forward, start using them for fwd thrust
|
2018-12-29 11:42:53 -04:00
|
|
|
motors->output_motor_mask(new_throttle, mask, plane.rudder_dt);
|
2016-07-03 09:02:38 -03:00
|
|
|
}
|
|
|
|
} else {
|
|
|
|
tiltrotor_binary_slew(false);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
update motor tilt
|
|
|
|
*/
|
|
|
|
void QuadPlane::tiltrotor_update(void)
|
|
|
|
{
|
|
|
|
if (tilt.tilt_mask <= 0) {
|
|
|
|
// no motors to tilt
|
|
|
|
return;
|
|
|
|
}
|
2017-04-22 22:35:25 -03:00
|
|
|
|
2016-07-03 09:02:38 -03:00
|
|
|
if (tilt.tilt_type == TILT_TYPE_BINARY) {
|
|
|
|
tiltrotor_binary_update();
|
|
|
|
} else {
|
|
|
|
tiltrotor_continuous_update();
|
|
|
|
}
|
2017-04-22 22:35:25 -03:00
|
|
|
|
|
|
|
if (tilt.tilt_type == TILT_TYPE_VECTORED_YAW) {
|
|
|
|
tiltrotor_vectored_yaw();
|
|
|
|
}
|
2016-07-03 09:02:38 -03:00
|
|
|
}
|
|
|
|
|
2016-05-08 20:11:11 -03:00
|
|
|
/*
|
2020-12-03 02:42:39 -04:00
|
|
|
tilt compensation for angle of tilt. When the rotors are tilted the
|
|
|
|
roll effect of differential thrust on the tilted rotors is decreased
|
|
|
|
and the yaw effect increased
|
|
|
|
We have two factors we apply.
|
2016-05-08 20:11:11 -03:00
|
|
|
|
2020-12-03 02:42:39 -04:00
|
|
|
1) when we are transitioning to fwd flight we scale the tilted rotors by 1/cos(angle). This pushes us towards more flight speed
|
|
|
|
|
|
|
|
2) when we are transitioning to hover we scale the non-tilted rotors by cos(angle). This pushes us towards lower fwd thrust
|
|
|
|
|
|
|
|
We also apply an equalisation to the tilted motors in proportion to
|
|
|
|
how much tilt we have. This smoothly reduces the impact of the roll
|
|
|
|
gains as we tilt further forward.
|
2016-05-08 20:11:11 -03:00
|
|
|
|
2020-12-03 02:42:39 -04:00
|
|
|
For yaw, we apply differential thrust in proportion to the demanded
|
|
|
|
yaw control and sin of the tilt angle
|
|
|
|
|
|
|
|
Finally we ensure no requested thrust is over 1 by scaling back all
|
|
|
|
motors so the largest thrust is at most 1.0
|
|
|
|
*/
|
|
|
|
void QuadPlane::tilt_compensate_angle(float *thrust, uint8_t num_motors, float non_tilted_mul, float tilted_mul)
|
|
|
|
{
|
2016-05-08 20:11:11 -03:00
|
|
|
float tilt_total = 0;
|
|
|
|
uint8_t tilt_count = 0;
|
|
|
|
|
2020-12-03 02:42:39 -04:00
|
|
|
// apply tilt_factors first
|
2016-05-08 20:11:11 -03:00
|
|
|
for (uint8_t i=0; i<num_motors; i++) {
|
2020-12-03 02:42:39 -04:00
|
|
|
if (!is_motor_tilting(i)) {
|
|
|
|
thrust[i] *= non_tilted_mul;
|
|
|
|
} else {
|
|
|
|
thrust[i] *= tilted_mul;
|
2016-05-08 20:11:11 -03:00
|
|
|
tilt_total += thrust[i];
|
|
|
|
tilt_count++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
float largest_tilted = 0;
|
2020-12-03 02:42:39 -04:00
|
|
|
const float sin_tilt = sinf(radians(tilt.current_tilt*90));
|
|
|
|
// yaw_gain relates the amount of differential thrust we get from
|
|
|
|
// tilt, so that the scaling of the yaw control is the same at any
|
|
|
|
// tilt angle
|
|
|
|
const float yaw_gain = sinf(radians(tilt.tilt_yaw_angle));
|
|
|
|
const float avg_tilt_thrust = tilt_total / tilt_count;
|
2016-05-08 20:11:11 -03:00
|
|
|
|
|
|
|
for (uint8_t i=0; i<num_motors; i++) {
|
2017-03-13 07:53:22 -03:00
|
|
|
if (is_motor_tilting(i)) {
|
2020-12-03 02:42:39 -04:00
|
|
|
// as we tilt we need to reduce the impact of the roll
|
|
|
|
// controller. This simple method keeps the same average,
|
|
|
|
// but moves us to no roll control as the angle increases
|
|
|
|
thrust[i] = tilt.current_tilt * avg_tilt_thrust + thrust[i] * (1-tilt.current_tilt);
|
|
|
|
// add in differential thrust for yaw control, scaled by tilt angle
|
|
|
|
const float diff_thrust = motors->get_roll_factor(i) * motors->get_yaw() * sin_tilt * yaw_gain;
|
|
|
|
thrust[i] += diff_thrust;
|
2016-05-08 20:11:11 -03:00
|
|
|
largest_tilted = MAX(largest_tilted, thrust[i]);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2020-12-03 02:42:39 -04:00
|
|
|
// if we are saturating one of the motors then reduce all motors
|
|
|
|
// to keep them in proportion to the original thrust. This helps
|
|
|
|
// maintain stability when tilted at a large angle
|
2016-05-08 20:11:11 -03:00
|
|
|
if (largest_tilted > 1.0f) {
|
|
|
|
float scale = 1.0f / largest_tilted;
|
|
|
|
for (uint8_t i=0; i<num_motors; i++) {
|
|
|
|
thrust[i] *= scale;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2017-01-22 22:06:31 -04:00
|
|
|
|
2017-03-13 07:53:22 -03:00
|
|
|
/*
|
|
|
|
choose up or down tilt compensation based on flight mode When going
|
|
|
|
to a fixed wing mode we use tilt_compensate_down, when going to a
|
|
|
|
VTOL mode we use tilt_compensate_up
|
|
|
|
*/
|
|
|
|
void QuadPlane::tilt_compensate(float *thrust, uint8_t num_motors)
|
|
|
|
{
|
|
|
|
if (tilt.current_tilt <= 0) {
|
|
|
|
// the motors are not tilted, no compensation needed
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (in_vtol_mode()) {
|
|
|
|
// we are transitioning to VTOL flight
|
2020-12-03 02:42:39 -04:00
|
|
|
const float tilt_factor = cosf(radians(tilt.current_tilt*90));
|
|
|
|
tilt_compensate_angle(thrust, num_motors, tilt_factor, 1);
|
2017-03-13 07:53:22 -03:00
|
|
|
} else {
|
2020-12-03 02:42:39 -04:00
|
|
|
float inv_tilt_factor;
|
|
|
|
if (tilt.current_tilt > 0.98f) {
|
|
|
|
inv_tilt_factor = 1.0 / cosf(radians(0.98f*90));
|
|
|
|
} else {
|
|
|
|
inv_tilt_factor = 1.0 / cosf(radians(tilt.current_tilt*90));
|
|
|
|
}
|
|
|
|
tilt_compensate_angle(thrust, num_motors, 1, inv_tilt_factor);
|
2017-03-13 07:53:22 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-01-22 22:06:31 -04:00
|
|
|
/*
|
|
|
|
return true if the rotors are fully tilted forward
|
|
|
|
*/
|
|
|
|
bool QuadPlane::tiltrotor_fully_fwd(void)
|
|
|
|
{
|
|
|
|
if (tilt.tilt_mask <= 0) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return (tilt.current_tilt >= 1);
|
|
|
|
}
|
2017-04-22 22:35:25 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
control vectored yaw with tilt multicopters
|
|
|
|
*/
|
|
|
|
void QuadPlane::tiltrotor_vectored_yaw(void)
|
|
|
|
{
|
|
|
|
// total angle the tilt can go through
|
|
|
|
float total_angle = 90 + tilt.tilt_yaw_angle;
|
|
|
|
// output value (0 to 1) to get motors pointed straight up
|
|
|
|
float zero_out = tilt.tilt_yaw_angle / total_angle;
|
|
|
|
|
|
|
|
// calculate the basic tilt amount from current_tilt
|
|
|
|
float base_output = zero_out + (tilt.current_tilt * (1 - zero_out));
|
2020-06-11 12:15:56 -03:00
|
|
|
|
|
|
|
// for testing when disarmed, apply vectored yaw in proportion to rudder stick
|
|
|
|
// Wait TILT_DELAY_MS after disarming to allow props to spin down first.
|
|
|
|
constexpr uint32_t TILT_DELAY_MS = 3000;
|
|
|
|
uint32_t now = AP_HAL::millis();
|
|
|
|
if (!hal.util->get_soft_armed() && (plane.quadplane.options & OPTION_DISARMED_TILT)) {
|
|
|
|
// this test is subject to wrapping at ~49 days, but the consequences are insignificant
|
|
|
|
if ((now - hal.util->get_last_armed_change()) > TILT_DELAY_MS) {
|
|
|
|
float yaw_out = plane.channel_rudder->get_control_in();
|
|
|
|
yaw_out /= plane.channel_rudder->get_range();
|
|
|
|
float yaw_range = zero_out;
|
|
|
|
|
2020-12-03 02:42:39 -04:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft, 1000 * constrain_float(base_output + yaw_out * yaw_range,0,1));
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRight, 1000 * constrain_float(base_output - yaw_out * yaw_range,0,1));
|
2020-12-18 06:54:08 -04:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRear, 1000 * constrain_float(base_output,0,1));
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRearLeft, 1000 * constrain_float(base_output + yaw_out * yaw_range,0,1));
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRearRight, 1000 * constrain_float(base_output - yaw_out * yaw_range,0,1));
|
2020-06-11 12:15:56 -03:00
|
|
|
}
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2017-04-22 22:35:25 -03:00
|
|
|
float tilt_threshold = (tilt.max_angle_deg/90.0f);
|
|
|
|
bool no_yaw = (tilt.current_tilt > tilt_threshold);
|
|
|
|
if (no_yaw) {
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft, 1000 * base_output);
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRight, 1000 * base_output);
|
2020-12-18 06:54:08 -04:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRear, 1000 * base_output);
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRearLeft, 1000 * base_output);
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRearRight, 1000 * base_output);
|
2017-04-22 22:35:25 -03:00
|
|
|
} else {
|
2020-12-03 02:42:39 -04:00
|
|
|
const float yaw_out = motors->get_yaw();
|
|
|
|
const float roll_out = motors->get_roll();
|
2017-04-22 22:35:25 -03:00
|
|
|
float yaw_range = zero_out;
|
|
|
|
|
2020-12-03 02:42:39 -04:00
|
|
|
// now apply vectored thrust for yaw and roll.
|
|
|
|
const float tilt_rad = radians(tilt.current_tilt*90);
|
|
|
|
const float sin_tilt = sinf(tilt_rad);
|
|
|
|
const float cos_tilt = cosf(tilt_rad);
|
|
|
|
// the MotorsMatrix library normalises roll factor to 0.5, so
|
|
|
|
// we need to use the same factor here to keep the same roll
|
|
|
|
// gains when tilted as we have when not tilted
|
|
|
|
const float avg_roll_factor = 0.5;
|
|
|
|
const float tilt_offset = constrain_float(yaw_out * cos_tilt + avg_roll_factor * roll_out * sin_tilt, -1, 1);
|
|
|
|
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft, 1000 * constrain_float(base_output + tilt_offset * yaw_range,0,1));
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRight, 1000 * constrain_float(base_output - tilt_offset * yaw_range,0,1));
|
2020-12-18 06:54:08 -04:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRear, 1000 * constrain_float(base_output,0,1));
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRearLeft, 1000 * constrain_float(base_output + tilt_offset * yaw_range,0,1));
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRearRight, 1000 * constrain_float(base_output - tilt_offset * yaw_range,0,1));
|
2017-04-22 22:35:25 -03:00
|
|
|
}
|
|
|
|
}
|
2019-03-18 21:00:25 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
control bicopter tiltrotors
|
|
|
|
*/
|
|
|
|
void QuadPlane::tiltrotor_bicopter(void)
|
|
|
|
{
|
2020-01-19 12:46:36 -04:00
|
|
|
if (tilt.tilt_type != TILT_TYPE_BICOPTER || motor_test.running) {
|
|
|
|
// don't override motor test with motors_output
|
2019-03-18 21:00:25 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (!in_vtol_mode() && tiltrotor_fully_fwd()) {
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft, -SERVO_MAX);
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRight, -SERVO_MAX);
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
float throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
|
|
|
|
if (assisted_flight) {
|
|
|
|
hold_stabilize(throttle * 0.01f);
|
|
|
|
motors_output(true);
|
|
|
|
} else {
|
|
|
|
motors_output(false);
|
|
|
|
}
|
|
|
|
|
|
|
|
// bicopter assumes that trim is up so we scale down so match
|
|
|
|
float tilt_left = SRV_Channels::get_output_scaled(SRV_Channel::k_tiltMotorLeft);
|
|
|
|
float tilt_right = SRV_Channels::get_output_scaled(SRV_Channel::k_tiltMotorRight);
|
|
|
|
|
|
|
|
if (is_negative(tilt_left)) {
|
|
|
|
tilt_left *= tilt.tilt_yaw_angle / 90.0f;
|
|
|
|
}
|
|
|
|
if (is_negative(tilt_right)) {
|
|
|
|
tilt_right *= tilt.tilt_yaw_angle / 90.0f;
|
|
|
|
}
|
|
|
|
|
|
|
|
// reduce authority of bicopter as motors are tilted forwards
|
|
|
|
const float scaling = cosf(tilt.current_tilt * M_PI_2);
|
|
|
|
tilt_left *= scaling;
|
|
|
|
tilt_right *= scaling;
|
|
|
|
|
|
|
|
// add current tilt and constrain
|
|
|
|
tilt_left = constrain_float(-(tilt.current_tilt * SERVO_MAX) + tilt_left, -SERVO_MAX, SERVO_MAX);
|
|
|
|
tilt_right = constrain_float(-(tilt.current_tilt * SERVO_MAX) + tilt_right, -SERVO_MAX, SERVO_MAX);
|
|
|
|
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft, tilt_left);
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRight, tilt_right);
|
|
|
|
}
|