Skip to content

Commit

Permalink
AP_Rangefinder: MAVLink: accept data only from configured orentation
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and tridge committed Sep 1, 2021
1 parent 83bcea1 commit 0d3c00c
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ void AP_RangeFinder_MAVLink::handle_msg(const mavlink_message_t &msg)
mavlink_distance_sensor_t packet;
mavlink_msg_distance_sensor_decode(&msg, &packet);

// only accept distances for downward facing sensors
if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_270) {
// only accept distances for the configured orentation
if (packet.orientation == orientation()) {
state.last_reading_ms = AP_HAL::millis();
distance_cm = packet.current_distance;
_max_distance_cm = packet.max_distance;
Expand Down

0 comments on commit 0d3c00c

Please sign in to comment.