mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Sub: move handling of SET_GPS_GLOBAL_ORIGIN up
This commit is contained in:
parent
b84e40a804
commit
5b7f396e23
@ -891,22 +891,6 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN:
|
||||
{
|
||||
mavlink_set_gps_global_origin_t packet;
|
||||
mavlink_msg_set_gps_global_origin_decode(msg, &packet);
|
||||
// sanity check location
|
||||
if (!check_latlng(packet.latitude, packet.longitude)) {
|
||||
break;
|
||||
}
|
||||
Location ekf_origin {};
|
||||
ekf_origin.lat = packet.latitude;
|
||||
ekf_origin.lng = packet.longitude;
|
||||
ekf_origin.alt = packet.altitude / 10;
|
||||
sub.set_ekf_origin(ekf_origin);
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: { // MAV ID: 66
|
||||
handle_request_data_stream(msg, false);
|
||||
break;
|
||||
@ -1636,5 +1620,10 @@ const AP_FWVersion &GCS_MAVLINK_Sub::get_fwver() const
|
||||
return sub.fwver;
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Sub::set_ekf_origin(const Location& loc)
|
||||
{
|
||||
sub.set_ekf_origin(loc);
|
||||
}
|
||||
|
||||
// dummy method to avoid linking AFS
|
||||
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate) { return false; }
|
||||
|
@ -21,6 +21,7 @@ protected:
|
||||
AP_ServoRelayEvents *get_servorelayevents() const override;
|
||||
AP_GPS *get_gps() const override;
|
||||
const AP_FWVersion &get_fwver() const override;
|
||||
void set_ekf_origin(const Location& loc) override;
|
||||
|
||||
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user