Browse Source

Copter: move handling of SET_GPS_GLOBAL_ORIGIN up

master
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
0afe1e7473
  1. 22
      ArduCopter/GCS_Mavlink.cpp
  2. 1
      ArduCopter/GCS_Mavlink.h

22
ArduCopter/GCS_Mavlink.cpp

@ -742,22 +742,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) @@ -742,22 +742,6 @@ void GCS_MAVLINK_Copter::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;
copter.set_ekf_origin(ekf_origin);
break;
}
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: // MAV ID: 66
{
handle_request_data_stream(msg, false);
@ -1767,3 +1751,9 @@ const AP_FWVersion &GCS_MAVLINK_Copter::get_fwver() const @@ -1767,3 +1751,9 @@ const AP_FWVersion &GCS_MAVLINK_Copter::get_fwver() const
{
return copter.fwver;
}
void GCS_MAVLINK_Copter::set_ekf_origin(const Location& loc)
{
copter.set_ekf_origin(loc);
}

1
ArduCopter/GCS_Mavlink.h

@ -27,6 +27,7 @@ protected: @@ -27,6 +27,7 @@ protected:
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) 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