From 4180345fdc46d6e60e72e094641e420e869acefd Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Tue, 30 Apr 2019 12:22:50 +0200 Subject: [PATCH] AntennaTracker: pass mavlink_message_t by const reference --- AntennaTracker/GCS_Mavlink.cpp | 22 +++++++++++----------- AntennaTracker/GCS_Mavlink.h | 4 ++-- 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index bcac25096a..14b4ec5176 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -294,7 +294,7 @@ const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = { MAVLINK_MSG_ID_SCALED_PRESSUREs */ void GCS_MAVLINK_Tracker::packetReceived(const mavlink_status_t &status, - mavlink_message_t &msg) + const mavlink_message_t &msg) { // return immediately if sysid doesn't match our target sysid if ((tracker.g.sysid_target != 0) && (tracker.g.sysid_target != msg.sysid)) { @@ -420,16 +420,16 @@ bool GCS_MAVLINK_Tracker::set_home(const Location& loc, bool lock) { return tracker.set_home(loc); } -void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg) +void GCS_MAVLINK_Tracker::handleMessage(const mavlink_message_t &msg) { - switch (msg->msgid) { + switch (msg.msgid) { // When mavproxy 'wp sethome' case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST: { // decode mavlink_mission_write_partial_list_t packet; - mavlink_msg_mission_write_partial_list_decode(msg, &packet); + mavlink_msg_mission_write_partial_list_decode(&msg, &packet); if (packet.start_index == 0) { // New home at wp index 0. Ask for it @@ -446,7 +446,7 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg) mavlink_mission_item_t packet; MAV_MISSION_RESULT result = MAV_MISSION_ACCEPTED; - mavlink_msg_mission_item_decode(msg, &packet); + mavlink_msg_mission_item_decode(&msg, &packet); struct Location tell_command; @@ -528,8 +528,8 @@ mission_failed: // we are rejecting the mission/waypoint mavlink_msg_mission_ack_send( chan, - msg->sysid, - msg->compid, + msg.sysid, + msg.compid, result, MAV_MISSION_TYPE_MISSION); break; @@ -538,7 +538,7 @@ mission_failed: case MAVLINK_MSG_ID_MANUAL_CONTROL: { mavlink_manual_control_t packet; - mavlink_msg_manual_control_decode(msg, &packet); + mavlink_msg_manual_control_decode(&msg, &packet); tracker.tracking_manual_control(packet); break; } @@ -547,7 +547,7 @@ mission_failed: { // decode mavlink_global_position_int_t packet; - mavlink_msg_global_position_int_decode(msg, &packet); + mavlink_msg_global_position_int_decode(&msg, &packet); tracker.tracking_update_position(packet); break; } @@ -556,7 +556,7 @@ mission_failed: { // decode mavlink_scaled_pressure_t packet; - mavlink_msg_scaled_pressure_decode(msg, &packet); + mavlink_msg_scaled_pressure_decode(&msg, &packet); tracker.tracking_update_pressure(packet); break; } @@ -649,7 +649,7 @@ void GCS_MAVLINK_Tracker::send_global_position_int() /* dummy methods to avoid having to link against AP_Camera */ -void AP_Camera::control_msg(mavlink_message_t const*) {} +void AP_Camera::control_msg(const mavlink_message_t &) {} void AP_Camera::configure(float, float, float, float, float, float, float) {} void AP_Camera::control(float, float, float, float, float, float) {} void AP_Camera::send_feedback(mavlink_channel_t chan) {} diff --git a/AntennaTracker/GCS_Mavlink.h b/AntennaTracker/GCS_Mavlink.h index 7134ca73e7..3c0967b88b 100644 --- a/AntennaTracker/GCS_Mavlink.h +++ b/AntennaTracker/GCS_Mavlink.h @@ -34,9 +34,9 @@ protected: private: - void packetReceived(const mavlink_status_t &status, mavlink_message_t &msg) override; + void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override; void mavlink_check_target(const mavlink_message_t &msg); - void handleMessage(mavlink_message_t * msg) override; + void handleMessage(const mavlink_message_t &msg) override; bool handle_guided_request(AP_Mission::Mission_Command &cmd) override; void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override; void send_global_position_int() override;