AP_OpticalFlow: pass mavlink_message_t by const reference

This commit is contained in:
Pierre Kancir 2019-04-30 12:22:49 +02:00 committed by Peter Barker
parent ad4563df2d
commit e7ae1b4fb6
5 changed files with 6 additions and 6 deletions

View File

@ -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

View File

@ -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);

View File

@ -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()) {

View File

@ -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; }

View File

@ -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