Browse Source

Rover: move handling of SET_GPS_GLOBAL_ORIGIN up

mission-4.1.18
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
b84e40a804
  1. 21
      APMrover2/GCS_Mavlink.cpp
  2. 1
      APMrover2/GCS_Mavlink.h

21
APMrover2/GCS_Mavlink.cpp

@ -644,22 +644,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) @@ -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 @@ -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);
}

1
APMrover2/GCS_Mavlink.h

@ -24,6 +24,7 @@ protected: @@ -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…
Cancel
Save