AC_PrecLand: pass mavlink_message_t by const reference

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

View File

@ -251,7 +251,7 @@ bool AC_PrecLand::get_target_velocity_relative_cms(Vector2f& ret)
} }
// handle_msg - Process a LANDING_TARGET mavlink message // handle_msg - Process a LANDING_TARGET mavlink message
void AC_PrecLand::handle_msg(mavlink_message_t* msg) void AC_PrecLand::handle_msg(const mavlink_message_t &msg)
{ {
// run backend update // run backend update
if (_backend != nullptr) { if (_backend != nullptr) {

View File

@ -86,7 +86,7 @@ public:
bool target_acquired(); bool target_acquired();
// process a LANDING_TARGET mavlink message // process a LANDING_TARGET mavlink message
void handle_msg(mavlink_message_t* msg); void handle_msg(const mavlink_message_t &msg);
// parameter var table // parameter var table
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];

View File

@ -35,7 +35,7 @@ public:
virtual float distance_to_target() { return 0.0f; }; virtual float distance_to_target() { return 0.0f; };
// parses a mavlink message from the companion computer // parses a mavlink message from the companion computer
virtual void handle_msg(mavlink_message_t* msg) {}; virtual void handle_msg(const mavlink_message_t &msg) {};
// get bus parameter // get bus parameter
int8_t get_bus(void) const { return _frontend._bus.get(); } int8_t get_bus(void) const { return _frontend._bus.get(); }

View File

@ -42,11 +42,11 @@ float AC_PrecLand_Companion::distance_to_target()
return _distance_to_target; return _distance_to_target;
} }
void AC_PrecLand_Companion::handle_msg(mavlink_message_t* msg) void AC_PrecLand_Companion::handle_msg(const mavlink_message_t &msg)
{ {
// parse mavlink message // parse mavlink message
__mavlink_landing_target_t packet; __mavlink_landing_target_t packet;
mavlink_msg_landing_target_decode(msg, &packet); mavlink_msg_landing_target_decode(&msg, &packet);
_timestamp_us = packet.time_usec; _timestamp_us = packet.time_usec;
_distance_to_target = packet.distance; _distance_to_target = packet.distance;

View File

@ -36,7 +36,7 @@ public:
float distance_to_target() override; float distance_to_target() override;
// parses a mavlink message from the companion computer // parses a mavlink message from the companion computer
void handle_msg(mavlink_message_t* msg) override; void handle_msg(const mavlink_message_t &msg) override;
private: private:
uint64_t _timestamp_us; // timestamp from message uint64_t _timestamp_us; // timestamp from message