Plane: changed for AP_Vehicle API change

This commit is contained in:
Andrew Tridgell 2016-06-23 22:40:13 +10:00
parent 1f29b51dd6
commit 1256c2f351
4 changed files with 4 additions and 5 deletions

View File

@ -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

View File

@ -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

View File

@ -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;

View File

@ -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;
}