AP_RangeFinder: MAV only accepts DISTANCE_SENSOR with orient 25

25 is  MAV_SENSOR_ROTATION_PITCH_270 meaning downward facing
This commit is contained in:
Randy Mackay 2016-12-23 15:02:36 +09:00
parent 653030b038
commit 8215b92371

View File

@ -51,8 +51,11 @@ void AP_RangeFinder_MAVLink::handle_msg(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);
last_update_ms = AP_HAL::millis(); // only accept distances for downward facing sensors
distance_cm = packet.current_distance; if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_270) {
last_update_ms = AP_HAL::millis();
distance_cm = packet.current_distance;
}
} }
/* /*