mirror of https://github.com/ArduPilot/ardupilot
Plane: added support for rear motor tilt
needed for X8 tilt tri test aircraft for this PR
This commit is contained in:
parent
7f3a851dd3
commit
8e3c6124eb
|
@ -766,6 +766,9 @@ bool QuadPlane::setup(void)
|
|||
// setup tilt servos for vectored yaw
|
||||
SRV_Channels::set_range(SRV_Channel::k_tiltMotorLeft, 1000);
|
||||
SRV_Channels::set_range(SRV_Channel::k_tiltMotorRight, 1000);
|
||||
SRV_Channels::set_range(SRV_Channel::k_tiltMotorRear, 1000);
|
||||
SRV_Channels::set_range(SRV_Channel::k_tiltMotorRearLeft, 1000);
|
||||
SRV_Channels::set_range(SRV_Channel::k_tiltMotorRearRight, 1000);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -737,6 +737,9 @@ void Plane::force_flare(void)
|
|||
SRV_Channels::set_output_scaled(SRV_Channel::k_motor_tilt, tilt);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft, tilt);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRight, tilt);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRear, tilt);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRearLeft, tilt);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRearRight, tilt);
|
||||
float throttle_min = MAX(aparm.throttle_min.get(),0); //allows ICE to run if used but accounts for reverse thrust setups
|
||||
if (arming.is_armed()) { //prevent running motors if unarmed
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, throttle_min);
|
||||
|
|
|
@ -344,6 +344,9 @@ void QuadPlane::tiltrotor_vectored_yaw(void)
|
|||
|
||||
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));
|
||||
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));
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
@ -353,6 +356,9 @@ void QuadPlane::tiltrotor_vectored_yaw(void)
|
|||
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);
|
||||
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);
|
||||
} else {
|
||||
const float yaw_out = motors->get_yaw();
|
||||
const float roll_out = motors->get_roll();
|
||||
|
@ -370,6 +376,9 @@ void QuadPlane::tiltrotor_vectored_yaw(void)
|
|||
|
||||
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));
|
||||
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));
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue