mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
Plane: split home-set and home-locked state
This commit is contained in:
parent
c09ccf5b61
commit
ad600fff68
@ -810,7 +810,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
||||
new_home_loc.alt += plane.ahrs.get_home().alt;
|
||||
}
|
||||
plane.ahrs.set_home(new_home_loc);
|
||||
AP::ahrs().set_home_status(HOME_SET_NOT_LOCKED);
|
||||
AP::ahrs().Log_Write_Home_And_Origin();
|
||||
gcs().send_home();
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
@ -1096,7 +1095,6 @@ 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);
|
||||
AP::ahrs().set_home_status(HOME_SET_NOT_LOCKED);
|
||||
AP::ahrs().Log_Write_Home_And_Origin();
|
||||
gcs().send_home();
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
@ -1514,7 +1512,6 @@ 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.ahrs.set_home_status(HOME_SET_NOT_LOCKED);
|
||||
plane.ahrs.Log_Write_Home_And_Origin();
|
||||
gcs().send_home();
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %um",
|
||||
|
@ -110,7 +110,6 @@ void Plane::init_home()
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Init HOME");
|
||||
|
||||
ahrs.set_home(gps.location());
|
||||
ahrs.set_home_status(HOME_SET_NOT_LOCKED);
|
||||
ahrs.Log_Write_Home_And_Origin();
|
||||
gcs().send_home();
|
||||
|
||||
@ -138,7 +137,7 @@ void Plane::update_home()
|
||||
// significantly
|
||||
return;
|
||||
}
|
||||
if (ahrs.home_status() == HOME_SET_NOT_LOCKED) {
|
||||
if (ahrs.home_is_set() && !ahrs.home_is_locked()) {
|
||||
Location loc;
|
||||
if(ahrs.get_position(loc)) {
|
||||
ahrs.set_home(loc);
|
||||
|
@ -937,7 +937,6 @@ void Plane::do_set_home(const AP_Mission::Mission_Command& cmd)
|
||||
init_home();
|
||||
} else {
|
||||
ahrs.set_home(cmd.content.location);
|
||||
ahrs.set_home_status(HOME_SET_NOT_LOCKED);
|
||||
ahrs.Log_Write_Home_And_Origin();
|
||||
gcs().send_home();
|
||||
gcs().send_ekf_origin();
|
||||
|
Loading…
Reference in New Issue
Block a user