diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp index 95844bfb1f..aa3314dde0 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp @@ -86,10 +86,10 @@ void AP_OpticalFlow_MAV::update(void) } // handle OPTICAL_FLOW mavlink messages -void AP_OpticalFlow_MAV::handle_msg(const mavlink_message_t *msg) +void AP_OpticalFlow_MAV::handle_msg(const mavlink_message_t &msg) { mavlink_optical_flow_t packet; - mavlink_msg_optical_flow_decode(msg, &packet); + mavlink_msg_optical_flow_decode(&msg, &packet); // record time message was received // ToDo: add jitter correction diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.h index 4a20929cc7..ddee89af47 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.h @@ -16,7 +16,7 @@ public: void update(void) override; // get update from mavlink - void handle_msg(const mavlink_message_t *msg) override; + void handle_msg(const mavlink_message_t &msg) override; // detect if the sensor is available static AP_OpticalFlow_MAV *detect(OpticalFlow &_frontend); diff --git a/libraries/AP_OpticalFlow/OpticalFlow.cpp b/libraries/AP_OpticalFlow/OpticalFlow.cpp index 2036a40f6e..1534e4f2e8 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/OpticalFlow.cpp @@ -164,7 +164,7 @@ void OpticalFlow::update(void) _flags.healthy = (AP_HAL::millis() - _last_update_ms < 500); } -void OpticalFlow::handle_msg(const mavlink_message_t *msg) +void OpticalFlow::handle_msg(const mavlink_message_t &msg) { // exit immediately if not enabled if (!enabled()) { diff --git a/libraries/AP_OpticalFlow/OpticalFlow.h b/libraries/AP_OpticalFlow/OpticalFlow.h index 796e23e0ad..d894212597 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.h +++ b/libraries/AP_OpticalFlow/OpticalFlow.h @@ -66,7 +66,7 @@ public: void update(void); // handle optical flow mavlink messages - void handle_msg(const mavlink_message_t *msg); + void handle_msg(const mavlink_message_t &msg); // quality - returns the surface quality as a measure from 0 ~ 255 uint8_t quality() const { return _state.surface_quality; } diff --git a/libraries/AP_OpticalFlow/OpticalFlow_backend.h b/libraries/AP_OpticalFlow/OpticalFlow_backend.h index 1b1124886d..a774baaea8 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow_backend.h +++ b/libraries/AP_OpticalFlow/OpticalFlow_backend.h @@ -36,7 +36,7 @@ public: virtual void update() = 0; // handle optical flow mavlink messages - virtual void handle_msg(const mavlink_message_t *msg) {} + virtual void handle_msg(const mavlink_message_t &msg) {} protected: // access to frontend