mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
Plane: move nav_delay state to be private in ModeAuto
This commit is contained in:
parent
db72fd16d4
commit
a1b021e833
@ -940,9 +940,6 @@ private:
|
|||||||
bool verify_command_callback(const AP_Mission::Mission_Command& cmd);
|
bool verify_command_callback(const AP_Mission::Mission_Command& cmd);
|
||||||
float get_wp_radius() const;
|
float get_wp_radius() const;
|
||||||
|
|
||||||
void do_nav_delay(const AP_Mission::Mission_Command& cmd);
|
|
||||||
bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);
|
|
||||||
|
|
||||||
bool is_land_command(uint16_t cmd) const;
|
bool is_land_command(uint16_t cmd) const;
|
||||||
|
|
||||||
bool do_change_speed(uint8_t speedtype, float speed_target_ms, float rhtottle_pct);
|
bool do_change_speed(uint8_t speedtype, float speed_target_ms, float rhtottle_pct);
|
||||||
@ -951,12 +948,6 @@ private:
|
|||||||
*/
|
*/
|
||||||
bool in_auto_mission_id(uint16_t command) const;
|
bool in_auto_mission_id(uint16_t command) const;
|
||||||
|
|
||||||
// Delay the next navigation command
|
|
||||||
struct {
|
|
||||||
uint32_t time_max_ms;
|
|
||||||
uint32_t time_start_ms;
|
|
||||||
} nav_delay;
|
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED
|
#if AP_SCRIPTING_ENABLED
|
||||||
// nav scripting support
|
// nav scripting support
|
||||||
void do_nav_script_time(const AP_Mission::Mission_Command& cmd);
|
void do_nav_script_time(const AP_Mission::Mission_Command& cmd);
|
||||||
|
@ -206,7 +206,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
case MAV_CMD_NAV_DELAY:
|
case MAV_CMD_NAV_DELAY:
|
||||||
do_nav_delay(cmd);
|
mode_auto.do_nav_delay(cmd);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
@ -311,7 +311,7 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
case MAV_CMD_NAV_DELAY:
|
case MAV_CMD_NAV_DELAY:
|
||||||
return verify_nav_delay(cmd);
|
return mode_auto.verify_nav_delay(cmd);
|
||||||
|
|
||||||
// do commands (always return true)
|
// do commands (always return true)
|
||||||
case MAV_CMD_DO_CHANGE_SPEED:
|
case MAV_CMD_DO_CHANGE_SPEED:
|
||||||
@ -533,7 +533,7 @@ void Plane::do_loiter_to_alt(const AP_Mission::Mission_Command& cmd)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// do_nav_delay - Delay the next navigation command
|
// do_nav_delay - Delay the next navigation command
|
||||||
void Plane::do_nav_delay(const AP_Mission::Mission_Command& cmd)
|
void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd)
|
||||||
{
|
{
|
||||||
nav_delay.time_start_ms = millis();
|
nav_delay.time_start_ms = millis();
|
||||||
|
|
||||||
@ -880,9 +880,9 @@ bool Plane::verify_altitude_wait(const AP_Mission::Mission_Command &cmd)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// verify_nav_delay - check if we have waited long enough
|
// verify_nav_delay - check if we have waited long enough
|
||||||
bool Plane::verify_nav_delay(const AP_Mission::Mission_Command& cmd)
|
bool ModeAuto::verify_nav_delay(const AP_Mission::Mission_Command& cmd)
|
||||||
{
|
{
|
||||||
if (arming.is_armed_and_safety_off()) {
|
if (AP::arming().is_armed_and_safety_off()) {
|
||||||
// don't delay while armed, we need a nav controller running
|
// don't delay while armed, we need a nav controller running
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -8,6 +8,7 @@
|
|||||||
#include <AP_Vehicle/ModeReason.h>
|
#include <AP_Vehicle/ModeReason.h>
|
||||||
#include "quadplane.h"
|
#include "quadplane.h"
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
|
#include <AP_Mission/AP_Mission.h>
|
||||||
|
|
||||||
class AC_PosControl;
|
class AC_PosControl;
|
||||||
class AC_AttitudeControl_Multi;
|
class AC_AttitudeControl_Multi;
|
||||||
@ -221,11 +222,23 @@ public:
|
|||||||
|
|
||||||
bool is_landing() const override;
|
bool is_landing() const override;
|
||||||
|
|
||||||
|
void do_nav_delay(const AP_Mission::Mission_Command& cmd);
|
||||||
|
bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
void _exit() override;
|
void _exit() override;
|
||||||
bool _pre_arm_checks(size_t buflen, char *buffer) const override;
|
bool _pre_arm_checks(size_t buflen, char *buffer) const override;
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
// Delay the next navigation command
|
||||||
|
struct {
|
||||||
|
uint32_t time_max_ms;
|
||||||
|
uint32_t time_start_ms;
|
||||||
|
} nav_delay;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user