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

This commit is contained in:
Randy Mackay 2015-10-02 20:53:28 +09:00
parent 17ed125e41
commit 012b632d09
2 changed files with 5 additions and 0 deletions

View File

@ -667,6 +667,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
}
break;
case MAV_CMD_GET_HOME_POSITION:
send_home(tracker.ahrs.get_home());
break;
case MAV_CMD_DO_SET_MODE:
switch ((uint16_t)packet.param1) {
case MAV_MODE_MANUAL_ARMED:

View File

@ -165,6 +165,7 @@ void Tracker::set_home(struct Location temp)
{
set_home_eeprom(temp);
current_loc = temp;
GCS_MAVLINK::send_home_all(temp);
}
void Tracker::arm_servos()