Tracker: send home position when home is set or get-home msg received
This commit is contained in:
parent
17ed125e41
commit
012b632d09
@ -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:
|
||||
|
@ -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()
|
||||
|
Loading…
Reference in New Issue
Block a user