Browse Source

Copter: add option to disable ACRO mode

master
Dr.-Ing. Amilcar Do Carmo Lucas 7 years ago committed by Randy Mackay
parent
commit
b27c00dc5f
  1. 1
      ArduCopter/APM_Config.h
  2. 2
      ArduCopter/AP_Arming.cpp
  3. 2
      ArduCopter/Copter.h
  4. 10
      ArduCopter/config.h
  5. 2
      ArduCopter/mode.cpp
  6. 2
      ArduCopter/mode.h
  7. 3
      ArduCopter/mode_acro.cpp
  8. 3
      ArduCopter/mode_acro_heli.cpp
  9. 2
      ArduCopter/switches.cpp

1
ArduCopter/APM_Config.h

@ -25,6 +25,7 @@ @@ -25,6 +25,7 @@
//#define SPRAYER DISABLED // disable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
//#define WINCH_ENABLED DISABLED // disable winch support
//#define GRIPPER_ENABLED DISABLED // disable gripper support
//#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support
//#define MODE_BRAKE_ENABLED DISABLED // disable brake mode support
//#define MODE_CIRCLE_ENABLED DISABLED // disable circle mode support

2
ArduCopter/AP_Arming.cpp

@ -212,12 +212,14 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) @@ -212,12 +212,14 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
}
// acro balance parameter check
#if MODE_ACRO_ENABLED == ENABLED
if ((copter.g.acro_balance_roll > copter.attitude_control->get_angle_roll_p().kP()) || (copter.g.acro_balance_pitch > copter.attitude_control->get_angle_pitch_p().kP())) {
if (display_failure) {
gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: ACRO_BAL_ROLL/PITCH");
}
return false;
}
#endif
#if RANGEFINDER_ENABLED == ENABLED && OPTFLOW == ENABLED
// check range finder if optflow enabled

2
ArduCopter/Copter.h

@ -960,10 +960,12 @@ private: @@ -960,10 +960,12 @@ private:
#include "mode.h"
Mode *flightmode;
#if MODE_ACRO_ENABLED == ENABLED
#if FRAME_CONFIG == HELI_FRAME
ModeAcro_Heli mode_acro;
#else
ModeAcro mode_acro;
#endif
#endif
ModeAltHold mode_althold;
#if MODE_AUTO_ENABLED == ENABLED

10
ArduCopter/config.h

@ -267,6 +267,12 @@ @@ -267,6 +267,12 @@
# define NAV_GUIDED !HAL_MINIMIZE_FEATURES
#endif
//////////////////////////////////////////////////////////////////////////////
// Acro - fly vehicle in acrobatic mode
#ifndef MODE_ACRO_ENABLED
# define MODE_ACRO_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Auto mode - allows vehicle to trace waypoints and perform automated actions
#ifndef MODE_AUTO_ENABLED
@ -674,6 +680,10 @@ @@ -674,6 +680,10 @@
#error Terrain requires ModeAuto which is disabled
#endif
#if FRAME_CONFIG == HELI_FRAME && !MODE_ACRO_ENABLED
#error Helicopter frame requires acro mode support which is disabled
#endif
//////////////////////////////////////////////////////////////////////////////
// Developer Items
//

2
ArduCopter/mode.cpp

@ -38,9 +38,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode) @@ -38,9 +38,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
Copter::Mode *ret = nullptr;
switch (mode) {
#if MODE_ACRO_ENABLED == ENABLED
case ACRO:
ret = &mode_acro;
break;
#endif
case STABILIZE:
ret = &mode_stabilize;

2
ArduCopter/mode.h

@ -105,6 +105,7 @@ protected: @@ -105,6 +105,7 @@ protected:
};
#if MODE_ACRO_ENABLED == ENABLED
class ModeAcro : public Mode {
public:
@ -129,6 +130,7 @@ protected: @@ -129,6 +130,7 @@ protected:
private:
};
#endif
#if FRAME_CONFIG == HELI_FRAME
class ModeAcro_Heli : public ModeAcro {

3
ArduCopter/mode_acro.cpp

@ -2,6 +2,8 @@ @@ -2,6 +2,8 @@
#include "mode.h"
#if MODE_ACRO_ENABLED == ENABLED
/*
* Init and run calls for acro flight mode
*/
@ -165,3 +167,4 @@ void Copter::ModeAcro::get_pilot_desired_angle_rates(int16_t roll_in, int16_t pi @@ -165,3 +167,4 @@ void Copter::ModeAcro::get_pilot_desired_angle_rates(int16_t roll_in, int16_t pi
pitch_out = rate_bf_request.y;
yaw_out = rate_bf_request.z;
}
#endif

3
ArduCopter/mode_acro_heli.cpp

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
#include "Copter.h"
#if MODE_ACRO_ENABLED == ENABLED
#if FRAME_CONFIG == HELI_FRAME
/*
* Init and run calls for acro flight mode for trad heli
@ -98,3 +100,4 @@ void Copter::ModeAcro_Heli::run() @@ -98,3 +100,4 @@ void Copter::ModeAcro_Heli::run()
}
#endif //HELI_FRAME
#endif //MODE_ACRO_ENABLED == ENABLED

2
ArduCopter/switches.cpp

@ -344,6 +344,7 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag) @@ -344,6 +344,7 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
break;
case AUXSW_ACRO_TRAINER:
#if MODE_ACRO_ENABLED == ENABLED
switch(ch_flag) {
case AUX_SWITCH_LOW:
g.acro_trainer = ACRO_TRAINER_DISABLED;
@ -358,6 +359,7 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag) @@ -358,6 +359,7 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
Log_Write_Event(DATA_ACRO_TRAINER_LIMITED);
break;
}
#endif
break;
case AUXSW_GRIPPER:

Loading…
Cancel
Save