Plane: move handling of SET_GPS_GLOBAL_ORIGIN up
This commit is contained in:
parent
d0c2898ebc
commit
7e631ba16c
@ -895,22 +895,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|||||||
{
|
{
|
||||||
switch (msg->msgid) {
|
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;
|
|
||||||
plane.set_ekf_origin(ekf_origin);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
|
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
|
||||||
{
|
{
|
||||||
handle_request_data_stream(msg, true);
|
handle_request_data_stream(msg, true);
|
||||||
@ -1955,3 +1939,8 @@ const AP_FWVersion &GCS_MAVLINK_Plane::get_fwver() const
|
|||||||
{
|
{
|
||||||
return plane.fwver;
|
return plane.fwver;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void GCS_MAVLINK_Plane::set_ekf_origin(const Location& loc)
|
||||||
|
{
|
||||||
|
plane.set_ekf_origin(loc);
|
||||||
|
}
|
||||||
|
@ -28,6 +28,7 @@ protected:
|
|||||||
AP_Rally *get_rally() const override;
|
AP_Rally *get_rally() const override;
|
||||||
AP_GPS *get_gps() const override;
|
AP_GPS *get_gps() const override;
|
||||||
const AP_FWVersion &get_fwver() const override;
|
const AP_FWVersion &get_fwver() const override;
|
||||||
|
void set_ekf_origin(const Location& loc) override;
|
||||||
|
|
||||||
uint8_t sysid_my_gcs() const override;
|
uint8_t sysid_my_gcs() const override;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user