|
|
|
@ -900,14 +900,14 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
@@ -900,14 +900,14 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
new_home_loc.alt = packet.z * 100; |
|
|
|
|
// handle relative altitude
|
|
|
|
|
if (packet.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT || packet.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT_INT) { |
|
|
|
|
if (plane.home_is_set == HOME_UNSET) { |
|
|
|
|
if (!AP::ahrs().home_is_set()) { |
|
|
|
|
// cannot use relative altitude if home is not set
|
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
new_home_loc.alt += plane.ahrs.get_home().alt; |
|
|
|
|
} |
|
|
|
|
plane.ahrs.set_home(new_home_loc); |
|
|
|
|
plane.home_is_set = HOME_SET_NOT_LOCKED; |
|
|
|
|
AP::ahrs().set_home_status(HOME_SET_NOT_LOCKED); |
|
|
|
|
plane.Log_Write_Home_And_Origin(); |
|
|
|
|
gcs().send_home(new_home_loc); |
|
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|
@ -1194,7 +1194,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
@@ -1194,7 +1194,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_CMD_GET_HOME_POSITION: |
|
|
|
|
if (plane.home_is_set != HOME_UNSET) { |
|
|
|
|
if (AP::ahrs().home_is_set()) { |
|
|
|
|
send_home(plane.ahrs.get_home()); |
|
|
|
|
Location ekf_origin; |
|
|
|
|
if (plane.ahrs.get_origin(ekf_origin)) { |
|
|
|
@ -1300,7 +1300,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
@@ -1300,7 +1300,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
new_home_loc.lng = (int32_t)(packet.param6 * 1.0e7f); |
|
|
|
|
new_home_loc.alt = (int32_t)(packet.param7 * 100.0f); |
|
|
|
|
plane.ahrs.set_home(new_home_loc); |
|
|
|
|
plane.home_is_set = HOME_SET_NOT_LOCKED; |
|
|
|
|
AP::ahrs().set_home_status(HOME_SET_NOT_LOCKED); |
|
|
|
|
plane.Log_Write_Home_And_Origin(); |
|
|
|
|
gcs().send_home(new_home_loc); |
|
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|
@ -1712,7 +1712,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
@@ -1712,7 +1712,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
new_home_loc.lng = packet.longitude; |
|
|
|
|
new_home_loc.alt = packet.altitude / 10; |
|
|
|
|
plane.ahrs.set_home(new_home_loc); |
|
|
|
|
plane.home_is_set = HOME_SET_NOT_LOCKED; |
|
|
|
|
plane.ahrs.set_home_status(HOME_SET_NOT_LOCKED); |
|
|
|
|
plane.Log_Write_Home_And_Origin(); |
|
|
|
|
gcs().send_home(new_home_loc); |
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %um", |
|
|
|
|