mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 17:25:20 +03:00
Merge branch 'master' of https://github.com/cleanflight/cleanflight
This commit is contained in:
commit
6abd6297df
5 changed files with 56 additions and 16 deletions
12
docs/Gps.md
12
docs/Gps.md
|
@ -130,3 +130,15 @@ From the UBlox documentation:
|
||||||
* Pedestrian - Applications with low acceleration and speed, e.g. how a pedestrian would move. Low acceleration assumed. MAX Altitude [m]: 9000, MAX Velocity [m/s]: 30, MAX Vertical, Velocity [m/s]: 20, Sanity check type: Altitude and Velocity, Max Position Deviation: Small.
|
* Pedestrian - Applications with low acceleration and speed, e.g. how a pedestrian would move. Low acceleration assumed. MAX Altitude [m]: 9000, MAX Velocity [m/s]: 30, MAX Vertical, Velocity [m/s]: 20, Sanity check type: Altitude and Velocity, Max Position Deviation: Small.
|
||||||
* Portable - Applications with low acceleration, e.g. portable devices. Suitable for most situations. MAX Altitude [m]: 12000, MAX Velocity [m/s]: 310, MAX Vertical Velocity [m/s]: 50, Sanity check type: Altitude and Velocity, Max Position Deviation: Medium.
|
* Portable - Applications with low acceleration, e.g. portable devices. Suitable for most situations. MAX Altitude [m]: 12000, MAX Velocity [m/s]: 310, MAX Vertical Velocity [m/s]: 50, Sanity check type: Altitude and Velocity, Max Position Deviation: Medium.
|
||||||
* Airborne < 1G - Used for applications with a higher dynamic range and vertical acceleration than a passenger car. No 2D position fixes supported. MAX Altitude [m]: 50000, MAX Velocity [m/s]: 100, MAX Vertical Velocity [m/s]: 100, Sanity check type: Altitude, Max Position Deviation: Large
|
* Airborne < 1G - Used for applications with a higher dynamic range and vertical acceleration than a passenger car. No 2D position fixes supported. MAX Altitude [m]: 50000, MAX Velocity [m/s]: 100, MAX Vertical Velocity [m/s]: 100, Sanity check type: Altitude, Max Position Deviation: Large
|
||||||
|
|
||||||
|
## Hardware
|
||||||
|
|
||||||
|
There are many GPS receivers available on the market, people have reported success with the following receivers:
|
||||||
|
|
||||||
|
Ublox Neo-7M GPS with Compass and Pedestal Mount
|
||||||
|
http://www.hobbyking.com/hobbyking/store/__55558__Ublox_Neo_7M_GPS_with_Compass_and_Pedestal_Mount.html
|
||||||
|
|
||||||
|
RY825AI 18Hz UART USB interface GPS Glonass BeiDou QZSS antenna module flash
|
||||||
|
http://www.ebay.com/itm/RY825AI-18Hz-UART-USB-interface-GPS-Glonass-BeiDou-QZSS-antenna-module-flash/181566850426
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -70,7 +70,7 @@ reason: renamed to `yaw_rate` for consistency
|
||||||
reason: renamed to `yaw_deadband` for consistency
|
reason: renamed to `yaw_deadband` for consistency
|
||||||
|
|
||||||
### midrc
|
### midrc
|
||||||
reason: renamed to `midrc` for consistency
|
reason: renamed to `mid_rc` for consistency
|
||||||
|
|
||||||
### mincheck
|
### mincheck
|
||||||
reason: renamed to `min_check` for consistency
|
reason: renamed to `min_check` for consistency
|
||||||
|
|
|
@ -50,12 +50,16 @@ To make configuration easier common usage scenarios are listed below.
|
||||||
|
|
||||||
### Constraints
|
### Constraints
|
||||||
|
|
||||||
|
If the configuration is invalid the serial port configuration will reset to it's defaults and features may be disabled.
|
||||||
|
|
||||||
* There must always be a port available to use for MSP
|
* There must always be a port available to use for MSP
|
||||||
* There must always be a port available to use for CLI
|
* There must always be a port available to use for CLI
|
||||||
* To use a port for a function, the function's corresponding feature must be enabled first.
|
* There can only be 1 CLI port.
|
||||||
e.g. to use GPS enable the GPS feature.
|
* There is a maximum of 2 MSP ports.
|
||||||
* If the configuration is invalid the serial port configuration will reset to it's defaults and features may be disabled.
|
* To use a port for a function, the function's corresponding feature must be also be enabled.
|
||||||
* If softserial is used be aware that both softserial ports must use the same baudrate.
|
e.g. after configuring a port for GPS enable the GPS feature.
|
||||||
|
* If softserial is used both softserial ports must use the same baudrate.
|
||||||
|
|
||||||
|
|
||||||
### Examples
|
### Examples
|
||||||
|
|
||||||
|
|
|
@ -141,7 +141,12 @@ void SetSysClock(bool overclock)
|
||||||
*RCC_CRH |= (uint32_t)0x8 << (RCC_CFGR_PLLMULL9 >> 16);
|
*RCC_CRH |= (uint32_t)0x8 << (RCC_CFGR_PLLMULL9 >> 16);
|
||||||
GPIOC->ODR &= (uint32_t)~(CAN_MCR_RESET);
|
GPIOC->ODR &= (uint32_t)~(CAN_MCR_RESET);
|
||||||
|
|
||||||
|
#if defined(CJMCU)
|
||||||
|
// On CJMCU new revision boards (Late 2014) bit 15 of GPIOC->IDR is '1'.
|
||||||
|
RCC_CFGR_PLLMUL = RCC_CFGR_PLLMULL9;
|
||||||
|
#else
|
||||||
RCC_CFGR_PLLMUL = GPIOC->IDR & CAN_MCR_RESET ? hse_value = 12000000, RCC_CFGR_PLLMULL6 : RCC_CFGR_PLLMULL9;
|
RCC_CFGR_PLLMUL = GPIOC->IDR & CAN_MCR_RESET ? hse_value = 12000000, RCC_CFGR_PLLMULL6 : RCC_CFGR_PLLMULL9;
|
||||||
|
#endif
|
||||||
switch (clocksrc) {
|
switch (clocksrc) {
|
||||||
case SRC_HSE:
|
case SRC_HSE:
|
||||||
if (overclock) {
|
if (overclock) {
|
||||||
|
|
|
@ -569,28 +569,37 @@ void activateConfig(void)
|
||||||
|
|
||||||
activateControlRateConfig();
|
activateControlRateConfig();
|
||||||
|
|
||||||
useRcControlsConfig(currentProfile->modeActivationConditions, &masterConfig.escAndServoConfig, ¤tProfile->pidProfile);
|
useRcControlsConfig(
|
||||||
|
currentProfile->modeActivationConditions,
|
||||||
|
&masterConfig.escAndServoConfig,
|
||||||
|
¤tProfile->pidProfile
|
||||||
|
);
|
||||||
|
|
||||||
useGyroConfig(&masterConfig.gyroConfig);
|
useGyroConfig(&masterConfig.gyroConfig);
|
||||||
|
|
||||||
#ifdef TELEMETRY
|
#ifdef TELEMETRY
|
||||||
useTelemetryConfig(&masterConfig.telemetryConfig);
|
useTelemetryConfig(&masterConfig.telemetryConfig);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
setPIDController(currentProfile->pidController);
|
setPIDController(currentProfile->pidController);
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
gpsUseProfile(¤tProfile->gpsProfile);
|
gpsUseProfile(¤tProfile->gpsProfile);
|
||||||
gpsUsePIDs(¤tProfile->pidProfile);
|
gpsUsePIDs(¤tProfile->pidProfile);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
useFailsafeConfig(¤tProfile->failsafeConfig);
|
useFailsafeConfig(¤tProfile->failsafeConfig);
|
||||||
setAccelerationTrims(&masterConfig.accZero);
|
setAccelerationTrims(&masterConfig.accZero);
|
||||||
|
|
||||||
mixerUseConfigs(
|
mixerUseConfigs(
|
||||||
currentProfile->servoConf,
|
currentProfile->servoConf,
|
||||||
&masterConfig.flight3DConfig,
|
&masterConfig.flight3DConfig,
|
||||||
&masterConfig.escAndServoConfig,
|
&masterConfig.escAndServoConfig,
|
||||||
¤tProfile->mixerConfig,
|
¤tProfile->mixerConfig,
|
||||||
&masterConfig.airplaneConfig,
|
&masterConfig.airplaneConfig,
|
||||||
&masterConfig.rxConfig,
|
&masterConfig.rxConfig,
|
||||||
¤tProfile->gimbalConfig
|
¤tProfile->gimbalConfig
|
||||||
);
|
);
|
||||||
|
|
||||||
imuRuntimeConfig.gyro_cmpf_factor = masterConfig.gyro_cmpf_factor;
|
imuRuntimeConfig.gyro_cmpf_factor = masterConfig.gyro_cmpf_factor;
|
||||||
imuRuntimeConfig.gyro_cmpfm_factor = masterConfig.gyro_cmpfm_factor;
|
imuRuntimeConfig.gyro_cmpfm_factor = masterConfig.gyro_cmpfm_factor;
|
||||||
|
@ -598,8 +607,18 @@ void activateConfig(void)
|
||||||
imuRuntimeConfig.acc_unarmedcal = currentProfile->acc_unarmedcal;;
|
imuRuntimeConfig.acc_unarmedcal = currentProfile->acc_unarmedcal;;
|
||||||
imuRuntimeConfig.small_angle = masterConfig.small_angle;
|
imuRuntimeConfig.small_angle = masterConfig.small_angle;
|
||||||
|
|
||||||
configureImu(&imuRuntimeConfig, ¤tProfile->pidProfile, ¤tProfile->accDeadband);
|
configureImu(
|
||||||
configureAltitudeHold(¤tProfile->pidProfile, ¤tProfile->barometerConfig, ¤tProfile->rcControlsConfig, &masterConfig.escAndServoConfig);
|
&imuRuntimeConfig,
|
||||||
|
¤tProfile->pidProfile,
|
||||||
|
¤tProfile->accDeadband
|
||||||
|
);
|
||||||
|
|
||||||
|
configureAltitudeHold(
|
||||||
|
¤tProfile->pidProfile,
|
||||||
|
¤tProfile->barometerConfig,
|
||||||
|
¤tProfile->rcControlsConfig,
|
||||||
|
&masterConfig.escAndServoConfig
|
||||||
|
);
|
||||||
|
|
||||||
calculateThrottleAngleScale(currentProfile->throttle_correction_angle);
|
calculateThrottleAngleScale(currentProfile->throttle_correction_angle);
|
||||||
calculateAccZLowPassFilterRCTimeConstant(currentProfile->accz_lpf_cutoff);
|
calculateAccZLowPassFilterRCTimeConstant(currentProfile->accz_lpf_cutoff);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue