mirror of https://github.com/ArduPilot/ardupilot
Plane: TRIM_PITCH_DEG to PTCH_TRIM_DEG
This commit is contained in:
parent
2f5cb42030
commit
5619dca389
|
@ -917,7 +917,7 @@ bool Plane::is_taking_off() const
|
||||||
return control_mode->is_taking_off();
|
return control_mode->is_taking_off();
|
||||||
}
|
}
|
||||||
|
|
||||||
// correct AHRS pitch for TRIM_PITCH_DEG in non-VTOL modes, and return VTOL view in VTOL
|
// correct AHRS pitch for PTCH_TRIM_DEG in non-VTOL modes, and return VTOL view in VTOL
|
||||||
void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const
|
void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const
|
||||||
{
|
{
|
||||||
#if HAL_QUADPLANE_ENABLED
|
#if HAL_QUADPLANE_ENABLED
|
||||||
|
@ -929,7 +929,7 @@ void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const
|
||||||
#endif
|
#endif
|
||||||
pitch = ahrs.get_pitch();
|
pitch = ahrs.get_pitch();
|
||||||
roll = ahrs.get_roll();
|
roll = ahrs.get_roll();
|
||||||
if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH))) { // correct for TRIM_PITCH_DEG
|
if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH))) { // correct for PTCH_TRIM_DEG
|
||||||
pitch -= g.pitch_trim * DEG_TO_RAD;
|
pitch -= g.pitch_trim * DEG_TO_RAD;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -644,13 +644,13 @@ const AP_Param::Info Plane::var_info[] = {
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
ASCALAR(min_groundspeed, "MIN_GROUNDSPEED", MIN_GROUNDSPEED),
|
ASCALAR(min_groundspeed, "MIN_GROUNDSPEED", MIN_GROUNDSPEED),
|
||||||
|
|
||||||
// @Param: TRIM_PITCH_DEG
|
// @Param: PTCH_TRIM_DEG
|
||||||
// @DisplayName: Pitch angle offset
|
// @DisplayName: Pitch angle offset
|
||||||
// @Description: Offset in degrees used for in-flight pitch trimming for level flight. Correct ground leveling is an alternative to changing this parameter.
|
// @Description: Offset in degrees used for in-flight pitch trimming for level flight. Correct ground leveling is an alternative to changing this parameter.
|
||||||
// @Units: deg
|
// @Units: deg
|
||||||
// @Range: -45 45
|
// @Range: -45 45
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(pitch_trim, "TRIM_PITCH_DEG", 0.0f),
|
GSCALAR(pitch_trim, "PTCH_TRIM_DEG", 0.0f),
|
||||||
|
|
||||||
// @Param: RTL_ALTITUDE
|
// @Param: RTL_ALTITUDE
|
||||||
// @DisplayName: RTL altitude
|
// @DisplayName: RTL altitude
|
||||||
|
|
Loading…
Reference in New Issue