mirror of https://github.com/ArduPilot/ardupilot
AP_OpticalFlow: pass mavlink_message_t by const reference
This commit is contained in:
parent
ad4563df2d
commit
e7ae1b4fb6
|
@ -86,10 +86,10 @@ void AP_OpticalFlow_MAV::update(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
// handle OPTICAL_FLOW mavlink messages
|
// 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_optical_flow_t packet;
|
||||||
mavlink_msg_optical_flow_decode(msg, &packet);
|
mavlink_msg_optical_flow_decode(&msg, &packet);
|
||||||
|
|
||||||
// record time message was received
|
// record time message was received
|
||||||
// ToDo: add jitter correction
|
// ToDo: add jitter correction
|
||||||
|
|
|
@ -16,7 +16,7 @@ public:
|
||||||
void update(void) override;
|
void update(void) override;
|
||||||
|
|
||||||
// get update from mavlink
|
// 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
|
// detect if the sensor is available
|
||||||
static AP_OpticalFlow_MAV *detect(OpticalFlow &_frontend);
|
static AP_OpticalFlow_MAV *detect(OpticalFlow &_frontend);
|
||||||
|
|
|
@ -164,7 +164,7 @@ void OpticalFlow::update(void)
|
||||||
_flags.healthy = (AP_HAL::millis() - _last_update_ms < 500);
|
_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
|
// exit immediately if not enabled
|
||||||
if (!enabled()) {
|
if (!enabled()) {
|
||||||
|
|
|
@ -66,7 +66,7 @@ public:
|
||||||
void update(void);
|
void update(void);
|
||||||
|
|
||||||
// handle optical flow mavlink messages
|
// 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
|
// quality - returns the surface quality as a measure from 0 ~ 255
|
||||||
uint8_t quality() const { return _state.surface_quality; }
|
uint8_t quality() const { return _state.surface_quality; }
|
||||||
|
|
|
@ -36,7 +36,7 @@ public:
|
||||||
virtual void update() = 0;
|
virtual void update() = 0;
|
||||||
|
|
||||||
// handle optical flow mavlink messages
|
// handle optical flow mavlink messages
|
||||||
virtual void handle_msg(const mavlink_message_t *msg) {}
|
virtual void handle_msg(const mavlink_message_t &msg) {}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
// access to frontend
|
// access to frontend
|
||||||
|
|
Loading…
Reference in New Issue