|
|
|
@ -1462,7 +1462,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
@@ -1462,7 +1462,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
plane.ahrs.set_home(new_home_loc); |
|
|
|
|
plane.home_is_set = HOME_SET_NOT_LOCKED; |
|
|
|
|
plane.Log_Write_Home_And_Origin(); |
|
|
|
|
GCS_MAVLINK::send_home_all(new_home_loc); |
|
|
|
|
gcs().send_home(new_home_loc); |
|
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %um", |
|
|
|
|
(double)(new_home_loc.lat*1.0e-7f), |
|
|
|
@ -1953,7 +1953,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
@@ -1953,7 +1953,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
plane.ahrs.set_home(new_home_loc); |
|
|
|
|
plane.home_is_set = HOME_SET_NOT_LOCKED; |
|
|
|
|
plane.Log_Write_Home_And_Origin(); |
|
|
|
|
GCS_MAVLINK::send_home_all(new_home_loc); |
|
|
|
|
gcs().send_home(new_home_loc); |
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %um", |
|
|
|
|
(double)(new_home_loc.lat*1.0e-7f), |
|
|
|
|
(double)(new_home_loc.lng*1.0e-7f), |
|
|
|
|