Copter: Restrict mode changes for TradHeli.

This commit is contained in:
Robert Lefebvre 2015-12-14 16:40:36 -05:00 committed by Randy Mackay
parent 01518ad1ab
commit 05ff279a18
12 changed files with 81 additions and 4 deletions

View File

@ -10,8 +10,9 @@
bool Copter::althold_init(bool ignore_checks)
{
#if FRAME_CONFIG == HELI_FRAME
// do not allow helis to enter Alt Hold if the Rotor Runup is not complete
if (!ignore_checks && !motors.rotor_runup_complete()){
// do not allow helis to enter Alt Hold if the Rotor Runup is not complete and current control mode has manual throttle control,
// as this will force the helicopter to descend.
if (!ignore_checks && mode_has_manual_throttle(control_mode) && !motors.rotor_runup_complete()){
return false;
}
#endif

View File

@ -22,6 +22,14 @@
// auto_init - initialise auto controller
bool Copter::auto_init(bool ignore_checks)
{
#if FRAME_CONFIG == HELI_FRAME
// do not allow helis to enter Alt Hold if the Rotor Runup is not complete and current control mode has manual throttle control,
// as this will force the helicopter to descend.
if (!ignore_checks && mode_has_manual_throttle(control_mode) && !motors.rotor_runup_complete()){
return false;
}
#endif
if ((position_ok() && mission.num_commands() > 1) || ignore_checks) {
auto_mode = Auto_Loiter;

View File

@ -164,6 +164,11 @@ static float tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp, tune_yaw_accel;
// autotune_init - should be called when autotune mode is selected
bool Copter::autotune_init(bool ignore_checks)
{
#if FRAME_CONFIG == HELI_FRAME
// Autotune mode not available for helicopters
return false;
#endif
bool success = true;
switch (autotune_state.mode) {

View File

@ -9,6 +9,14 @@
// brake_init - initialise brake controller
bool Copter::brake_init(bool ignore_checks)
{
#if FRAME_CONFIG == HELI_FRAME
// do not allow helis to enter Alt Hold if the Rotor Runup is not complete and current control mode has manual throttle control,
// as this will force the helicopter to descend.
if (!ignore_checks && mode_has_manual_throttle(control_mode) && !motors.rotor_runup_complete()){
return false;
}
#endif
if (position_ok() || ignore_checks) {
// set desired acceleration to zero

View File

@ -9,6 +9,14 @@
// circle_init - initialise circle controller flight mode
bool Copter::circle_init(bool ignore_checks)
{
#if FRAME_CONFIG == HELI_FRAME
// do not allow helis to enter Alt Hold if the Rotor Runup is not complete and current control mode has manual throttle control,
// as this will force the helicopter to descend.
if (!ignore_checks && mode_has_manual_throttle(control_mode) && !motors.rotor_runup_complete()){
return false;
}
#endif
if (position_ok() || ignore_checks) {
circle_pilot_yaw_override = false;

View File

@ -31,6 +31,14 @@
// drift_init - initialise drift controller
bool Copter::drift_init(bool ignore_checks)
{
#if FRAME_CONFIG == HELI_FRAME
// do not allow helis to enter Alt Hold if the Rotor Runup is not complete and current control mode has manual throttle control,
// as this will force the helicopter to descend.
if (!ignore_checks && mode_has_manual_throttle(control_mode) && !motors.rotor_runup_complete()){
return false;
}
#endif
if (position_ok() || ignore_checks) {
return true;
}else{

View File

@ -41,6 +41,12 @@ int8_t flip_pitch_dir; // pitch direction (-1 = pitch forward, 1 =
// flip_init - initialise flip controller
bool Copter::flip_init(bool ignore_checks)
{
#if FRAME_CONFIG == HELI_FRAME
// Flip mode not available for helis as it is untested.
return false;
#endif
// only allow flip from ACRO, Stabilize, AltHold or Drift flight modes
if (control_mode != ACRO && control_mode != STABILIZE && control_mode != ALT_HOLD) {
return false;

View File

@ -29,6 +29,14 @@ struct Guided_Limit {
// guided_init - initialise guided controller
bool Copter::guided_init(bool ignore_checks)
{
#if FRAME_CONFIG == HELI_FRAME
// do not allow helis to enter Alt Hold if the Rotor Runup is not complete and current control mode has manual throttle control,
// as this will force the helicopter to descend.
if (!ignore_checks && mode_has_manual_throttle(control_mode) && !motors.rotor_runup_complete()){
return false;
}
#endif
if (position_ok() || ignore_checks) {
// initialise yaw
set_auto_yaw_mode(get_default_auto_yaw_mode(false));

View File

@ -10,8 +10,9 @@
bool Copter::loiter_init(bool ignore_checks)
{
#if FRAME_CONFIG == HELI_FRAME
// do not allow helis to enter Loiter if the Rotor Runup is not complete
if (!ignore_checks && !motors.rotor_runup_complete()){
// do not allow helis to enter Alt Hold if the Rotor Runup is not complete and current control mode has manual throttle control,
// as this will force the helicopter to descend.
if (!ignore_checks && mode_has_manual_throttle(control_mode) && !motors.rotor_runup_complete()){
return false;
}
#endif

View File

@ -77,6 +77,14 @@ static struct {
// poshold_init - initialise PosHold controller
bool Copter::poshold_init(bool ignore_checks)
{
#if FRAME_CONFIG == HELI_FRAME
// do not allow helis to enter Alt Hold if the Rotor Runup is not complete and current control mode has manual throttle control,
// as this will force the helicopter to descend.
if (!ignore_checks && mode_has_manual_throttle(control_mode) && !motors.rotor_runup_complete()){
return false;
}
#endif
// fail to initialise PosHold mode if no GPS lock
if (!position_ok() && !ignore_checks) {
return false;

View File

@ -12,6 +12,14 @@
// rtl_init - initialise rtl controller
bool Copter::rtl_init(bool ignore_checks)
{
#if FRAME_CONFIG == HELI_FRAME
// do not allow helis to enter Alt Hold if the Rotor Runup is not complete and current control mode has manual throttle control,
// as this will force the helicopter to descend.
if (!ignore_checks && mode_has_manual_throttle(control_mode) && !motors.rotor_runup_complete()){
return false;
}
#endif
if (position_ok() || ignore_checks) {
rtl_climb_start();
return true;

View File

@ -9,6 +9,14 @@
// sport_init - initialise sport controller
bool Copter::sport_init(bool ignore_checks)
{
#if FRAME_CONFIG == HELI_FRAME
// do not allow helis to enter Alt Hold if the Rotor Runup is not complete and current control mode has manual throttle control,
// as this will force the helicopter to descend.
if (!ignore_checks && mode_has_manual_throttle(control_mode) && !motors.rotor_runup_complete()){
return false;
}
#endif
// initialize vertical speed and accelerationj
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
pos_control.set_accel_z(g.pilot_accel_z);