Plane: send home position when home is set or get-home msg received

This commit is contained in:
Randy Mackay 2015-10-02 20:35:32 +09:00
parent 93b0dd4d61
commit d54e28e129
3 changed files with 8 additions and 0 deletions

View File

@ -1304,6 +1304,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
}
break;
case MAV_CMD_GET_HOME_POSITION:
send_home(plane.ahrs.get_home());
break;
case MAV_CMD_DO_SET_MODE:
switch ((uint16_t)packet.param1) {
case MAV_MODE_MANUAL_ARMED:
@ -1448,6 +1452,7 @@ void GCS_MAVLINK::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);
result = MAV_RESULT_ACCEPTED;
plane.gcs_send_text_fmt(PSTR("set home to %.6f %.6f at %um"),
(double)(new_home_loc.lat*1.0e-7f),

View File

@ -105,6 +105,7 @@ void Plane::init_home()
ahrs.set_home(gps.location());
home_is_set = HOME_SET_NOT_LOCKED;
Log_Write_Home_And_Origin();
GCS_MAVLINK::send_home_all(gps.location());
gcs_send_text_fmt(PSTR("gps alt: %lu"), (unsigned long)home.alt);
@ -126,6 +127,7 @@ void Plane::update_home()
if (home_is_set == HOME_SET_NOT_LOCKED) {
ahrs.set_home(gps.location());
Log_Write_Home_And_Origin();
GCS_MAVLINK::send_home_all(gps.location());
}
barometer.update_calibration();
}

View File

@ -862,6 +862,7 @@ void Plane::do_set_home(const AP_Mission::Mission_Command& cmd)
ahrs.set_home(cmd.content.location);
home_is_set = HOME_SET_NOT_LOCKED;
Log_Write_Home_And_Origin();
GCS_MAVLINK::send_home_all(cmd.content.location);
}
}