Browse Source

AP_Proximity: pass mavlink_message_t by const reference

master
Pierre Kancir 6 years ago committed by Peter Barker
parent
commit
5b745aa1f1
  1. 2
      libraries/AP_Proximity/AP_Proximity.cpp
  2. 2
      libraries/AP_Proximity/AP_Proximity.h
  3. 2
      libraries/AP_Proximity/AP_Proximity_Backend.h
  4. 10
      libraries/AP_Proximity/AP_Proximity_MAV.cpp
  5. 2
      libraries/AP_Proximity/AP_Proximity_MAV.h

2
libraries/AP_Proximity/AP_Proximity.cpp

@ -269,7 +269,7 @@ AP_Proximity::Proximity_Status AP_Proximity::get_status() const @@ -269,7 +269,7 @@ AP_Proximity::Proximity_Status AP_Proximity::get_status() const
}
// handle mavlink DISTANCE_SENSOR messages
void AP_Proximity::handle_msg(mavlink_message_t *msg)
void AP_Proximity::handle_msg(const mavlink_message_t &msg)
{
for (uint8_t i=0; i<num_instances; i++) {
if ((drivers[i] != nullptr) && (_type[i] != Proximity_Type_None)) {

2
libraries/AP_Proximity/AP_Proximity.h

@ -128,7 +128,7 @@ public: @@ -128,7 +128,7 @@ public:
float distance_min() const;
// handle mavlink DISTANCE_SENSOR messages
void handle_msg(mavlink_message_t *msg);
void handle_msg(const mavlink_message_t &msg);
// The Proximity_State structure is filled in by the backend driver
struct Proximity_State {

2
libraries/AP_Proximity/AP_Proximity_Backend.h

@ -43,7 +43,7 @@ public: @@ -43,7 +43,7 @@ public:
virtual bool get_upward_distance(float &distance) const { return false; }
// handle mavlink DISTANCE_SENSOR messages
virtual void handle_msg(mavlink_message_t *msg) {}
virtual void handle_msg(const mavlink_message_t &msg) {}
// get distance in meters in a particular direction in degrees (0 is forward, clockwise)
// returns true on successful read and places distance in distance

10
libraries/AP_Proximity/AP_Proximity_MAV.cpp

@ -57,11 +57,11 @@ bool AP_Proximity_MAV::get_upward_distance(float &distance) const @@ -57,11 +57,11 @@ bool AP_Proximity_MAV::get_upward_distance(float &distance) const
}
// handle mavlink DISTANCE_SENSOR messages
void AP_Proximity_MAV::handle_msg(mavlink_message_t *msg)
void AP_Proximity_MAV::handle_msg(const mavlink_message_t &msg)
{
if (msg->msgid == MAVLINK_MSG_ID_DISTANCE_SENSOR) {
if (msg.msgid == MAVLINK_MSG_ID_DISTANCE_SENSOR) {
mavlink_distance_sensor_t packet;
mavlink_msg_distance_sensor_decode(msg, &packet);
mavlink_msg_distance_sensor_decode(&msg, &packet);
// store distance to appropriate sector based on orientation field
if (packet.orientation <= MAV_SENSOR_ROTATION_YAW_315) {
@ -83,9 +83,9 @@ void AP_Proximity_MAV::handle_msg(mavlink_message_t *msg) @@ -83,9 +83,9 @@ void AP_Proximity_MAV::handle_msg(mavlink_message_t *msg)
return;
}
if (msg->msgid == MAVLINK_MSG_ID_OBSTACLE_DISTANCE) {
if (msg.msgid == MAVLINK_MSG_ID_OBSTACLE_DISTANCE) {
mavlink_obstacle_distance_t packet;
mavlink_msg_obstacle_distance_decode(msg, &packet);
mavlink_msg_obstacle_distance_decode(&msg, &packet);
// check increment (message's sector width)
float increment;

2
libraries/AP_Proximity/AP_Proximity_MAV.h

@ -21,7 +21,7 @@ public: @@ -21,7 +21,7 @@ public:
bool get_upward_distance(float &distance) const override;
// handle mavlink DISTANCE_SENSOR messages
void handle_msg(mavlink_message_t *msg) override;
void handle_msg(const mavlink_message_t &msg) override;
private:

Loading…
Cancel
Save