GCS_MAVLink: allow Copter to emit MISSION_STATE_PAUSED when paused in auto
This commit is contained in:
parent
a3cc0f137c
commit
15ec9f6f82
@ -325,7 +325,7 @@ public:
|
|||||||
|
|
||||||
// generate a MISSION_STATE enumeration value for where the
|
// generate a MISSION_STATE enumeration value for where the
|
||||||
// mission is up to:
|
// mission is up to:
|
||||||
MISSION_STATE mission_state(const class AP_Mission &mission) const;
|
virtual MISSION_STATE mission_state(const class AP_Mission &mission) const;
|
||||||
// send a mission_current message for the supplied waypoint
|
// send a mission_current message for the supplied waypoint
|
||||||
void send_mission_current(const class AP_Mission &mission, uint16_t seq);
|
void send_mission_current(const class AP_Mission &mission, uint16_t seq);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user