mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 12:25:20 +03:00
Changes missed from last commit.
This commit is contained in:
parent
0045e5c328
commit
3d65e4ff96
3 changed files with 1177 additions and 1176 deletions
|
@ -1,83 +1,84 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
// 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
|
||||
uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band
|
||||
|
||||
motorMixer_t customMixer[MAX_SUPPORTED_MOTORS]; // custom mixtable
|
||||
|
||||
// motor/esc/servo related stuff
|
||||
escAndServoConfig_t escAndServoConfig;
|
||||
flight3DConfig_t flight3DConfig;
|
||||
|
||||
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
|
||||
|
||||
sensorAlignmentConfig_t sensorAlignmentConfig;
|
||||
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
|
||||
|
||||
gyroConfig_t gyroConfig;
|
||||
|
||||
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
|
||||
flightDynamicsTrims_t accZero;
|
||||
flightDynamicsTrims_t magZero;
|
||||
|
||||
batteryConfig_t batteryConfig;
|
||||
|
||||
rxConfig_t rxConfig;
|
||||
inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
|
||||
|
||||
uint8_t retarded_arm; // allow disarsm/arm on throttle down + roll left/right
|
||||
|
||||
airplaneConfig_t airplaneConfig;
|
||||
int8_t fixedwing_althold_dir; // +1 or -1 for pitch/althold gain. later check if need more than just sign
|
||||
|
||||
#ifdef GPS
|
||||
gpsConfig_t gpsConfig;
|
||||
#endif
|
||||
|
||||
serialConfig_t serialConfig;
|
||||
|
||||
telemetryConfig_t telemetryConfig;
|
||||
|
||||
profile_t profile[3]; // 3 separate profiles
|
||||
uint8_t current_profile_index; // currently loaded profile
|
||||
|
||||
uint8_t magic_ef; // magic number, should be 0xEF
|
||||
uint8_t chk; // XOR checksum
|
||||
} master_t;
|
||||
|
||||
extern master_t masterConfig;
|
||||
extern profile_t currentProfile;
|
||||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
// 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
|
||||
uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band
|
||||
|
||||
motorMixer_t customMixer[MAX_SUPPORTED_MOTORS]; // custom mixtable
|
||||
|
||||
// motor/esc/servo related stuff
|
||||
escAndServoConfig_t escAndServoConfig;
|
||||
flight3DConfig_t flight3DConfig;
|
||||
|
||||
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
|
||||
|
||||
sensorAlignmentConfig_t sensorAlignmentConfig;
|
||||
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
|
||||
|
||||
gyroConfig_t gyroConfig;
|
||||
|
||||
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
|
||||
flightDynamicsTrims_t accZero;
|
||||
flightDynamicsTrims_t magZero;
|
||||
|
||||
batteryConfig_t batteryConfig;
|
||||
|
||||
rxConfig_t rxConfig;
|
||||
inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
|
||||
|
||||
uint8_t retarded_arm; // allow disarsm/arm on throttle down + roll left/right
|
||||
uint8_t small_angle;
|
||||
|
||||
airplaneConfig_t airplaneConfig;
|
||||
int8_t fixedwing_althold_dir; // +1 or -1 for pitch/althold gain. later check if need more than just sign
|
||||
|
||||
#ifdef GPS
|
||||
gpsConfig_t gpsConfig;
|
||||
#endif
|
||||
|
||||
serialConfig_t serialConfig;
|
||||
|
||||
telemetryConfig_t telemetryConfig;
|
||||
|
||||
profile_t profile[3]; // 3 separate profiles
|
||||
uint8_t current_profile_index; // currently loaded profile
|
||||
|
||||
uint8_t magic_ef; // magic number, should be 0xEF
|
||||
uint8_t chk; // XOR checksum
|
||||
} master_t;
|
||||
|
||||
extern master_t masterConfig;
|
||||
extern profile_t currentProfile;
|
||||
|
|
|
@ -78,6 +78,11 @@ float anglerad[2] = { 0.0f, 0.0f }; // absolute angle inclination in radians
|
|||
|
||||
static void getEstimatedAttitude(void);
|
||||
|
||||
imuRuntimeConfig_t *imuRuntimeConfig;
|
||||
pidProfile_t *pidProfile;
|
||||
barometerConfig_t *barometerConfig;
|
||||
accDeadband_t *accDeadband;
|
||||
|
||||
void imuInit()
|
||||
{
|
||||
smallAngle = lrintf(acc_1G * cosf(RAD * imuRuntimeConfig->small_angle));
|
||||
|
@ -90,11 +95,6 @@ void calculateThrottleAngleScale(uint16_t throttle_correction_angle)
|
|||
throttleAngleScale = (1800.0f / M_PI) * (900.0f / throttle_correction_angle);
|
||||
}
|
||||
|
||||
imuRuntimeConfig_t *imuRuntimeConfig;
|
||||
pidProfile_t *pidProfile;
|
||||
barometerConfig_t *barometerConfig;
|
||||
accDeadband_t *accDeadband;
|
||||
|
||||
void configureImu(imuRuntimeConfig_t *initialImuRuntimeConfig, pidProfile_t *initialPidProfile, barometerConfig_t *intialBarometerConfig, accDeadband_t *initialAccDeadband)
|
||||
{
|
||||
imuRuntimeConfig = initialImuRuntimeConfig;
|
||||
|
|
File diff suppressed because it is too large
Load diff
Loading…
Add table
Add a link
Reference in a new issue