diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 2eaa08e32a6291..e06a2bcec2aa1c 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -904,7 +904,7 @@ bool Plane::is_taking_off() const return control_mode->is_taking_off(); } -// correct AHRS pitch for TRIM_PITCH 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 { #if HAL_QUADPLANE_ENABLED @@ -916,7 +916,7 @@ void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const #endif pitch = ahrs.pitch; roll = ahrs.roll; - if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH))) { // correct for TRIM_PITCH + if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH))) { // correct for PTCH_TRIM_DEG pitch -= g.pitch_trim * DEG_TO_RAD; } } diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 5a663eb0bc3629..bc0f73a4cb0702 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -644,13 +644,13 @@ const AP_Param::Info Plane::var_info[] = { // @User: Advanced ASCALAR(min_gndspeed_cm, "MIN_GNDSPD_CM", MIN_GNDSPEED_CM), - // @Param: TRIM_PITCH + // @Param: PTCH_TRIM_DEG // @DisplayName: Pitch angle offset - // @Description: Offset 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 // @Range: -45 45 // @User: Standard - GSCALAR(pitch_trim, "TRIM_PITCH", 0.0f), + GSCALAR(pitch_trim, "PTCH_TRIM_DEG", 0.0f), // @Param: ALT_HOLD_RTL // @DisplayName: RTL altitude