Quadplane: add trim params

This commit is contained in:
IamPete1 2018-09-25 16:13:34 +01:00 committed by Andrew Tridgell
parent 4c3651c2be
commit 5a7bd61e8c
2 changed files with 16 additions and 4 deletions

View File

@ -358,7 +358,16 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = {
// @Range: 1 5
// @User: Standard
AP_GROUPINFO("TAILSIT_THSCMX", 3, QuadPlane, tailsitter.throttle_scale_max, 5),
// @Param: TRIM_PIT
// @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
// @Units: deg
// @Range: -180 +180
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO("TRIM_PIT", 4, QuadPlane, quadplane_ahrs_trim_pitch, 0),
AP_GROUPEND
};
@ -548,11 +557,11 @@ 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(rotation);
ahrs_view = ahrs.create_view_trim(rotation, (float)quadplane_ahrs_trim_pitch);
if (ahrs_view == nullptr) {
goto failed;
}
attitude_control = new AC_AttitudeControl_Multi(*ahrs_view, aparm, *motors, loop_delta_t);
if (!attitude_control) {
hal.console->printf("%s attitude_control\n", strUnableToAllocate);

View File

@ -230,7 +230,10 @@ private:
// transition deceleration, m/s/s
AP_Float transition_decel;
// Quadplane trim, degrees
AP_Float quadplane_ahrs_trim_pitch;
AP_Int16 rc_speed;
// min and max PWM for throttle