mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: allow Copter to emit MISSION_STATE_PAUSED when paused in auto
This commit is contained in:
parent
15ec9f6f82
commit
f33e5e7847
|
@ -579,6 +579,14 @@ const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
|
|||
MAV_STREAM_TERMINATOR // must have this at end of stream_entries
|
||||
};
|
||||
|
||||
MISSION_STATE GCS_MAVLINK_Copter::mission_state(const class AP_Mission &mission) const
|
||||
{
|
||||
if (copter.mode_auto.paused()) {
|
||||
return MISSION_STATE_PAUSED;
|
||||
}
|
||||
return GCS_MAVLINK::mission_state(mission);
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK_Copter::handle_guided_request(AP_Mission::Mission_Command &cmd)
|
||||
{
|
||||
#if MODE_AUTO_ENABLED == ENABLED
|
||||
|
|
|
@ -55,6 +55,8 @@ protected:
|
|||
|
||||
private:
|
||||
|
||||
MISSION_STATE mission_state(const class AP_Mission &mission) const override;
|
||||
|
||||
void handleMessage(const mavlink_message_t &msg) override;
|
||||
void handle_command_ack(const mavlink_message_t &msg) override;
|
||||
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
|
||||
|
|
|
@ -462,6 +462,7 @@ public:
|
|||
// pause continue in auto mode
|
||||
bool pause() override;
|
||||
bool resume() override;
|
||||
bool paused() const;
|
||||
|
||||
bool loiter_start();
|
||||
void rtl_start();
|
||||
|
|
|
@ -2251,4 +2251,9 @@ bool ModeAuto::resume()
|
|||
return true;
|
||||
}
|
||||
|
||||
bool ModeAuto::paused() const
|
||||
{
|
||||
return wp_nav->paused();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue