Copter: Pause/Continue in AUTO and GUIDED modes with SCurves

This commit is contained in:
m 2022-01-27 21:36:21 +03:00 committed by Andrew Tridgell
parent 16e3ef06fa
commit 280792abef
4 changed files with 77 additions and 41 deletions

View File

@ -995,32 +995,25 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
MAV_RESULT GCS_MAVLINK_Copter::handle_command_pause_continue(const mavlink_command_int_t &packet) MAV_RESULT GCS_MAVLINK_Copter::handle_command_pause_continue(const mavlink_command_int_t &packet)
{ {
#if MODE_AUTO_ENABLED // requested pause
if (copter.flightmode->mode_number() != Mode::Number::AUTO) { if ((uint8_t) packet.param1 == 0) {
// only supported in AUTO mode if (copter.flightmode->pause()) {
return MAV_RESULT_ACCEPTED;
}
send_text(MAV_SEVERITY_INFO, "Failed to pause");
return MAV_RESULT_FAILED; return MAV_RESULT_FAILED;
} }
// requested pause from GCS // requested resume
if ((int8_t) packet.param1 == 0) { if ((uint8_t) packet.param1 == 1) {
// copter.mode_auto.mission.stop(); if (copter.flightmode->resume()) {
copter.mode_auto.pause_mission();
gcs().send_text(MAV_SEVERITY_INFO, "Paused mission");
return MAV_RESULT_ACCEPTED; return MAV_RESULT_ACCEPTED;
} }
send_text(MAV_SEVERITY_INFO, "Failed to resume");
// requested resume from GCS
if ((int8_t) packet.param1 == 1) {
// copter.mode_auto.mission.resume();
copter.mode_auto.continue_mission();
gcs().send_text(MAV_SEVERITY_INFO, "Resumed mission");
return MAV_RESULT_ACCEPTED;
}
#endif
// fail pause or continue
return MAV_RESULT_FAILED; return MAV_RESULT_FAILED;
} }
return MAV_RESULT_DENIED;
}
void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg) void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg)
{ {

View File

@ -110,6 +110,10 @@ public:
// returns true if pilot's yaw input should be used to adjust vehicle's heading // returns true if pilot's yaw input should be used to adjust vehicle's heading
virtual bool use_pilot_yaw() const {return true; } virtual bool use_pilot_yaw() const {return true; }
// pause and resume a mode
virtual bool pause() { return false; };
virtual bool resume() { return false; };
protected: protected:
// helper functions // helper functions
@ -419,6 +423,10 @@ public:
// Auto // Auto
SubMode mode() const { return _mode; } SubMode mode() const { return _mode; }
// pause continue in auto mode
bool pause() override;
bool resume() override;
bool loiter_start(); bool loiter_start();
void rtl_start(); void rtl_start();
void takeoff_start(const Location& dest_loc); void takeoff_start(const Location& dest_loc);
@ -428,9 +436,6 @@ public:
void circle_start(); void circle_start();
void nav_guided_start(); void nav_guided_start();
void pause_mission();
void continue_mission();
bool is_landing() const override; bool is_landing() const override;
bool is_taking_off() const override; bool is_taking_off() const override;
@ -973,6 +978,10 @@ public:
bool use_pilot_yaw() const override; bool use_pilot_yaw() const override;
// pause continue in guided mode
bool pause() override;
bool resume() override;
protected: protected:
const char *name() const override { return "GUIDED"; } const char *name() const override { return "GUIDED"; }
@ -1016,6 +1025,9 @@ private:
SubMode guided_mode = SubMode::TakeOff; SubMode guided_mode = SubMode::TakeOff;
bool send_notification; // used to send one time notification to ground station bool send_notification; // used to send one time notification to ground station
bool takeoff_complete; // true once takeoff has completed (used to trigger retracting of landing gear) bool takeoff_complete; // true once takeoff has completed (used to trigger retracting of landing gear)
// guided mode is paused or not
bool _paused;
}; };

View File

@ -673,18 +673,6 @@ void ModeAuto::exit_mission()
} }
} }
// pause_mission - Prevent aircraft from progressing along the track
void ModeAuto::pause_mission()
{
wp_nav->set_pause();
}
// continue_mission - Allow aircraft to progress along the track
void ModeAuto::continue_mission()
{
wp_nav->set_continue();
}
// do_guided - start guided mode // do_guided - start guided mode
bool ModeAuto::do_guided(const AP_Mission::Mission_Command& cmd) bool ModeAuto::do_guided(const AP_Mission::Mission_Command& cmd)
{ {
@ -2078,4 +2066,28 @@ bool ModeAuto::verify_nav_script_time()
} }
#endif #endif
// pause - Prevent aircraft from progressing along the track
bool ModeAuto::pause()
{
// do not pause if already paused or not in the WP sub mode or already reached to the destination
if(wp_nav->paused() || _mode != SubMode::WP || wp_nav->reached_wp_destination()) {
return false;
}
wp_nav->set_pause();
return true;
}
// resume - Allow aircraft to progress along the track
bool ModeAuto::resume()
{
// do not resume if not paused before
if(!wp_nav->paused()) {
return false;
}
wp_nav->set_resume();
return true;
}
#endif #endif

View File

@ -40,6 +40,10 @@ bool ModeGuided::init(bool ignore_checks)
guided_vel_target_cms.zero(); guided_vel_target_cms.zero();
guided_accel_target_cmss.zero(); guided_accel_target_cmss.zero();
send_notification = false; send_notification = false;
// clear pause state when entering guided mode
_paused = false;
return true; return true;
} }
@ -47,10 +51,11 @@ bool ModeGuided::init(bool ignore_checks)
// should be called at 100hz or more // should be called at 100hz or more
void ModeGuided::run() void ModeGuided::run()
{ {
// if (paused) { // run pause control if the vehicle is paused
// pause_control_run(); if (_paused) {
// return; pause_control_run();
// } return;
}
// call the correct auto controller // call the correct auto controller
switch (guided_mode) { switch (guided_mode) {
@ -854,7 +859,7 @@ void ModeGuided::velaccel_control_run()
} }
} }
// velaccel_control_run - runs the guided velocity and acceleration controller // pause_control_run - runs the guided mode pause controller
// called from guided_run // called from guided_run
void ModeGuided::pause_control_run() void ModeGuided::pause_control_run()
{ {
@ -1199,4 +1204,18 @@ uint32_t ModeGuided::get_timeout_ms() const
return MAX(copter.g2.guided_timeout, 0.1) * 1000; return MAX(copter.g2.guided_timeout, 0.1) * 1000;
} }
// pause guide mode
bool ModeGuided::pause()
{
_paused = true;
return true;
}
// resume guided mode
bool ModeGuided::resume()
{
_paused = false;
return true;
}
#endif #endif