Copter: add use_pilot_yaw to Mode class

This commit is contained in:
Tatsuya Yamaguchi 2021-09-03 15:22:25 +09:00 committed by Randy Mackay
parent e6968395c6
commit 94c771ee74
1 changed files with 8 additions and 5 deletions

View File

@ -106,6 +106,9 @@ public:
// send output to the motors, can be overridden by subclasses
virtual void output_to_motors();
// returns true if pilot's yaw input should be used to adjust vehicle's heading
virtual bool use_pilot_yaw() const {return true; }
protected:
// helper functions
@ -415,6 +418,7 @@ public:
bool is_landing() const override;
bool is_taking_off() const override;
bool use_pilot_yaw() const override;
bool requires_terrain_failsafe() const override { return true; }
@ -453,8 +457,6 @@ private:
IgnorePilotYaw = (1 << 2U),
};
bool use_pilot_yaw(void) const;
bool start_command(const AP_Mission::Mission_Command& cmd);
bool verify_command(const AP_Mission::Mission_Command& cmd);
void exit_mission();
@ -920,6 +922,8 @@ public:
// return guided mode timeout in milliseconds. Only used for velocity, acceleration and angle control
uint32_t get_timeout_ms() const;
bool use_pilot_yaw() const override;
protected:
const char *name() const override { return "GUIDED"; }
@ -953,7 +957,6 @@ private:
void posvelaccel_control_run();
void set_desired_velocity_with_accel_and_fence_limits(const Vector3f& vel_des);
void set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle);
bool use_pilot_yaw(void) const;
// controls which controller is run (pos or vel):
SubMode guided_mode = SubMode::TakeOff;
@ -1178,6 +1181,8 @@ public:
// for reporting to GCS
bool get_wp(Location &loc) const override;
bool use_pilot_yaw() const override;
// RTL states
enum class SubMode : uint8_t {
STARTING,
@ -1260,8 +1265,6 @@ private:
IgnorePilotYaw = (1U << 2),
};
bool use_pilot_yaw(void) const;
};