mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RangeFinder: pass mavlink_message_t by const reference
This commit is contained in:
parent
5b745aa1f1
commit
c4ec373b20
@ -46,10 +46,10 @@ bool AP_RangeFinder_MAVLink::detect()
|
|||||||
/*
|
/*
|
||||||
Set the distance based on a MAVLINK message
|
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_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
|
// only accept distances for downward facing sensors
|
||||||
if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_270) {
|
if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_270) {
|
||||||
|
@ -20,7 +20,7 @@ public:
|
|||||||
void update(void) override;
|
void update(void) override;
|
||||||
|
|
||||||
// Get update from mavlink
|
// Get update from mavlink
|
||||||
void handle_msg(mavlink_message_t *msg) override;
|
void handle_msg(const mavlink_message_t &msg) override;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
@ -541,7 +541,7 @@ RangeFinder::RangeFinder_Status RangeFinder::status_orient(enum Rotation orienta
|
|||||||
return backend->status();
|
return backend->status();
|
||||||
}
|
}
|
||||||
|
|
||||||
void RangeFinder::handle_msg(mavlink_message_t *msg)
|
void RangeFinder::handle_msg(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
for (i=0; i<num_instances; i++) {
|
for (i=0; i<num_instances; i++) {
|
||||||
|
@ -119,7 +119,7 @@ public:
|
|||||||
void update(void);
|
void update(void);
|
||||||
|
|
||||||
// Handle an incoming DISTANCE_SENSOR message (from a MAVLink enabled range finder)
|
// Handle an incoming DISTANCE_SENSOR message (from a MAVLink enabled range finder)
|
||||||
void handle_msg(mavlink_message_t *msg);
|
void handle_msg(const mavlink_message_t &msg);
|
||||||
|
|
||||||
// return true if we have a range finder with the specified orientation
|
// return true if we have a range finder with the specified orientation
|
||||||
bool has_orientation(enum Rotation orientation) const;
|
bool has_orientation(enum Rotation orientation) const;
|
||||||
|
@ -31,7 +31,7 @@ public:
|
|||||||
// update the state structure
|
// update the state structure
|
||||||
virtual void update() = 0;
|
virtual void update() = 0;
|
||||||
|
|
||||||
virtual void handle_msg(mavlink_message_t *msg) { return; }
|
virtual void handle_msg(const mavlink_message_t &msg) { return; }
|
||||||
|
|
||||||
enum Rotation orientation() const { return (Rotation)params.orientation.get(); }
|
enum Rotation orientation() const { return (Rotation)params.orientation.get(); }
|
||||||
uint16_t distance_cm() const { return state.distance_cm; }
|
uint16_t distance_cm() const { return state.distance_cm; }
|
||||||
|
Loading…
Reference in New Issue
Block a user