Copter: constify some ModeThrow methods

This commit is contained in:
Peter Barker 2021-07-02 16:06:42 +10:00 committed by Andrew Tridgell
parent b16d86ebbe
commit 952c8f7ff5
2 changed files with 6 additions and 6 deletions

View File

@ -1465,9 +1465,9 @@ protected:
private: private:
bool throw_detected(); bool throw_detected();
bool throw_position_good(); bool throw_position_good() const;
bool throw_height_good(); bool throw_height_good() const;
bool throw_attitude_good(); bool throw_attitude_good() const;
// Throw stages // Throw stages
enum ThrowModeStage { enum ThrowModeStage {

View File

@ -276,20 +276,20 @@ bool ModeThrow::throw_detected()
return throw_condition_confirmed; return throw_condition_confirmed;
} }
bool ModeThrow::throw_attitude_good() bool ModeThrow::throw_attitude_good() const
{ {
// Check that we have uprighted the copter // Check that we have uprighted the copter
const Matrix3f &rotMat = ahrs.get_rotation_body_to_ned(); const Matrix3f &rotMat = ahrs.get_rotation_body_to_ned();
return (rotMat.c.z > 0.866f); // is_upright 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 // Check that we are within 0.5m of the demanded height
return (pos_control->get_pos_error_z_cm() < 50.0f); 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 // check that our horizontal position error is within 50cm
return (pos_control->get_pos_error_xy_cm() < 50.0f); return (pos_control->get_pos_error_xy_cm() < 50.0f);