Browse Source

AP_VisualOdom: pass mavlink_message_t by const reference

master
Pierre Kancir 6 years ago committed by Peter Barker
parent
commit
9a734c1fc7
  1. 2
      libraries/AP_VisualOdom/AP_VisualOdom.cpp
  2. 2
      libraries/AP_VisualOdom/AP_VisualOdom.h
  3. 2
      libraries/AP_VisualOdom/AP_VisualOdom_Backend.h
  4. 4
      libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp
  5. 2
      libraries/AP_VisualOdom/AP_VisualOdom_MAV.h

2
libraries/AP_VisualOdom/AP_VisualOdom.cpp

@ -126,7 +126,7 @@ bool AP_VisualOdom::healthy() const @@ -126,7 +126,7 @@ bool AP_VisualOdom::healthy() const
}
// consume VISION_POSITION_DELTA MAVLink message
void AP_VisualOdom::handle_msg(mavlink_message_t *msg)
void AP_VisualOdom::handle_msg(const mavlink_message_t &msg)
{
// exit immediately if not enabled
if (!enabled()) {

2
libraries/AP_VisualOdom/AP_VisualOdom.h

@ -69,7 +69,7 @@ public: @@ -69,7 +69,7 @@ public:
const Vector3f &get_pos_offset(void) const { return _pos_offset; }
// consume data from MAVLink messages
void handle_msg(mavlink_message_t *msg);
void handle_msg(const mavlink_message_t &msg);
static const struct AP_Param::GroupInfo var_info[];

2
libraries/AP_VisualOdom/AP_VisualOdom_Backend.h

@ -25,7 +25,7 @@ public: @@ -25,7 +25,7 @@ public:
AP_VisualOdom_Backend(AP_VisualOdom &frontend);
// consume VISION_POSITION_DELTA MAVLink message
virtual void handle_msg(mavlink_message_t *msg) {};
virtual void handle_msg(const mavlink_message_t &msg) {};
protected:

4
libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp

@ -26,11 +26,11 @@ AP_VisualOdom_MAV::AP_VisualOdom_MAV(AP_VisualOdom &frontend) : @@ -26,11 +26,11 @@ AP_VisualOdom_MAV::AP_VisualOdom_MAV(AP_VisualOdom &frontend) :
}
// consume VISIOIN_POSITION_DELTA MAVLink message
void AP_VisualOdom_MAV::handle_msg(mavlink_message_t *msg)
void AP_VisualOdom_MAV::handle_msg(const mavlink_message_t &msg)
{
// decode message
mavlink_vision_position_delta_t packet;
mavlink_msg_vision_position_delta_decode(msg, &packet);
mavlink_msg_vision_position_delta_decode(&msg, &packet);
const Vector3f angle_delta(packet.angle_delta[0], packet.angle_delta[1], packet.angle_delta[2]);
const Vector3f position_delta(packet.position_delta[0], packet.position_delta[1], packet.position_delta[2]);

2
libraries/AP_VisualOdom/AP_VisualOdom_MAV.h

@ -10,5 +10,5 @@ public: @@ -10,5 +10,5 @@ public:
AP_VisualOdom_MAV(AP_VisualOdom &frontend);
// consume VISION_POSITION_DELTA MAVLink message
void handle_msg(mavlink_message_t *msg) override;
void handle_msg(const mavlink_message_t &msg) override;
};

Loading…
Cancel
Save