AP_RangeFinder_MAVLink: only set sensor type if we accept a reading

This commit is contained in:
Peter Barker 2020-12-05 12:39:17 +11:00 committed by Peter Barker
parent fdd0297f12
commit 223e775a3c
1 changed files with 1 additions and 1 deletions

View File

@ -28,8 +28,8 @@ void AP_RangeFinder_MAVLink::handle_msg(const mavlink_message_t &msg)
if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_270) {
state.last_reading_ms = AP_HAL::millis();
distance_cm = packet.current_distance;
sensor_type = (MAV_DISTANCE_SENSOR)packet.type;
}
sensor_type = (MAV_DISTANCE_SENSOR)packet.type;
}
/*