From 5a7bd61e8cffee90db1996dc92db5f68f8ae792a Mon Sep 17 00:00:00 2001 From: IamPete1 <33176108+IamPete1@users.noreply.github.com> Date: Tue, 25 Sep 2018 16:13:34 +0100 Subject: [PATCH] Quadplane: add trim params --- ArduPlane/quadplane.cpp | 15 ++++++++++++--- ArduPlane/quadplane.h | 5 ++++- 2 files changed, 16 insertions(+), 4 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index b100b18b43..dfd9c1825a 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -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); diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 8536aaddbb..043e92d778 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -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