GCS_MAVLink: move gps inject handling up

Also, make AP_GPS responsible for decoding inject packets
This commit is contained in:
Peter Barker 2017-07-25 17:58:25 +10:00 committed by Francisco Ferreira
parent c25bd13b78
commit 60ffe00164
2 changed files with 2 additions and 13 deletions

View File

@ -263,8 +263,6 @@ protected:
void handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio);
void handle_serial_control(mavlink_message_t *msg, AP_GPS &gps);
void handle_gps_inject(const mavlink_message_t *msg, AP_GPS &gps);
void handle_common_message(mavlink_message_t *msg);
void handle_setup_signing(const mavlink_message_t *msg);
uint8_t handle_preflight_reboot(const mavlink_command_long_t &packet, bool disable_overrides);

View File

@ -755,17 +755,6 @@ mission_ack:
return mission_is_complete;
}
void
GCS_MAVLINK::handle_gps_inject(const mavlink_message_t *msg, AP_GPS &gps)
{
mavlink_gps_inject_data_t packet;
mavlink_msg_gps_inject_data_decode(msg, &packet);
//TODO: check target
gps.inject_data(packet.data, packet.len);
}
// send a message using mavlink, handling message queueing
void GCS_MAVLINK::send_message(enum ap_message id)
{
@ -1816,6 +1805,8 @@ void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg)
case MAVLINK_MSG_ID_GPS_INPUT:
/* fall through */
case MAVLINK_MSG_ID_HIL_GPS:
/* fall through */
case MAVLINK_MSG_ID_GPS_INJECT_DATA:
handle_common_gps_message(msg);
break;