mirror of https://github.com/ArduPilot/ardupilot
Copter: TradHelis force spool up before takeoff
This commit is contained in:
parent
ca565675f2
commit
50c5ad7076
|
@ -874,6 +874,7 @@ private:
|
|||
MAV_TYPE get_frame_mav_type();
|
||||
const char* get_frame_string();
|
||||
void allocate_motors(void);
|
||||
bool is_tradheli() const;
|
||||
|
||||
// terrain.cpp
|
||||
void terrain_update();
|
||||
|
|
|
@ -373,9 +373,13 @@ bool Copter::Mode::_TakeOff::triggered(const float target_climb_rate) const
|
|||
return true;
|
||||
}
|
||||
|
||||
void Copter::Mode::zero_throttle_and_relax_ac()
|
||||
void Copter::Mode::zero_throttle_and_relax_ac(bool spool_up)
|
||||
{
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
if (spool_up) {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
} else {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
}
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// Helicopters always stabilize roll/pitch/yaw
|
||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0.0f, 0.0f, 0.0f);
|
||||
|
|
|
@ -112,7 +112,7 @@ protected:
|
|||
bool takeoff_triggered(float target_climb_rate) const;
|
||||
|
||||
// helper functions
|
||||
void zero_throttle_and_relax_ac();
|
||||
void zero_throttle_and_relax_ac(bool spool_up = false);
|
||||
|
||||
// functions to control landing
|
||||
// in modes that support landing
|
||||
|
|
|
@ -50,7 +50,7 @@ void Copter::ModeDrift::run()
|
|||
|
||||
// if landed and throttle at zero, set throttle to zero and exit immediately
|
||||
if (!motors->armed() || !motors->get_interlock() || (ap.land_complete && ap.throttle_zero)) {
|
||||
zero_throttle_and_relax_ac();
|
||||
zero_throttle_and_relax_ac(copter.is_tradheli() && motors->get_interlock());
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
|
@ -139,7 +139,7 @@ void Copter::ModePosHold::run()
|
|||
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
|
||||
if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
|
||||
loiter_nav->init_target();
|
||||
zero_throttle_and_relax_ac();
|
||||
zero_throttle_and_relax_ac(copter.is_tradheli() && motors->get_interlock());
|
||||
pos_control->relax_alt_hold_controllers(0.0f);
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -43,7 +43,7 @@ void Copter::ModeZigZag::run()
|
|||
|
||||
// if not auto armed or motors not enabled set throttle to zero and exit immediately
|
||||
if (!motors->armed() || !ap.auto_armed || !motors->get_interlock() || ap.land_complete) {
|
||||
zero_throttle_and_relax_ac();
|
||||
zero_throttle_and_relax_ac(copter.is_tradheli() && motors->get_interlock());
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
|
@ -649,3 +649,12 @@ void Copter::allocate_motors(void)
|
|||
// upgrade parameters. This must be done after allocating the objects
|
||||
convert_pid_parameters();
|
||||
}
|
||||
|
||||
bool Copter::is_tradheli() const
|
||||
{
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
return true;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue