From f92f46ee99ae0392bca34b8189b6594d9cbbbc0f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 8 Sep 2015 13:54:45 +1000 Subject: [PATCH] Plane: update for changed AP_Arming API --- ArduPlane/Plane.h | 7 +++---- ArduPlane/arming_checks.cpp | 8 ++++---- 2 files changed, 7 insertions(+), 8 deletions(-) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index e46720af90..5e16b5f51f 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -117,8 +117,8 @@ class AP_Arming_Plane : public AP_Arming { public: AP_Arming_Plane(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass, - const enum HomeState &home_set, gcs_send_t_p gcs_send) : - AP_Arming(ahrs_ref, baro, compass, home_set, gcs_send) { + const enum HomeState &home_set) : + AP_Arming(ahrs_ref, baro, compass, home_set) { AP_Param::setup_object_defaults(this, var_info); } bool pre_arm_checks(bool report); @@ -658,8 +658,7 @@ private: #endif // Arming/Disarming mangement class - AP_Arming_Plane arming {ahrs, barometer, compass, home_is_set, - FUNCTOR_BIND_MEMBER(&Plane::gcs_send_text_P, void, MAV_SEVERITY, const prog_char_t *)}; + AP_Arming_Plane arming {ahrs, barometer, compass, home_is_set }; AP_Param param_loader {var_info}; diff --git a/ArduPlane/arming_checks.cpp b/ArduPlane/arming_checks.cpp index 1489370cc1..27c6f40c12 100644 --- a/ArduPlane/arming_checks.cpp +++ b/ArduPlane/arming_checks.cpp @@ -32,21 +32,21 @@ bool AP_Arming_Plane::pre_arm_checks(bool report) if (plane.g.roll_limit_cd < 300) { if (report) { - gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: LIM_ROLL_CD too small")); + GCS_MAVLINK::send_statustext_all(PSTR("PreArm: LIM_ROLL_CD too small (%u)"), plane.g.roll_limit_cd); } ret = false; } if (plane.aparm.pitch_limit_max_cd < 300) { if (report) { - gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: LIM_PITCH_MAX too small")); + GCS_MAVLINK::send_statustext_all(PSTR("PreArm: LIM_PITCH_MAX too small (%u)"), plane.aparm.pitch_limit_max_cd); } ret = false; } if (plane.aparm.pitch_limit_min_cd > -300) { if (report) { - gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: LIM_PITCH_MIN too large")); + GCS_MAVLINK::send_statustext_all(PSTR("PreArm: LIM_PITCH_MIN too large (%u)"), plane.aparm.pitch_limit_min_cd); } ret = false; } @@ -56,7 +56,7 @@ bool AP_Arming_Plane::pre_arm_checks(bool report) plane.g.throttle_fs_value < plane.channel_throttle->radio_max) { if (report) { - gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: invalid THR_FS_VALUE for rev throttle")); + GCS_MAVLINK::send_statustext_all(PSTR("PreArm: invalid THR_FS_VALUE for rev throttle")); } ret = false; }