mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-26 01:35:41 +03:00
de-duplicate failsafe code. extract failsafe code to seperate files.
remove dependency on board.h and mw.h on a few files. Moved rx configuration paramaters into rxConfig in order to remove the dependency on config_t from the sbus rx code - sumd/spektrum to follow. Avoided use of YAW/PITCH/ROLL in some files since those constants are from an unrelated enum type. Replaced some magic numbers with constants to remove comments and improve code readability. Note, due to the tight coupling and global variable usage it was difficult to create a smaller commit.
This commit is contained in:
parent
d7eb416aa9
commit
0f02e12f40
26 changed files with 606 additions and 437 deletions
188
src/config.h
188
src/config.h
|
@ -17,171 +17,27 @@ enum {
|
|||
PID_ITEM_COUNT
|
||||
};
|
||||
|
||||
enum {
|
||||
BOXARM = 0,
|
||||
BOXANGLE,
|
||||
BOXHORIZON,
|
||||
BOXBARO,
|
||||
BOXVARIO,
|
||||
BOXMAG,
|
||||
BOXHEADFREE,
|
||||
BOXHEADADJ,
|
||||
BOXCAMSTAB,
|
||||
BOXCAMTRIG,
|
||||
BOXGPSHOME,
|
||||
BOXGPSHOLD,
|
||||
BOXPASSTHRU,
|
||||
BOXBEEPERON,
|
||||
BOXLEDMAX,
|
||||
BOXLEDLOW,
|
||||
BOXLLIGHTS,
|
||||
BOXCALIB,
|
||||
BOXGOV,
|
||||
BOXOSD,
|
||||
BOXTELEMETRY,
|
||||
CHECKBOX_ITEM_COUNT
|
||||
};
|
||||
typedef enum {
|
||||
FEATURE_PPM = 1 << 0,
|
||||
FEATURE_VBAT = 1 << 1,
|
||||
FEATURE_INFLIGHT_ACC_CAL = 1 << 2,
|
||||
FEATURE_SERIALRX = 1 << 3,
|
||||
FEATURE_MOTOR_STOP = 1 << 4,
|
||||
FEATURE_SERVO_TILT = 1 << 5,
|
||||
FEATURE_SOFTSERIAL = 1 << 6,
|
||||
FEATURE_LED_RING = 1 << 7,
|
||||
FEATURE_GPS = 1 << 8,
|
||||
FEATURE_FAILSAFE = 1 << 9,
|
||||
FEATURE_SONAR = 1 << 10,
|
||||
FEATURE_TELEMETRY = 1 << 11,
|
||||
FEATURE_POWERMETER = 1 << 12,
|
||||
FEATURE_VARIO = 1 << 13,
|
||||
FEATURE_3D = 1 << 14,
|
||||
} AvailableFeatures;
|
||||
|
||||
|
||||
typedef struct config_t {
|
||||
uint8_t pidController; // 0 = multiwii original, 1 = rewrite from http://www.multiwii.com/forum/viewtopic.php?f=8&t=3671
|
||||
uint8_t P8[PID_ITEM_COUNT];
|
||||
uint8_t I8[PID_ITEM_COUNT];
|
||||
uint8_t D8[PID_ITEM_COUNT];
|
||||
|
||||
uint8_t rcRate8;
|
||||
uint8_t rcExpo8;
|
||||
uint8_t thrMid8;
|
||||
uint8_t thrExpo8;
|
||||
|
||||
uint8_t rollPitchRate;
|
||||
uint8_t yawRate;
|
||||
|
||||
uint8_t dynThrPID;
|
||||
uint16_t tpaBreakPoint; // Breakpoint where TPA is activated
|
||||
int16_t mag_declination; // Get your magnetic decliniation from here : http://magnetic-declination.com/
|
||||
int16_t angleTrim[2]; // accelerometer trim
|
||||
|
||||
// sensor-related stuff
|
||||
uint8_t acc_lpf_factor; // Set the Low Pass Filter factor for ACC. Increasing this value would reduce ACC noise (visible in GUI), but would increase ACC lag time. Zero = no filter
|
||||
uint8_t accz_deadband; // set the acc deadband for z-Axis, this ignores small accelerations
|
||||
uint8_t accxy_deadband; // set the acc deadband for xy-Axis
|
||||
uint8_t baro_tab_size; // size of baro filter array
|
||||
float baro_noise_lpf; // additional LPF to reduce baro noise
|
||||
float baro_cf_vel; // apply Complimentary Filter to keep the calculated velocity based on baro velocity (i.e. near real velocity)
|
||||
float baro_cf_alt; // apply CF to use ACC for height estimation
|
||||
uint8_t acc_unarmedcal; // turn automatic acc compensation on/off
|
||||
|
||||
uint16_t activate[CHECKBOX_ITEM_COUNT]; // activate switches
|
||||
|
||||
// Radio/ESC-related configuration
|
||||
uint8_t deadband; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero.
|
||||
uint8_t yawdeadband; // introduce a deadband around the stick center for yaw axis. Must be greater than zero.
|
||||
uint8_t alt_hold_throttle_neutral; // defines the neutral zone of throttle stick during altitude hold, default setting is +/-40
|
||||
uint8_t alt_hold_fast_change; // when disabled, turn off the althold when throttle stick is out of deadband defined with alt_hold_throttle_neutral; when enabled, altitude changes slowly proportional to stick movement
|
||||
uint16_t throttle_correction_angle; // the angle when the throttle correction is maximal. in 0.1 degres, ex 225 = 22.5 ,30.0, 450 = 45.0 deg
|
||||
uint8_t throttle_correction_value; // the correction that will be applied at throttle_correction_angle.
|
||||
|
||||
// Servo-related stuff
|
||||
servoParam_t servoConf[MAX_SUPPORTED_SERVOS]; // servo configuration
|
||||
|
||||
// Failsafe related configuration
|
||||
uint8_t failsafe_delay; // Guard time for failsafe activation after signal lost. 1 step = 0.1sec - 1sec in example (10)
|
||||
uint8_t failsafe_off_delay; // Time for Landing before motors stop in 0.1sec. 1 step = 0.1sec - 20sec in example (200)
|
||||
uint16_t failsafe_throttle; // Throttle level used for landing - specify value between 1000..2000 (pwm pulse width for slightly below hover). center throttle = 1500.
|
||||
uint16_t failsafe_detect_threshold; // Update controls channel only if pulse is above failsafe_detect_threshold. below this trigger failsafe.
|
||||
|
||||
// mixer-related configuration
|
||||
int8_t yaw_direction;
|
||||
uint8_t tri_unarmed_servo; // send tail servo correction pulses even when unarmed
|
||||
|
||||
// gimbal-related configuration
|
||||
uint8_t gimbal_flags; // in servotilt mode, various things that affect stuff
|
||||
|
||||
// gps-related stuff
|
||||
uint16_t gps_wp_radius; // if we are within this distance to a waypoint then we consider it reached (distance is in cm)
|
||||
uint8_t gps_lpf; // Low pass filter cut frequency for derivative calculation (default 20Hz)
|
||||
uint8_t nav_slew_rate; // Adds a rate control to nav output, will smoothen out nav angle spikes
|
||||
uint8_t nav_controls_heading; // copter faces toward the navigation point, maghold must be enabled for it
|
||||
uint16_t nav_speed_min; // cm/sec
|
||||
uint16_t nav_speed_max; // cm/sec
|
||||
uint16_t ap_mode; // Temporarily Disables GPS_HOLD_MODE to be able to make it possible to adjust the Hold-position when moving the sticks, creating a deadspan for GPS
|
||||
} config_t;
|
||||
|
||||
// System-wide
|
||||
typedef struct master_t {
|
||||
uint8_t version;
|
||||
uint16_t size;
|
||||
uint8_t magic_be; // magic number, should be 0xBE
|
||||
|
||||
uint8_t mixerConfiguration;
|
||||
uint32_t enabledFeatures;
|
||||
uint16_t looptime; // imu loop time in us
|
||||
motorMixer_t customMixer[MAX_SUPPORTED_MOTORS]; // custom mixtable
|
||||
|
||||
// motor/esc/servo related stuff
|
||||
uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed.
|
||||
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
|
||||
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
|
||||
uint16_t deadband3d_low; // min 3d value
|
||||
uint16_t deadband3d_high; // max 3d value
|
||||
uint16_t neutral3d; // center 3d value
|
||||
uint16_t deadband3d_throttle; // default throttle deadband from MIDRC
|
||||
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
|
||||
uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
|
||||
|
||||
// global sensor-related stuff
|
||||
sensor_align_e gyro_align; // gyro alignment
|
||||
sensor_align_e acc_align; // acc alignment
|
||||
sensor_align_e mag_align; // mag alignment
|
||||
boardAlignment_t boardAlignment;
|
||||
int8_t yaw_control_direction; // change control direction of yaw (inverted, normal)
|
||||
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
|
||||
uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
|
||||
uint16_t gyro_cmpf_factor; // Set the Gyro Weight for Gyro/Acc complementary filter. Increasing this value would reduce and delay Acc influence on the output of the filter.
|
||||
uint16_t gyro_cmpfm_factor; // Set the Gyro Weight for Gyro/Magnetometer complementary filter. Increasing this value would reduce and delay Magnetometer influence on the output of the filter
|
||||
uint8_t moron_threshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default.
|
||||
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
|
||||
int16_t accZero[3];
|
||||
int16_t magZero[3];
|
||||
|
||||
batteryConfig_t batteryConfig;
|
||||
|
||||
uint8_t power_adc_channel; // which channel is used for current sensor. Right now, only 2 places are supported: RC_CH2 (unused when in CPPM mode, = 1), RC_CH8 (last channel in PWM mode, = 9)
|
||||
|
||||
// Radio/ESC-related configuration
|
||||
uint8_t rcmap[8]; // mapping of radio channels to internal RPYTA+ order
|
||||
uint8_t serialrx_type; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_SERIALRX first.
|
||||
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
||||
uint16_t mincheck; // minimum rc end
|
||||
uint16_t maxcheck; // maximum rc end
|
||||
uint8_t retarded_arm; // allow disarsm/arm on throttle down + roll left/right
|
||||
uint8_t flaps_speed; // airplane mode flaps, 0 = no flaps, > 0 = flap speed, larger = faster
|
||||
int8_t fixedwing_althold_dir; // +1 or -1 for pitch/althold gain. later check if need more than just sign
|
||||
|
||||
uint8_t rssi_aux_channel; // Read rssi from channel. 1+ = AUX1+, 0 to disable.
|
||||
|
||||
// gps-related stuff
|
||||
uint8_t gps_type; // See GPSHardware enum.
|
||||
int8_t gps_baudrate; // See GPSBaudRates enum.
|
||||
|
||||
uint32_t serial_baudrate;
|
||||
|
||||
uint32_t softserial_baudrate; // shared by both soft serial ports
|
||||
uint8_t softserial_1_inverted; // use inverted softserial input and output signals on port 1
|
||||
uint8_t softserial_2_inverted; // use inverted softserial input and output signals on port 2
|
||||
|
||||
uint8_t telemetry_provider; // See TelemetryProvider enum.
|
||||
uint8_t telemetry_port; // See TelemetryPort enum.
|
||||
uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed.
|
||||
config_t profile[3]; // 3 separate profiles
|
||||
uint8_t current_profile; // currently loaded profile
|
||||
uint8_t reboot_character; // which byte is used to reboot. Default 'R', could be changed carefully to something else.
|
||||
|
||||
uint8_t magic_ef; // magic number, should be 0xEF
|
||||
uint8_t chk; // XOR checksum
|
||||
} master_t;
|
||||
|
||||
extern master_t mcfg;
|
||||
extern config_t cfg;
|
||||
bool feature(uint32_t mask);
|
||||
void featureSet(uint32_t mask);
|
||||
void featureClear(uint32_t mask);
|
||||
void featureClearAll(void);
|
||||
uint32_t featureMask(void);
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue