AP_Rangefinder: MAVLink: accept data only from configured orentation

This commit is contained in:
Iampete1 2021-08-30 15:27:41 +01:00 committed by Andrew Tridgell
parent 83bcea1fe0
commit 0d3c00cb96

View File

@ -24,8 +24,8 @@ void AP_RangeFinder_MAVLink::handle_msg(const mavlink_message_t &msg)
mavlink_distance_sensor_t packet; mavlink_distance_sensor_t packet;
mavlink_msg_distance_sensor_decode(&msg, &packet); mavlink_msg_distance_sensor_decode(&msg, &packet);
// only accept distances for downward facing sensors // only accept distances for the configured orentation
if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_270) { if (packet.orientation == orientation()) {
state.last_reading_ms = AP_HAL::millis(); state.last_reading_ms = AP_HAL::millis();
distance_cm = packet.current_distance; distance_cm = packet.current_distance;
_max_distance_cm = packet.max_distance; _max_distance_cm = packet.max_distance;