mirror of https://github.com/ArduPilot/ardupilot
Copter: allow tradheli inverted feature for stabilize, althold, loiter and auto modes
This commit is contained in:
parent
f06bbd471f
commit
a07b514ee8
|
@ -106,8 +106,9 @@ void Copter::update_heli_control_dynamics(void)
|
|||
bool Copter::should_use_landing_swash() const
|
||||
{
|
||||
if (flightmode->has_manual_throttle() ||
|
||||
flightmode->mode_number() == Mode::Number::DRIFT) {
|
||||
// manual modes always uses full swash range
|
||||
flightmode->mode_number() == Mode::Number::DRIFT ||
|
||||
attitude_control->get_inverted_flight()) {
|
||||
// manual modes or modes using inverted flight uses full swash range
|
||||
return false;
|
||||
}
|
||||
if (flightmode->is_landing()) {
|
||||
|
|
|
@ -471,7 +471,9 @@ public:
|
|||
}
|
||||
bool allows_autotune() const override { return true; }
|
||||
bool allows_flip() const override { return true; }
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
bool allows_inverted() const override { return true; };
|
||||
#endif
|
||||
protected:
|
||||
|
||||
const char *name() const override { return "ALT_HOLD"; }
|
||||
|
@ -499,6 +501,9 @@ public:
|
|||
bool allows_arming(AP_Arming::Method method) const override;
|
||||
bool is_autopilot() const override { return true; }
|
||||
bool in_guided_mode() const override { return _mode == SubMode::NAVGUIDED || _mode == SubMode::NAV_SCRIPT_TIME; }
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
bool allows_inverted() const override { return true; };
|
||||
#endif
|
||||
|
||||
// Auto modes
|
||||
enum class SubMode : uint8_t {
|
||||
|
@ -1250,6 +1255,10 @@ public:
|
|||
bool has_user_takeoff(bool must_navigate) const override { return true; }
|
||||
bool allows_autotune() const override { return true; }
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
bool allows_inverted() const override { return true; };
|
||||
#endif
|
||||
|
||||
#if AC_PRECLAND_ENABLED
|
||||
void set_precision_loiter_enabled(bool value) { _precision_loiter_enabled = value; }
|
||||
#endif
|
||||
|
|
|
@ -78,7 +78,7 @@ void ModeStabilize_Heli::run()
|
|||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
|
||||
|
||||
// output pilot's throttle - note that TradHeli does not used angle-boost
|
||||
attitude_control->set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt);
|
||||
attitude_control->set_throttle_out(pilot_throttle_scaled, true, g.throttle_filt);
|
||||
}
|
||||
|
||||
#endif //HELI_FRAME
|
||||
|
|
Loading…
Reference in New Issue