mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
Update ArduCopter/GCS_Mavlink.cpp
Co-authored-by: Peter Hall <33176108+IamPete1@users.noreply.github.com>
This commit is contained in:
parent
926558a808
commit
8037eaf4cf
@ -1401,10 +1401,7 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
|
|||||||
mavlink_set_home_position_t packet;
|
mavlink_set_home_position_t packet;
|
||||||
mavlink_msg_set_home_position_decode(&msg, &packet);
|
mavlink_msg_set_home_position_decode(&msg, &packet);
|
||||||
if ((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) {
|
if ((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) {
|
||||||
#pragma GCC diagnostic push
|
IGNORE_RETURN(copter.set_home_to_current_location(true));
|
||||||
#pragma GCC diagnostic ignored "-Wunused-result"
|
|
||||||
copter.set_home_to_current_location(true);
|
|
||||||
#pragma GCC diagnostic pop
|
|
||||||
} else {
|
} else {
|
||||||
Location new_home_loc;
|
Location new_home_loc;
|
||||||
new_home_loc.lat = packet.latitude;
|
new_home_loc.lat = packet.latitude;
|
||||||
|
Loading…
Reference in New Issue
Block a user