mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: add use_pilot_yaw to Mode class
This commit is contained in:
parent
9cba6fa7aa
commit
d5a4ae864c
@ -101,6 +101,9 @@ public:
|
|||||||
return pos_control->get_vel_desired_cms();
|
return pos_control->get_vel_desired_cms();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// returns true if pilot's yaw input should be used to adjust vehicle's heading
|
||||||
|
virtual bool use_pilot_yaw() const {return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
// helper functions
|
// helper functions
|
||||||
@ -394,6 +397,7 @@ public:
|
|||||||
bool is_landing() const override;
|
bool is_landing() const override;
|
||||||
|
|
||||||
bool is_taking_off() const override;
|
bool is_taking_off() const override;
|
||||||
|
bool use_pilot_yaw() const override;
|
||||||
|
|
||||||
bool requires_terrain_failsafe() const override { return true; }
|
bool requires_terrain_failsafe() const override { return true; }
|
||||||
|
|
||||||
@ -429,8 +433,6 @@ private:
|
|||||||
IgnorePilotYaw = (1 << 2U),
|
IgnorePilotYaw = (1 << 2U),
|
||||||
};
|
};
|
||||||
|
|
||||||
bool use_pilot_yaw(void) const;
|
|
||||||
|
|
||||||
bool start_command(const AP_Mission::Mission_Command& cmd);
|
bool start_command(const AP_Mission::Mission_Command& cmd);
|
||||||
bool verify_command(const AP_Mission::Mission_Command& cmd);
|
bool verify_command(const AP_Mission::Mission_Command& cmd);
|
||||||
void exit_mission();
|
void exit_mission();
|
||||||
@ -895,6 +897,8 @@ public:
|
|||||||
// return guided mode timeout in milliseconds. Only used for velocity, acceleration and angle control
|
// return guided mode timeout in milliseconds. Only used for velocity, acceleration and angle control
|
||||||
uint32_t get_timeout_ms() const;
|
uint32_t get_timeout_ms() const;
|
||||||
|
|
||||||
|
bool use_pilot_yaw() const override;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
const char *name() const override { return "GUIDED"; }
|
const char *name() const override { return "GUIDED"; }
|
||||||
@ -932,7 +936,6 @@ private:
|
|||||||
void velaccel_control_run();
|
void velaccel_control_run();
|
||||||
void posvelaccel_control_run();
|
void posvelaccel_control_run();
|
||||||
void set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle);
|
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):
|
// controls which controller is run (pos or vel):
|
||||||
SubMode guided_mode = SubMode::TakeOff;
|
SubMode guided_mode = SubMode::TakeOff;
|
||||||
@ -1157,6 +1160,8 @@ public:
|
|||||||
// for reporting to GCS
|
// for reporting to GCS
|
||||||
bool get_wp(Location &loc) override;
|
bool get_wp(Location &loc) override;
|
||||||
|
|
||||||
|
bool use_pilot_yaw() const override;
|
||||||
|
|
||||||
// RTL states
|
// RTL states
|
||||||
enum class SubMode : uint8_t {
|
enum class SubMode : uint8_t {
|
||||||
STARTING,
|
STARTING,
|
||||||
@ -1239,8 +1244,6 @@ private:
|
|||||||
IgnorePilotYaw = (1U << 2),
|
IgnorePilotYaw = (1U << 2),
|
||||||
};
|
};
|
||||||
|
|
||||||
bool use_pilot_yaw(void) const;
|
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user