mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: move handling of SET_GPS_GLOBAL_ORIGIN up
This commit is contained in:
parent
0afe1e7473
commit
b84e40a804
@ -644,22 +644,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
||||
{
|
||||
switch (msg->msgid) {
|
||||
|
||||
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;
|
||||
rover.set_ekf_origin(ekf_origin);
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
|
||||
{
|
||||
handle_request_data_stream(msg, true);
|
||||
@ -1386,3 +1370,8 @@ const AP_FWVersion &GCS_MAVLINK_Rover::get_fwver() const
|
||||
{
|
||||
return rover.fwver;
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Rover::set_ekf_origin(const Location& loc)
|
||||
{
|
||||
rover.set_ekf_origin(loc);
|
||||
}
|
||||
|
@ -24,6 +24,7 @@ protected:
|
||||
AP_GPS *get_gps() const override;
|
||||
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
|
||||
const AP_FWVersion &get_fwver() const override;
|
||||
void set_ekf_origin(const Location& loc) override;
|
||||
|
||||
uint8_t sysid_my_gcs() const override;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user