mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: add option to disable ACRO mode
This commit is contained in:
parent
20ac17cda8
commit
b27c00dc5f
@ -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
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
|
@ -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 @@
|
||||
#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
|
||||
//
|
||||
|
@ -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;
|
||||
|
@ -105,6 +105,7 @@ protected:
|
||||
};
|
||||
|
||||
|
||||
#if MODE_ACRO_ENABLED == ENABLED
|
||||
class ModeAcro : public Mode {
|
||||
|
||||
public:
|
||||
@ -129,6 +130,7 @@ protected:
|
||||
private:
|
||||
|
||||
};
|
||||
#endif
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
class ModeAcro_Heli : public ModeAcro {
|
||||
|
@ -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
|
||||
pitch_out = rate_bf_request.y;
|
||||
yaw_out = rate_bf_request.z;
|
||||
}
|
||||
#endif
|
||||
|
@ -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()
|
||||
}
|
||||
|
||||
#endif //HELI_FRAME
|
||||
#endif //MODE_ACRO_ENABLED == ENABLED
|
||||
|
@ -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)
|
||||
Log_Write_Event(DATA_ACRO_TRAINER_LIMITED);
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
|
||||
case AUXSW_GRIPPER:
|
||||
|
Loading…
Reference in New Issue
Block a user