AC_PrecLand: remove check of type when using distance-to-target
This commit is contained in:
parent
438ffd870a
commit
974a6f48c6
@ -162,10 +162,11 @@ void AC_PrecLand::update(float rangefinder_alt_cm, bool rangefinder_alt_valid)
|
||||
Vector3f target_vec_unit_ned = _attitude_history.front() * Rz * target_vec_unit_body;
|
||||
|
||||
bool target_vec_valid = target_vec_unit_ned.z > 0.0f;
|
||||
bool alt_valid = (rangefinder_alt_valid && rangefinder_alt_cm > 0.0f) || (_backend->distance_to_target() > 0.0f);
|
||||
|
||||
if (target_vec_valid && ( (rangefinder_alt_valid && rangefinder_alt_cm > 0.0f) || ((enum PrecLandType)(_type.get()) == PRECLAND_TYPE_COMPANION && _backend->distance_to_target()) ) ) {
|
||||
if (target_vec_valid && alt_valid) {
|
||||
float alt;
|
||||
if ((enum PrecLandType)(_type.get()) == PRECLAND_TYPE_COMPANION && _backend->distance_to_target()) {
|
||||
if (_backend->distance_to_target() > 0.0f) {
|
||||
alt = _backend->distance_to_target();
|
||||
} else {
|
||||
alt = MAX(rangefinder_alt_cm*0.01f, 0.0f);
|
||||
|
@ -32,9 +32,9 @@ public:
|
||||
|
||||
// return true if there is a valid los measurement available
|
||||
virtual bool have_los_meas() = 0;
|
||||
|
||||
// return distance to target
|
||||
virtual float distance_to_target() = 0;
|
||||
|
||||
// returns distance to target in meters (0 means distance is not known)
|
||||
virtual float distance_to_target() { return 0.0f; };
|
||||
|
||||
// parses a mavlink message from the companion computer
|
||||
virtual void handle_msg(mavlink_message_t* msg) {};
|
||||
|
@ -31,9 +31,9 @@ public:
|
||||
// return true if there is a valid los measurement available
|
||||
bool have_los_meas();
|
||||
|
||||
// return distance to target
|
||||
float distance_to_target();
|
||||
|
||||
// returns distance to target in meters (0 means distance is not known)
|
||||
float distance_to_target() override;
|
||||
|
||||
// parses a mavlink message from the companion computer
|
||||
void handle_msg(mavlink_message_t* msg);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user