diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index c21086ee49..b4c428e72e 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -1465,9 +1465,9 @@ protected: private: bool throw_detected(); - bool throw_position_good(); - bool throw_height_good(); - bool throw_attitude_good(); + bool throw_position_good() const; + bool throw_height_good() const; + bool throw_attitude_good() const; // Throw stages enum ThrowModeStage { diff --git a/ArduCopter/mode_throw.cpp b/ArduCopter/mode_throw.cpp index 34d954c643..c039af7acd 100644 --- a/ArduCopter/mode_throw.cpp +++ b/ArduCopter/mode_throw.cpp @@ -276,20 +276,20 @@ bool ModeThrow::throw_detected() return throw_condition_confirmed; } -bool ModeThrow::throw_attitude_good() +bool ModeThrow::throw_attitude_good() const { // Check that we have uprighted the copter const Matrix3f &rotMat = ahrs.get_rotation_body_to_ned(); return (rotMat.c.z > 0.866f); // is_upright } -bool ModeThrow::throw_height_good() +bool ModeThrow::throw_height_good() const { // Check that we are within 0.5m of the demanded height return (pos_control->get_pos_error_z_cm() < 50.0f); } -bool ModeThrow::throw_position_good() +bool ModeThrow::throw_position_good() const { // check that our horizontal position error is within 50cm return (pos_control->get_pos_error_xy_cm() < 50.0f);