mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 02:13:57 -04:00
Copter: send home position when home is set or get-home msg received
This commit is contained in:
parent
9b96a2c385
commit
330961b524
@ -1386,6 +1386,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MAV_CMD_GET_HOME_POSITION:
|
||||||
|
send_home(copter.ahrs.get_home());
|
||||||
|
break;
|
||||||
|
|
||||||
case MAV_CMD_DO_SET_SERVO:
|
case MAV_CMD_DO_SET_SERVO:
|
||||||
if (copter.ServoRelayEvents.do_set_servo(packet.param1, packet.param2)) {
|
if (copter.ServoRelayEvents.do_set_servo(packet.param1, packet.param2)) {
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
|
@ -104,6 +104,9 @@ bool Copter::set_home(const Location& loc)
|
|||||||
// log ahrs home and ekf origin dataflash
|
// log ahrs home and ekf origin dataflash
|
||||||
Log_Write_Home_And_Origin();
|
Log_Write_Home_And_Origin();
|
||||||
|
|
||||||
|
// send new home location to GCS
|
||||||
|
GCS_MAVLINK::send_home_all(loc);
|
||||||
|
|
||||||
// return success
|
// return success
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user