mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Plane: add tailsitter assist with motors only option
This commit is contained in:
parent
6710bab006
commit
08a710235d
@ -329,7 +329,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
|||||||
// @Param: OPTIONS
|
// @Param: OPTIONS
|
||||||
// @DisplayName: quadplane options
|
// @DisplayName: quadplane options
|
||||||
// @Description: This provides a set of additional control options for quadplanes. LevelTransition means that the wings should be held level to within LEVEL_ROLL_LIMIT degrees during transition to fixed wing flight, and the vehicle will not use the vertical lift motors to climb during the transition. If AllowFWTakeoff bit is not set then fixed wing takeoff on quadplanes will instead perform a VTOL takeoff. If AllowFWLand bit is not set then fixed wing land on quadplanes will instead perform a VTOL land. If respect takeoff frame is not set the vehicle will interpret all takeoff waypoints as an altitude above the corrent position. When Use QRTL is set it will replace QLAND with QRTL for failsafe actions when in VTOL modes.
|
// @Description: This provides a set of additional control options for quadplanes. LevelTransition means that the wings should be held level to within LEVEL_ROLL_LIMIT degrees during transition to fixed wing flight, and the vehicle will not use the vertical lift motors to climb during the transition. If AllowFWTakeoff bit is not set then fixed wing takeoff on quadplanes will instead perform a VTOL takeoff. If AllowFWLand bit is not set then fixed wing land on quadplanes will instead perform a VTOL land. If respect takeoff frame is not set the vehicle will interpret all takeoff waypoints as an altitude above the corrent position. When Use QRTL is set it will replace QLAND with QRTL for failsafe actions when in VTOL modes.
|
||||||
// @Bitmask: 0:LevelTransition,1:AllowFWTakeoff,2:AllowFWLand,3:Respect takeoff frame types,4:Use a fixed wing approach for VTOL landings,5:Use QRTL instead of QLAND for failsafe when in VTOL modes,6:Use idle governor in MANUAL,7:QAssist force enabled
|
// @Bitmask: 0:LevelTransition,1:AllowFWTakeoff,2:AllowFWLand,3:Respect takeoff frame types,4:Use a fixed wing approach for VTOL landings,5:Use QRTL instead of QLAND for failsafe when in VTOL modes,6:Use idle governor in MANUAL,7:QAssist force enabled,8:Tailsitter QAssist motors only
|
||||||
AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0),
|
AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0),
|
||||||
|
|
||||||
AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2),
|
AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2),
|
||||||
|
@ -555,6 +555,7 @@ private:
|
|||||||
OPTION_FS_QRTL=(1<<5),
|
OPTION_FS_QRTL=(1<<5),
|
||||||
OPTION_IDLE_GOV_MANUAL=(1<<6),
|
OPTION_IDLE_GOV_MANUAL=(1<<6),
|
||||||
OPTION_Q_ASSIST_FORCE_ENABLE=(1<<7),
|
OPTION_Q_ASSIST_FORCE_ENABLE=(1<<7),
|
||||||
|
OPTION_TAILSIT_Q_ASSIST_MOTORS_ONLY=(1<<8),
|
||||||
};
|
};
|
||||||
|
|
||||||
AP_Float takeoff_failure_scalar;
|
AP_Float takeoff_failure_scalar;
|
||||||
|
@ -111,16 +111,32 @@ void QuadPlane::tailsitter_output(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// handle VTOL modes
|
// handle Copter controller
|
||||||
// the MultiCopter rate controller has already been run in an earlier call
|
// the MultiCopter rate controller has already been run in an earlier call
|
||||||
// to motors_output() from quadplane.update(), unless we are in assisted flight
|
// to motors_output() from quadplane.update(), unless we are in assisted flight
|
||||||
if (assisted_flight) {
|
if (assisted_flight && tailsitter_transition_fw_complete()) {
|
||||||
hold_stabilize(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * 0.01f);
|
hold_stabilize(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * 0.01f);
|
||||||
motors_output(true);
|
motors_output(true);
|
||||||
|
|
||||||
|
if ((options & OPTION_TAILSIT_Q_ASSIST_MOTORS_ONLY) != 0) {
|
||||||
|
// only use motors for Q assist, control surfaces remain under plane control
|
||||||
|
// zero copter I terms and use plane
|
||||||
|
attitude_control->reset_rate_controller_I_terms();
|
||||||
|
|
||||||
|
// output tilt motors
|
||||||
|
if (tailsitter.vectored_hover_gain > 0) {
|
||||||
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft, SRV_Channels::get_output_scaled(SRV_Channel::k_tiltMotorLeft) * tailsitter.vectored_hover_gain);
|
||||||
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRight, SRV_Channels::get_output_scaled(SRV_Channel::k_tiltMotorRight) * tailsitter.vectored_hover_gain);
|
||||||
|
}
|
||||||
|
|
||||||
|
// skip remainder of the function that overwrites plane control surface outputs with copter
|
||||||
|
return;
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
motors_output(false);
|
motors_output(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// In full Q assist it is better to use cotper I and zero plane
|
||||||
plane.pitchController.reset_I();
|
plane.pitchController.reset_I();
|
||||||
plane.rollController.reset_I();
|
plane.rollController.reset_I();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user