Copter: add use_pilot_yaw to ModeSmartRTL class

This commit is contained in:
Tatsuya Yamaguchi 2021-09-03 15:27:49 +09:00 committed by Randy Mackay
parent 397bbf9c8e
commit c23b7fdbd7
2 changed files with 7 additions and 1 deletions

View File

@ -1266,6 +1266,7 @@ public:
void exit() override; void exit() override;
bool is_landing() const override; bool is_landing() const override;
bool use_pilot_yaw() const override;
// Safe RTL states // Safe RTL states
enum class SubMode : uint8_t { enum class SubMode : uint8_t {

View File

@ -82,7 +82,7 @@ void ModeSmartRTL::wait_cleanup_run()
void ModeSmartRTL::path_follow_run() void ModeSmartRTL::path_follow_run()
{ {
float target_yaw_rate = 0.0f; float target_yaw_rate = 0.0f;
if (!copter.failsafe.radio && g2.smart_rtl.use_pilot_yaw()) { if (!copter.failsafe.radio && use_pilot_yaw()) {
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) { if (!is_zero(target_yaw_rate)) {
@ -207,4 +207,9 @@ int32_t ModeSmartRTL::wp_bearing() const
return wp_nav->get_wp_bearing_to_destination(); return wp_nav->get_wp_bearing_to_destination();
} }
bool ModeSmartRTL::use_pilot_yaw() const
{
return g2.smart_rtl.use_pilot_yaw();
}
#endif #endif