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

This commit is contained in:
Randy Mackay 2015-10-02 17:56:31 +09:00
parent 9b96a2c385
commit 330961b524
2 changed files with 7 additions and 0 deletions

View File

@ -1386,6 +1386,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
}
break;
case MAV_CMD_GET_HOME_POSITION:
send_home(copter.ahrs.get_home());
break;
case MAV_CMD_DO_SET_SERVO:
if (copter.ServoRelayEvents.do_set_servo(packet.param1, packet.param2)) {
result = MAV_RESULT_ACCEPTED;

View File

@ -104,6 +104,9 @@ bool Copter::set_home(const Location& loc)
// log ahrs home and ekf origin dataflash
Log_Write_Home_And_Origin();
// send new home location to GCS
GCS_MAVLINK::send_home_all(loc);
// return success
return true;
}