From c4ec373b20058d0ac2ae8b8e05db57f2a194a1d8 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Tue, 30 Apr 2019 12:22:49 +0200 Subject: [PATCH] AP_RangeFinder: pass mavlink_message_t by const reference --- libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp | 4 ++-- libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h | 2 +- libraries/AP_RangeFinder/RangeFinder.cpp | 2 +- libraries/AP_RangeFinder/RangeFinder.h | 2 +- libraries/AP_RangeFinder/RangeFinder_Backend.h | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp index 3941164134..cae9a7db72 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp @@ -46,10 +46,10 @@ bool AP_RangeFinder_MAVLink::detect() /* Set the distance based on a MAVLINK message */ -void AP_RangeFinder_MAVLink::handle_msg(mavlink_message_t *msg) +void AP_RangeFinder_MAVLink::handle_msg(const mavlink_message_t &msg) { 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 if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_270) { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h index f489a471ad..8e5a783232 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h @@ -20,7 +20,7 @@ public: void update(void) override; // Get update from mavlink - void handle_msg(mavlink_message_t *msg) override; + void handle_msg(const mavlink_message_t &msg) override; protected: diff --git a/libraries/AP_RangeFinder/RangeFinder.cpp b/libraries/AP_RangeFinder/RangeFinder.cpp index ffc0efd428..7512c207d8 100644 --- a/libraries/AP_RangeFinder/RangeFinder.cpp +++ b/libraries/AP_RangeFinder/RangeFinder.cpp @@ -541,7 +541,7 @@ RangeFinder::RangeFinder_Status RangeFinder::status_orient(enum Rotation orienta return backend->status(); } -void RangeFinder::handle_msg(mavlink_message_t *msg) +void RangeFinder::handle_msg(const mavlink_message_t &msg) { uint8_t i; for (i=0; i