Plane: convert parameter TRIM_PITCH_CD to TRIM_PITCH_DEG

This commit is contained in:
Tim Tuxworth 2023-12-13 14:49:48 -07:00 committed by Andrew Tridgell
parent 6c634ebc00
commit 3cf0de2224
7 changed files with 23 additions and 20 deletions

View File

@ -917,7 +917,7 @@ bool Plane::is_taking_off() const
return control_mode->is_taking_off();
}
// correct AHRS pitch for TRIM_PITCH_CD in non-VTOL modes, and return VTOL view in VTOL
// correct AHRS pitch for TRIM_PITCH_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
@ -929,8 +929,8 @@ void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const
#endif
pitch = ahrs.get_pitch();
roll = ahrs.get_roll();
if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH_CD))) { // correct for TRIM_PITCH_CD
pitch -= g.pitch_trim_cd * 0.01 * DEG_TO_RAD;
if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH))) { // correct for TRIM_PITCH_DEG
pitch -= g.pitch_trim * DEG_TO_RAD;
}
}

View File

@ -209,7 +209,7 @@ float Plane::stabilize_pitch_get_pitch_out()
const bool quadplane_in_transition = false;
#endif
int32_t demanded_pitch = nav_pitch_cd + g.pitch_trim_cd + SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * g.kff_throttle_to_pitch;
int32_t demanded_pitch = nav_pitch_cd + int32_t(g.pitch_trim * 100.0) + SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * g.kff_throttle_to_pitch;
bool disable_integrator = false;
if (control_mode == &mode_stabilize && channel_pitch->get_control_in() != 0) {
disable_integrator = true;

View File

@ -133,8 +133,8 @@ void GCS_MAVLINK_Plane::send_attitude() const
float p = ahrs.get_pitch();
float y = ahrs.get_yaw();
if (!(plane.flight_option_enabled(FlightOptions::GCS_REMOVE_TRIM_PITCH_CD))) {
p -= radians(plane.g.pitch_trim_cd * 0.01f);
if (!(plane.flight_option_enabled(FlightOptions::GCS_REMOVE_TRIM_PITCH))) {
p -= radians(plane.g.pitch_trim);
}
#if HAL_QUADPLANE_ENABLED

View File

@ -644,14 +644,13 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Advanced
ASCALAR(min_gndspeed_cm, "MIN_GNDSPD_CM", MIN_GNDSPEED_CM),
// @Param: TRIM_PITCH_CD
// @Param: TRIM_PITCH_DEG
// @DisplayName: Pitch angle offset
// @Description: Offset applied to AHRS pitch used for in-flight pitch trimming. Correct ground leveling is better than changing this parameter.
// @Units: cdeg
// @Range: -4500 4500
// @Increment: 10
// @User: Advanced
GSCALAR(pitch_trim_cd, "TRIM_PITCH_CD", 0),
// @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_DEG", 0.0f),
// @Param: ALT_HOLD_RTL
// @DisplayName: RTL altitude
@ -1095,8 +1094,8 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Bitmask: 5: Enable yaw damper in acro mode
// @Bitmask: 6: Supress speed scaling during auto takeoffs to be 1 or less to prevent oscillations without airspeed sensor.
// @Bitmask: 7: EnableDefaultAirspeed for takeoff
// @Bitmask: 8: Remove the TRIM_PITCH_CD on the GCS horizon
// @Bitmask: 9: Remove the TRIM_PITCH_CD on the OSD horizon
// @Bitmask: 8: Remove the TRIM_PITCH on the GCS horizon
// @Bitmask: 9: Remove the TRIM_PITCH on the OSD horizon
// @Bitmask: 10: Adjust mid-throttle to be TRIM_THROTTLE in non-auto throttle modes except MANUAL
// @Bitmask: 11: Disable suppression of fixed wing rate gains in ground mode
// @Bitmask: 12: Enable FBWB style loiter altitude control
@ -1545,6 +1544,10 @@ void Plane::load_parameters(void)
#if AP_FENCE_ENABLED
AP_Param::convert_class(g.k_param_fence, &fence, fence.var_info, 0, 0, true);
#endif
// PARAMETER_CONVERSION - Added: Dec 2023
// Convert _CM (centimeter) parameters to meters and _CD (centidegrees) parameters to meters
g.pitch_trim.convert_centi_parameter(AP_PARAM_INT16);
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
}

View File

@ -56,7 +56,7 @@ public:
//
k_param_auto_trim = 10, // unused
k_param_log_bitmask_old, // unused
k_param_pitch_trim_cd,
k_param_pitch_trim, // replaced by pitch_trim
k_param_mix_mode,
k_param_reverse_elevons, // unused
k_param_reverse_ch1_elevon, // unused
@ -437,7 +437,7 @@ public:
AP_Int16 dspoiler_rud_rate;
AP_Int32 log_bitmask;
AP_Int32 RTL_altitude_cm;
AP_Int16 pitch_trim_cd;
AP_Float pitch_trim;
AP_Int16 FBWB_min_altitude_cm;
AP_Int8 flap_1_percent;

View File

@ -161,8 +161,8 @@ enum FlightOptions {
ACRO_YAW_DAMPER = (1 << 5),
SURPRESS_TKOFF_SCALING = (1<<6),
ENABLE_DEFAULT_AIRSPEED = (1<<7),
GCS_REMOVE_TRIM_PITCH_CD = (1 << 8),
OSD_REMOVE_TRIM_PITCH_CD = (1 << 9),
GCS_REMOVE_TRIM_PITCH = (1 << 8),
OSD_REMOVE_TRIM_PITCH = (1 << 9),
CENTER_THROTTLE_TRIM = (1<<10),
DISABLE_GROUND_PID_SUPPRESSION = (1<<11),
ENABLE_LOITER_ALT_CONTROL = (1<<12),

View File

@ -310,7 +310,7 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = {
// @Param: TRIM_PITCH
// @DisplayName: Quadplane AHRS trim pitch
// @Description: This sets the compensation for the pitch angle trim difference between calibrated AHRS level and vertical flight pitch. NOTE! this is relative to calibrated AHRS trim, not forward flight trim which includes TRIM_PITCH_CD. For tailsitters, this is relative to a baseline of 90 degrees in AHRS.
// @Description: This sets the compensation for the pitch angle trim difference between calibrated AHRS level and vertical flight pitch. NOTE! this is relative to calibrated AHRS trim, not forward flight trim which includes TRIM_PITCH. For tailsitters, this is relative to a baseline of 90 degrees in AHRS.
// @Units: deg
// @Range: -10 +10
// @Increment: 0.1