mirror of https://github.com/ArduPilot/ardupilot
Plane: add TKOFF_GND_PITCH
This commit is contained in:
parent
b5e17bfc5d
commit
7a6f398668
|
@ -160,7 +160,7 @@ const AP_Param::Info Plane::var_info[] = {
|
|||
|
||||
// @Param: TKOFF_ROTATE_SPD
|
||||
// @DisplayName: Takeoff rotate speed
|
||||
// @Description: This parameter sets the airspeed at which the aircraft will "rotate", setting climb pitch specified in the mission. If TKOFF_ROTATE_SPD is zero then the climb pitch will be used as soon as takeoff is started. For hand launch and catapult launches a TKOFF_ROTATE_SPD of zero should be set. For all ground launches TKOFF_ROTATE_SPD should be set above the stall speed, usually by about 10 to 30 percent
|
||||
// @Description: This parameter sets the airspeed at which the aircraft will "rotate", setting climb pitch specified in the mission. If TKOFF_ROTATE_SPD is zero then the climb pitch will be used as soon as takeoff is started. For hand launch and catapult launches a TKOFF_ROTATE_SPD of zero should be set. For all ground launches TKOFF_ROTATE_SPD should be set above the stall speed, usually by about 10 to 30 percent. During the run, use TKOFF_GND_PITCH to keep the aircraft on the runway while below this airspeed.
|
||||
// @Units: m/s
|
||||
// @Range: 0 30
|
||||
// @Increment: 0.1
|
||||
|
|
|
@ -737,6 +737,8 @@ public:
|
|||
// var_info for holding parameter information
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
AP_Float ground_pitch;
|
||||
|
||||
protected:
|
||||
AP_Int16 target_alt;
|
||||
AP_Int16 target_dist;
|
||||
|
|
|
@ -41,6 +41,15 @@ const AP_Param::GroupInfo ModeTakeoff::var_info[] = {
|
|||
// @User: Standard
|
||||
AP_GROUPINFO("DIST", 4, ModeTakeoff, target_dist, 200),
|
||||
|
||||
// @Param: GND_PITCH
|
||||
// @DisplayName: Takeoff run pitch demand
|
||||
// @Description: Degrees of pitch angle demanded during the takeoff run before speed reaches TKOFF_ROTATE_SPD. For taildraggers set to 3-point ground pitch angle and use TKOFF_TDRAG_ELEV to prevent nose tipover. For nose-wheel steer aircraft set to the ground pitch angle and if a reduction in nose-wheel load is required as speed rises, use a positive offset in TKOFF_GND_PITCH of up to 5 degrees above the angle on ground, starting at the mesured pitch angle and incrementing in 1 degree steps whilst checking for premature rotation and takeoff with each increment. To increase nose-wheel load, use a negative TKOFF_TDRAG_ELEV and refer to notes on TKOFF_TDRAG_ELEV before making adjustments.
|
||||
// @Units: deg
|
||||
// @Range: -5.0 10.0
|
||||
// @Increment: 0.1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("GND_PITCH", 5, ModeTakeoff, ground_pitch, 5),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -155,11 +155,8 @@ void Plane::takeoff_calc_roll(void)
|
|||
void Plane::takeoff_calc_pitch(void)
|
||||
{
|
||||
if (auto_state.highest_airspeed < g.takeoff_rotate_speed) {
|
||||
// we have not reached rotate speed, use a target pitch of 5
|
||||
// degrees. This should be enough to get the tail off the
|
||||
// ground, while making it unlikely that overshoot in the
|
||||
// pitch controller will cause a prop strike
|
||||
nav_pitch_cd = 500;
|
||||
// we have not reached rotate speed, use the specified takeoff target pitch angle
|
||||
nav_pitch_cd = int32_t(100.0f * mode_takeoff.ground_pitch);
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue