Plane: fixes for Q_TRIM_PITCH
improved documentation and variable names
This commit is contained in:
parent
33b26da2eb
commit
c59b2c156a
@ -359,14 +359,15 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = {
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("TAILSIT_THSCMX", 3, QuadPlane, tailsitter.throttle_scale_max, 5),
|
||||
|
||||
// @Param: TRIM_PIT
|
||||
// @Param: TRIM_PITCH
|
||||
// @DisplayName: Quadplane AHRS trim pitch
|
||||
// @Description: Compensates for the pitch angle trim difference between forward and vertical flight pitch, NOTE! this is relative to forward flight trim not mounting locaiton
|
||||
// @Description: This sets the compensation for the pitch angle trim difference between forward and vertical flight pitch, NOTE! this is relative to forward flight trim not mounting locaiton. For tailsitters this is relative to a baseline of 90 degrees.
|
||||
// @Units: deg
|
||||
// @Range: -180 +180
|
||||
// @User: Standard
|
||||
// @Range: -10 +10
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("TRIM_PIT", 4, QuadPlane, quadplane_ahrs_trim_pitch, 0),
|
||||
AP_GROUPINFO("TRIM_PITCH", 4, QuadPlane, ahrs_trim_pitch, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
@ -557,7 +558,7 @@ bool QuadPlane::setup(void)
|
||||
AP_Param::load_object_from_eeprom(motors, motors_var_info);
|
||||
|
||||
// create the attitude view used by the VTOL code
|
||||
ahrs_view = ahrs.create_view_trim(rotation, (float)quadplane_ahrs_trim_pitch);
|
||||
ahrs_view = ahrs.create_view(rotation, ahrs_trim_pitch);
|
||||
if (ahrs_view == nullptr) {
|
||||
goto failed;
|
||||
}
|
||||
|
@ -232,7 +232,7 @@ private:
|
||||
AP_Float transition_decel;
|
||||
|
||||
// Quadplane trim, degrees
|
||||
AP_Float quadplane_ahrs_trim_pitch;
|
||||
AP_Float ahrs_trim_pitch;
|
||||
|
||||
AP_Int16 rc_speed;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user