Plane: fixes for tilt quadplane after rebase
This commit is contained in:
parent
2feaa9926c
commit
586f8a9ca8
@ -332,7 +332,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
|||||||
// @DisplayName: Tiltrotor type
|
// @DisplayName: Tiltrotor type
|
||||||
// @Description: This is the type of tiltrotor when TILT_MASK is non-zero. A continuous tiltrotor can tilt the rotors to any angle on demand. A binary tiltrotor assumes a retract style servo where the servo is either fully forward or fully up. In both cases the servo can't move faster than Q_TILT_RATE
|
// @Description: This is the type of tiltrotor when TILT_MASK is non-zero. A continuous tiltrotor can tilt the rotors to any angle on demand. A binary tiltrotor assumes a retract style servo where the servo is either fully forward or fully up. In both cases the servo can't move faster than Q_TILT_RATE
|
||||||
// @Values: 0:Continuous,1:Binary
|
// @Values: 0:Continuous,1:Binary
|
||||||
AP_GROUPINFO("TILT_TYPE", 46, QuadPlane, tilt.tilt_type, TILT_TYPE_CONTINUOUS),
|
AP_GROUPINFO("TILT_TYPE", 47, QuadPlane, tilt.tilt_type, TILT_TYPE_CONTINUOUS),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
@ -104,7 +104,7 @@ void QuadPlane::tiltrotor_continuous_update(void)
|
|||||||
*/
|
*/
|
||||||
void QuadPlane::tiltrotor_binary_slew(bool forward)
|
void QuadPlane::tiltrotor_binary_slew(bool forward)
|
||||||
{
|
{
|
||||||
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_motor_tilt, forward?1000:0);
|
SRV_Channels::set_output_scaled(SRV_Channel::k_motor_tilt, forward?1000:0);
|
||||||
|
|
||||||
float max_change = (tilt.max_rate_dps.get() * plane.G_Dt) / 90.0f;
|
float max_change = (tilt.max_rate_dps.get() * plane.G_Dt) / 90.0f;
|
||||||
if (forward) {
|
if (forward) {
|
||||||
@ -130,7 +130,7 @@ void QuadPlane::tiltrotor_binary_update(void)
|
|||||||
// all the way forward and run them as a forward motor
|
// all the way forward and run them as a forward motor
|
||||||
tiltrotor_binary_slew(true);
|
tiltrotor_binary_slew(true);
|
||||||
|
|
||||||
float new_throttle = plane.channel_throttle->get_servo_out()*0.01f;
|
float new_throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)*0.01f;
|
||||||
if (tilt.current_tilt >= 1) {
|
if (tilt.current_tilt >= 1) {
|
||||||
uint8_t mask = is_zero(new_throttle)?0:(uint8_t)tilt.tilt_mask.get();
|
uint8_t mask = is_zero(new_throttle)?0:(uint8_t)tilt.tilt_mask.get();
|
||||||
// the motors are all the way forward, start using them for fwd thrust
|
// the motors are all the way forward, start using them for fwd thrust
|
||||||
|
Loading…
Reference in New Issue
Block a user