From 1256c2f351d86f454a4e4070df55f663a0158967 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 23 Jun 2016 22:40:13 +1000 Subject: [PATCH] Plane: changed for AP_Vehicle API change --- ArduPlane/ArduPlane.cpp | 2 +- ArduPlane/Parameters.cpp | 2 +- ArduPlane/Parameters.h | 1 - ArduPlane/arming_checks.cpp | 4 ++-- 4 files changed, 4 insertions(+), 5 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index c04eaadb3a..8ee9b2a67a 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -164,7 +164,7 @@ void Plane::ahrs_update() } // calculate a scaled roll limit based on current pitch - roll_limit_cd = g.roll_limit_cd * cosf(ahrs.pitch); + roll_limit_cd = aparm.roll_limit_cd * cosf(ahrs.pitch); pitch_limit_min_cd = aparm.pitch_limit_min_cd * fabsf(cosf(ahrs.roll)); // updated the summed gyro used for ground steering and diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 7494e8168d..7860db467c 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -736,7 +736,7 @@ const AP_Param::Info Plane::var_info[] = { // @Range: 0 9000 // @Increment: 1 // @User: Standard - GSCALAR(roll_limit_cd, "LIM_ROLL_CD", HEAD_MAX_CENTIDEGREE), + ASCALAR(roll_limit_cd, "LIM_ROLL_CD", HEAD_MAX_CENTIDEGREE), // @Param: LIM_PITCH_MAX // @DisplayName: Maximum Pitch Angle diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 73f905f206..cfedd2683b 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -449,7 +449,6 @@ public: // Navigational maneuvering limits // - AP_Int16 roll_limit_cd; AP_Int16 alt_offset; AP_Int16 acro_roll_rate; AP_Int16 acro_pitch_rate; diff --git a/ArduPlane/arming_checks.cpp b/ArduPlane/arming_checks.cpp index a9c4bcdc21..f2b839f2c2 100644 --- a/ArduPlane/arming_checks.cpp +++ b/ArduPlane/arming_checks.cpp @@ -30,9 +30,9 @@ bool AP_Arming_Plane::pre_arm_checks(bool report) // Check airspeed sensor ret &= AP_Arming::airspeed_checks(report); - if (plane.g.roll_limit_cd < 300) { + if (plane.aparm.roll_limit_cd < 300) { if (report) { - GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: LIM_ROLL_CD too small (%u)", plane.g.roll_limit_cd); + GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: LIM_ROLL_CD too small (%u)", plane.aparm.roll_limit_cd); } ret = false; }