Copter: auto yaw fix issues after testing

This commit is contained in:
Iampete1 2022-10-07 01:38:52 +01:00 committed by Randy Mackay
parent 55e72a9848
commit e0b6145997
5 changed files with 15 additions and 4 deletions

View File

@ -561,7 +561,10 @@ void ModeAuto::payload_place_start()
// returns true if pilot's yaw input should be used to adjust vehicle's heading
bool ModeAuto::use_pilot_yaw(void) const
{
return (copter.g2.auto_options.get() & uint32_t(Options::IgnorePilotYaw)) == 0;
const bool allow_yaw_option = (copter.g2.auto_options.get() & uint32_t(Options::IgnorePilotYaw)) == 0;
const bool rtl_allow_yaw = (_mode == SubMode::RTL) && copter.mode_rtl.use_pilot_yaw();
const bool landing = _mode == SubMode::LAND;
return allow_yaw_option || rtl_allow_yaw || landing;
}
bool ModeAuto::set_speed_xy(float speed_xy_cms)

View File

@ -20,6 +20,9 @@ bool ModeCircle::init(bool ignore_checks)
// initialise circle controller including setting the circle center based on vehicle speed
copter.circle_nav->init();
// set auto yaw circle mode
auto_yaw.set_mode(AutoYaw::Mode::CIRCLE);
return true;
}

View File

@ -834,7 +834,7 @@ void ModeGuided::pause_control_run()
pos_control->update_z_controller();
// call attitude controller
attitude_control->input_thrust_vector_heading(pos_control->get_thrust_vector(), auto_yaw.get_heading());
attitude_control->input_thrust_vector_rate_heading(pos_control->get_thrust_vector(), 0.0);
}
// posvelaccel_control_run - runs the guided position, velocity and acceleration controller

View File

@ -546,7 +546,10 @@ int32_t ModeRTL::wp_bearing() const
// returns true if pilot's yaw input should be used to adjust vehicle's heading
bool ModeRTL::use_pilot_yaw(void) const
{
return (copter.g2.rtl_options.get() & uint32_t(Options::IgnorePilotYaw)) == 0;
const bool allow_yaw_option = (copter.g2.rtl_options.get() & uint32_t(Options::IgnorePilotYaw)) == 0;
const bool land_repositioning = g.land_repositioning && (_state == SubMode::FINAL_DESCENT);
const bool final_landing = _state == SubMode::LAND;
return allow_yaw_option || land_repositioning || final_landing;
}
#endif

View File

@ -194,7 +194,9 @@ int32_t ModeSmartRTL::wp_bearing() const
bool ModeSmartRTL::use_pilot_yaw() const
{
return g2.smart_rtl.use_pilot_yaw();
const bool land_repositioning = g.land_repositioning && (smart_rtl_state == SubMode::DESCEND);
const bool final_landing = smart_rtl_state == SubMode::LAND;
return g2.smart_rtl.use_pilot_yaw() || land_repositioning || final_landing;
}
#endif