Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ArduPlane: convert parameter TRIM_PITCH_CD to TRIM_PITCH_DEG #25768

Closed
wants to merge 7 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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;
}
}

Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
21 changes: 12 additions & 9 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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));
}
4 changes: 2 additions & 2 deletions ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class Parameters {
//
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
Expand Down Expand Up @@ -437,7 +437,7 @@ class Parameters {
AP_Int16 dspoiler_rud_rate;
AP_Int32 log_bitmask;
AP_Int32 RTL_altitude_cm;
AP_Int16 pitch_trim_cd;
timtuxworth marked this conversation as resolved.
Show resolved Hide resolved
AP_Float pitch_trim;
AP_Int16 FBWB_min_altitude_cm;

AP_Int8 flap_1_percent;
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/defines.h
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion Tools/Frame_params/QuadPlanes/MFE_StriverMini.param
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ SCALING_SPEED 15
TECS_CLMB_MAX 3
TECS_LAND_ARSPD 20
TKOFF_THR_MAX 85
TRIM_PITCH_CD 100
PITCH_TRIM 1
TRIM_THROTTLE 40
WP_LOITER_RAD 120
WP_RADIUS 110
Expand Down
2 changes: 1 addition & 1 deletion Tools/Frame_params/QuadPlanes/XPlane-Alia.parm
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ TRIM_THROTTLE,60
GROUND_STEER_ALT,10
TRIM_ARSPD_CM,5200
SCALING_SPEED,60
TRIM_PITCH_CD,400
TRIM_PITCH_DEG,4
ALT_HOLD_RTL,25000
FLAP_1_PERCNT,50
FLAP_1_SPEED,30
Expand Down
2 changes: 1 addition & 1 deletion Tools/Frame_params/SkyWalkerX8.param
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ TKOFF_THR_MINSPD,0
TKOFF_THR_SLEW,100
TRIM_ARSPD_CM,1600
TRIM_AUTO,0
TRIM_PITCH_CD,0
PITCH_TRIM,0
TRIM_RC_AT_START,0
TRIM_THROTTLE,55
USE_REV_THRUST,0
Expand Down
2 changes: 1 addition & 1 deletion Tools/Frame_params/SkyWalkerX8_ReverseThrust.param
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ TKOFF_THR_MINSPD,0
TKOFF_THR_SLEW,100
TRIM_ARSPD_CM,1600
TRIM_AUTO,0
TRIM_PITCH_CD,0
PITCH_TRIM,0
TRIM_RC_AT_START,0
TRIM_THROTTLE,55
USE_REV_THRUST,2
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/default_params/plane-jsbsim.parm
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ EK2_ENABLE 1
BATT_MONITOR 4
LOG_BITMASK 65535
TRIM_ARSPD_CM 2200
TRIM_PITCH_CD 0
PITCH_TRIM 0
TRIM_THROTTLE 50
LIM_PITCH_MIN -2000
LIM_PITCH_MAX 2500
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/default_params/vee-gull 005.param
Original file line number Diff line number Diff line change
Expand Up @@ -803,7 +803,7 @@ TKOFF_THR_MINSPD,0
TKOFF_THR_SLEW,0
TRIM_ARSPD_CM,1200
TRIM_AUTO,0
TRIM_PITCH_CD,0
PITCH_TRIM,0
TRIM_RC_AT_START,0
TRIM_THROTTLE,45
TUNE_CHAN,0
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/models/plane.parm
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ EK2_ENABLE 1
BATT_MONITOR 4
LOG_BITMASK 65535
TRIM_ARSPD_CM 2200
TRIM_PITCH_CD 0
PITCH_TRIM 0
TRIM_THROTTLE 50
LIM_PITCH_MIN -2000
LIM_PITCH_MAX 2500
Expand Down
16 changes: 10 additions & 6 deletions libraries/AP_Param/AP_Param.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1883,7 +1883,6 @@ bool AP_Param::find_old_parameter(const struct ConversionInfo *info, AP_Param *v
return true;
}


#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wformat"
// convert one old vehicle parameter to new object parameter
Expand Down Expand Up @@ -1944,11 +1943,17 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info, float sc
#pragma GCC diagnostic pop


// convert old vehicle parameters to new object parametersv
// convert old vehicle parameters to new object parameters
void AP_Param::convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags)
{
convert_old_parameters_scaled(conversion_table, table_size, 1.0f,flags);
}

// convert old vehicle parameters to new object parameters with scaling - assumes all parameters will have the same scaling factor
void AP_Param::convert_old_parameters_scaled(const struct ConversionInfo *conversion_table, uint8_t table_size, float scaler, uint8_t flags)
{
for (uint8_t i=0; i<table_size; i++) {
convert_old_parameter(&conversion_table[i], 1.0f, flags);
convert_old_parameter(&conversion_table[i], scaler, flags);
}
// we need to flush here to prevent a later set_default_by_name()
// causing a save to be done on a converted parameter
Expand Down Expand Up @@ -2004,7 +2009,7 @@ void AP_Param::convert_class(uint16_t param_key, void *object_pointer,
convert width of a parameter, allowing update to wider scalar values
without changing the parameter indexes
*/
bool AP_Param::convert_parameter_width(ap_var_type old_ptype)
bool AP_Param::convert_parameter_width(ap_var_type old_ptype, float scale_factor)
{
if (configured_in_storage()) {
// already converted or set by the user
Expand Down Expand Up @@ -2051,15 +2056,14 @@ bool AP_Param::convert_parameter_width(ap_var_type old_ptype)
// going via float is safe as the only time we would be converting
// from AP_Int32 is when converting to float
float old_float_value = old_ap->cast_to_float(old_ptype);
set_value(new_ptype, this, old_float_value);
set_value(new_ptype, this, old_float_value*scale_factor);

// force save as the new type
save(true);

return true;
}


/*
set a parameter to a float value
*/
Expand Down
7 changes: 6 additions & 1 deletion libraries/AP_Param/AP_Param.h
Original file line number Diff line number Diff line change
Expand Up @@ -467,13 +467,18 @@ class AP_Param

// convert old vehicle parameters to new object parameters
static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags=0);
// convert old vehicle parameters to new object parameters with scaling - assumes we use the same scaling factor for all values in the table
static void convert_old_parameters_scaled(const ConversionInfo *conversion_table, uint8_t table_size, float scaler, uint8_t flags);

/*
convert width of a parameter, allowing update to wider scalar
values without changing the parameter indexes. This will return
true if the parameter was converted from an old parameter value
*/
bool convert_parameter_width(ap_var_type old_ptype);
bool convert_parameter_width(ap_var_type old_ptype, float scale_factor=1.0);
bool convert_centi_parameter(ap_var_type old_ptype) {
return convert_parameter_width(old_ptype, 0.01f);
}

// convert a single parameter with scaling
enum {
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_TECS/AP_TECS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -859,7 +859,7 @@ void AP_TECS::_update_throttle_without_airspeed(int16_t throttle_nudge)
_pitch_demand_lpf.apply(_pitch_dem, _DT);
const float pitch_demand_hpf = _pitch_dem - _pitch_demand_lpf.get();
_pitch_measured_lpf.apply(_ahrs.get_pitch(), _DT);
const float pitch_corrected_lpf = _pitch_measured_lpf.get() - radians(0.01f * (float)aparm.pitch_trim_cd);
const float pitch_corrected_lpf = _pitch_measured_lpf.get();
const float pitch_blended = pitch_demand_hpf + pitch_corrected_lpf;

if (pitch_blended > 0.0f && _PITCHmaxf > 0.0f)
Expand Down
1 change: 0 additions & 1 deletion libraries/AP_Vehicle/AP_FixedWing.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@ struct AP_FixedWing {
AP_Int32 autotune_options;
AP_Int8 stall_prevention;
AP_Int16 loiter_radius;
AP_Int16 pitch_trim_cd;
AP_Float takeoff_throttle_max_t;

struct Rangefinder_State {
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Vehicle/AP_Vehicle.h
Original file line number Diff line number Diff line change
Expand Up @@ -268,7 +268,7 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks {
*/
virtual bool get_pan_tilt_norm(float &pan_norm, float &tilt_norm) const { return false; }

// Returns roll and pitch for OSD Horizon, Plane overrides to correct for VTOL view and fixed wing TRIM_PITCH_CD
// Returns roll and pitch for OSD Horizon, Plane overrides to correct for VTOL view and fixed wing TRIM_PITCH
virtual void get_osd_roll_pitch_rad(float &roll, float &pitch) const;

/*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -851,7 +851,7 @@ TKOFF_THR_MINSPD,0
TKOFF_THR_SLEW,0
TRIM_ARSPD_CM,3000
TRIM_AUTO,0
TRIM_PITCH_CD,0
TRIM_PITCH,0
TRIM_THROTTLE,45
TUNE_CHAN,0
TUNE_CHAN_MAX,2000
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -845,7 +845,7 @@ TKOFF_THR_MINSPD,0
TKOFF_THR_SLEW,0
TRIM_ARSPD_CM,2700
TRIM_AUTO,0
TRIM_PITCH_CD,0
TRIM_PITCH,0
TRIM_THROTTLE,45
TUNE_CHAN,0
TUNE_CHAN_MAX,2000
Expand Down
Loading