diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index b2e29dc674..1d1d3ac47f 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -103,9 +103,9 @@ public: // handle terrain data and reports from GCS void send_terrain_report(mavlink_channel_t chan, const Location &loc, bool extrapolate); - void handle_data(mavlink_channel_t chan, mavlink_message_t *msg); - void handle_terrain_check(mavlink_channel_t chan, mavlink_message_t *msg); - void handle_terrain_data(mavlink_message_t *msg); + void handle_data(mavlink_channel_t chan, const mavlink_message_t &msg); + void handle_terrain_check(mavlink_channel_t chan, const mavlink_message_t &msg); + void handle_terrain_data(const mavlink_message_t &msg); /* find the terrain height in meters above sea level for a location diff --git a/libraries/AP_Terrain/TerrainGCS.cpp b/libraries/AP_Terrain/TerrainGCS.cpp index e25a71fb41..bc77579f13 100644 --- a/libraries/AP_Terrain/TerrainGCS.cpp +++ b/libraries/AP_Terrain/TerrainGCS.cpp @@ -188,11 +188,11 @@ void AP_Terrain::get_statistics(uint16_t &pending, uint16_t &loaded) /* handle terrain messages from GCS */ -void AP_Terrain::handle_data(mavlink_channel_t chan, mavlink_message_t *msg) +void AP_Terrain::handle_data(mavlink_channel_t chan, const mavlink_message_t &msg) { - if (msg->msgid == MAVLINK_MSG_ID_TERRAIN_DATA) { + if (msg.msgid == MAVLINK_MSG_ID_TERRAIN_DATA) { handle_terrain_data(msg); - } else if (msg->msgid == MAVLINK_MSG_ID_TERRAIN_CHECK) { + } else if (msg.msgid == MAVLINK_MSG_ID_TERRAIN_CHECK) { handle_terrain_check(chan, msg); } } @@ -243,10 +243,10 @@ void AP_Terrain::send_terrain_report(mavlink_channel_t chan, const Location &loc /* handle TERRAIN_CHECK messages from GCS */ -void AP_Terrain::handle_terrain_check(mavlink_channel_t chan, mavlink_message_t *msg) +void AP_Terrain::handle_terrain_check(mavlink_channel_t chan, const mavlink_message_t &msg) { mavlink_terrain_check_t packet; - mavlink_msg_terrain_check_decode(msg, &packet); + mavlink_msg_terrain_check_decode(&msg, &packet); Location loc; loc.lat = packet.lat; loc.lng = packet.lon; @@ -256,10 +256,10 @@ void AP_Terrain::handle_terrain_check(mavlink_channel_t chan, mavlink_message_t /* handle TERRAIN_DATA messages from GCS */ -void AP_Terrain::handle_terrain_data(mavlink_message_t *msg) +void AP_Terrain::handle_terrain_data(const mavlink_message_t &msg) { mavlink_terrain_data_t packet; - mavlink_msg_terrain_data_decode(msg, &packet); + mavlink_msg_terrain_data_decode(&msg, &packet); uint16_t i; for (i=0; i