Browse Source

AP_RangeFinder_MAVLink: only set sensor type if we accept a reading

c415-sdk
Peter Barker 4 years ago committed by Peter Barker
parent
commit
223e775a3c
  1. 2
      libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp

2
libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp

@ -28,8 +28,8 @@ void AP_RangeFinder_MAVLink::handle_msg(const mavlink_message_t &msg) @@ -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;
}
/*

Loading…
Cancel
Save