Merge remote-tracking branch 'upstream/master' into documentation-edits
This commit is contained in:
commit
8edd51b1e2
1
Makefile
1
Makefile
|
@ -212,6 +212,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
|||
VPATH := $(VPATH):$(TARGET_DIR)
|
||||
|
||||
COMMON_SRC = build_config.c \
|
||||
debug.c \
|
||||
version.c \
|
||||
$(TARGET_SRC) \
|
||||
config/config.c \
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
Autotune helps to automatically tune your multirotor.
|
||||
|
||||
WARNING: Autotune is an experimental feature. Currently enough feedback has been gathered and we do not recommend that anyone uses it until this warning is removed. Autotune may be replaces by G-Tune, Please see https://github.com/cleanflight/cleanflight/pull/568 for details.
|
||||
WARNING: Autotune is an experimental feature. Currently enough feedback has been gathered and we do not recommend that anyone uses it until this warning is removed. Autotune may be replaced by G-Tune, Please see https://github.com/cleanflight/cleanflight/pull/568 for details.
|
||||
|
||||
## Configuration.
|
||||
|
||||
|
|
|
@ -169,8 +169,8 @@ Re-apply any new defaults as desired.
|
|||
| max_angle_inclination | This setting controls max inclination (tilt) allowed in angle (level) mode. default 500 (50 degrees). | 100 | 900 | 500 | Master | UINT16 |
|
||||
| gyro_lpf | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 5,10,20,42,98,188,256Hz, while MPU3050 doesn't allow 5Hz. If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. Values outside of supported range will usually be ignored by drivers, and will configure lpf to default value of 42Hz. | 0 | 256 | 42 | Master | UINT16 |
|
||||
| moron_threshold | When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold (default of 32) means how much average gyro reading could differ before re-calibration is triggered. | 0 | 128 | 32 | Master | UINT8 |
|
||||
| gyro_cmpf_factor | | 100 | 1000 | 600 | Master | UINT16 |
|
||||
| gyro_cmpfm_factor | | 100 | 1000 | 250 | Master | UINT16 |
|
||||
| gyro_cmpf_factor | This setting controls the Gyro Weight for the Gyro/Acc complementary filter. Increasing this value reduces and delays Acc influence on the output of the filter. | 100 | 1000 | 600 | Master | UINT16 |
|
||||
| gyro_cmpfm_factor | This setting controls the Gyro Weight for the Gyro/Magnetometer complementary filter. Increasing this value reduces and delays the Magnetometer influence on the output of the filter. | 100 | 1000 | 250 | Master | UINT16 |
|
||||
| alt_hold_deadband | | 1 | 250 | 40 | Profile | UINT8 |
|
||||
| alt_hold_fast_change | | 0 | 1 | 1 | Profile | UINT8 |
|
||||
| deadband | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | 0 | 32 | 0 | Profile | UINT8 |
|
||||
|
@ -196,7 +196,7 @@ Re-apply any new defaults as desired.
|
|||
| failsafe_max_usec | | 100 | 3000 | 2115 | Profile | UINT16 |
|
||||
| gimbal_flags | When feature SERVO_TILT is enabled, this can be a combination of the following numbers: 1=normal gimbal (default), 2=tiltmix gimbal, 4=in PPM (or SERIALRX) input mode, this will forward AUX1..4 RC inputs to PWM5..8 pins | 0 | 255 | 1 | Profile | UINT8 |
|
||||
| acc_hardware | This is used to suggest which accelerometer driver should load, or to force no accelerometer in case gyro-only flight is needed. Default (0) will attempt to auto-detect among enabled drivers. Otherwise, to force a particular device, set it to 2 for ADXL345, 3 for MPU6050 integrated accelerometer, 4 for MMA8452, 5 for BMA280, 6 for LSM303DLHC, 7 for SPI_MPU6000, 8 for SPI_MPU6500 or 1 to disable accelerometer alltogether - resulting in gyro-only operation. | 0 | 9 | 0 | Master | UINT8 |
|
||||
| acc_lpf_factor | | 0 | 250 | 4 | Profile | UINT8 |
|
||||
| acc_lpf_factor | This setting controls the Low Pass Filter factor for ACC. Increasing this value reduces ACC noise (visible in GUI), but would increase ACC lag time. Zero = no filter | 0 | 250 | 4 | Profile | UINT8 |
|
||||
| accxy_deadband | | 0 | 100 | 40 | Profile | UINT8 |
|
||||
| accz_deadband | | 0 | 100 | 40 | Profile | UINT8 |
|
||||
| accz_lpf_cutoff | | 1 | 20 | 5 | Profile | FLOAT |
|
||||
|
|
|
@ -63,12 +63,25 @@ can not be used at the same time at Parallel PWM.
|
|||
|
||||
If you have LEDs that are intermittent, flicker or show the wrong colors then drop the VIN to less than 4.7v, e.g. by using an inline
|
||||
diode on the VIN to the LED strip. The problem occurs because of the difference in voltage between the data signal and the power
|
||||
signal. The WS2811 LED's require the data signal (Din) to be MAX 0.7 * VIN. Data In on the LEDs will allways be around ~3.3v,
|
||||
so the Vin MAX should be 4.7v (3.3v / 0.7 = 4.71v). Some LEDs are more tolerant of this than others.
|
||||
signal. The WS2811 LED's require the data signal (Din) to be between 0.3 * Vin (Max) and 0.7 * VIN (Min) to register valid logic
|
||||
low/high signals. The LED pin on the CPU will always be between 0v to ~3.3v, so the Vin should be 4.7v (3.3v / 0.7 = 4.71v).
|
||||
Some LEDs are more tolerant of this than others.
|
||||
|
||||
The datasheet can be found here: http://www.adafruit.com/datasheets/WS2812.pdf
|
||||
|
||||
## Configuration
|
||||
|
||||
The led strip feature can be configured via the GUI
|
||||
|
||||
GUI:
|
||||
Enable the Led Strip feature via the GUI under setup.
|
||||
|
||||
Configure the leds from the Led Strip tab in the cleanflight GUI.
|
||||
First setup how the led's are laid out so that you can visualize it later as you configure and so the flight controller knows how many led's there are available.
|
||||
|
||||
There is a step by step guide on how to use the GUI to configure the Led Strip feature using the GUI http://blog.oscarliang.net/setup-rgb-led-cleanflight/ which was published early 2015 by Oscar Liang which may or may not be up-to-date by the time you read this.
|
||||
|
||||
CLI:
|
||||
Enable the `LED_STRIP` feature via the cli:
|
||||
|
||||
```
|
||||
|
|
|
@ -160,4 +160,20 @@ The PID controller is flight tested and running well with the default PID settin
|
|||
Yaw authority is also quite good.
|
||||
|
||||
|
||||
## RC rate, Pitch and Roll Rates (P/R rate before they were separated), and Yaw rate
|
||||
|
||||
### RC Rate
|
||||
|
||||
An overall multiplier on the RC stick inputs for pitch, rol;, and yaw.
|
||||
|
||||
On PID Controllers 0, and 3-5 can be used to set the "feel" around center stick for small control movements. (RC Expo also affects this).For PID Controllers 1 and 2, this basically sets the baseline stick sensitivity
|
||||
|
||||
### Pitch and Roll rates
|
||||
|
||||
In PID Controllers 0 and 3-5, the affect of the PID error terms for P and D are gradually lessened as the control sticks are moved away from center, ie 0.3 rate gives a 30% reduction of those terms at full throw, effectively making the stabilizing effect of the PID controller less at stick extremes. This results in faster rotation rates. So for these controllers, you can set center stick sensitivity to control movement with RC rate above, and yet have much faster rotation rates at stick extremes.
|
||||
|
||||
For PID Controllers 1 and 2, this is an multiplier on overall stick sensitivity, like RC rate, but for roll and pitch independently. Stablility (to outside factors like turbulence) is not reduced at stick extremes. A zero value is no increase in stick sensitivity over that set by RC rate above. Higher values increases stick sensitivity across the entire stick movement range.
|
||||
|
||||
### Yaw Rate
|
||||
|
||||
In PID Controllers 0 and 5, it acts as a PID reduction as explained above. In PID Controllers 1-4, it acts as a stick sensitivity multiplier, as explained above.
|
||||
|
|
|
@ -35,27 +35,3 @@
|
|||
#define REQUIRE_PRINTF_LONG_SUPPORT
|
||||
#endif
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
||||
#define DEBUG_SECTION_TIMES
|
||||
|
||||
#ifdef DEBUG_SECTION_TIMES
|
||||
extern uint32_t sectionTimes[2][4];
|
||||
|
||||
#define TIME_SECTION_BEGIN(index) { \
|
||||
extern uint32_t sectionTimes[2][4]; \
|
||||
sectionTimes[0][index] = micros(); \
|
||||
}
|
||||
|
||||
#define TIME_SECTION_END(index) { \
|
||||
extern uint32_t sectionTimes[2][4]; \
|
||||
sectionTimes[1][index] = micros(); \
|
||||
debug[index] = sectionTimes[1][index] - sectionTimes[0][index]; \
|
||||
}
|
||||
#else
|
||||
|
||||
#define TIME_SECTION_BEGIN(index) {}
|
||||
#define TIME_SECTION_END(index) {}
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -369,7 +369,13 @@ static void resetConf(void)
|
|||
#if defined(CJMCU) || defined(SPARKY)
|
||||
featureSet(FEATURE_RX_PPM);
|
||||
#endif
|
||||
|
||||
#ifdef BOARD_HAS_VOLTAGE_DIVIDER
|
||||
// only enable the VBAT feature by default if the board has a voltage divider otherwise
|
||||
// the user may see incorrect readings and unexpected issues with pin mappings may occur.
|
||||
featureSet(FEATURE_VBAT);
|
||||
#endif
|
||||
|
||||
featureSet(FEATURE_FAILSAFE);
|
||||
|
||||
// global settings
|
||||
|
@ -516,7 +522,6 @@ static void resetConf(void)
|
|||
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
||||
masterConfig.batteryConfig.vbatscale = 20;
|
||||
#else
|
||||
featureClear(FEATURE_VBAT);
|
||||
masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL;
|
||||
#endif
|
||||
masterConfig.rxConfig.serialrx_provider = 1;
|
||||
|
|
|
@ -0,0 +1,27 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#include "stdint.h"
|
||||
|
||||
|
||||
#include "debug.h"
|
||||
|
||||
int16_t debug[DEBUG16_VALUE_COUNT];
|
||||
|
||||
#ifdef DEBUG_SECTION_TIMES
|
||||
uint32_t sectionTimes[2][4];
|
||||
#endif
|
|
@ -0,0 +1,41 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#define DEBUG16_VALUE_COUNT 4
|
||||
extern int16_t debug[DEBUG16_VALUE_COUNT];
|
||||
|
||||
#define DEBUG_SECTION_TIMES
|
||||
|
||||
#ifdef DEBUG_SECTION_TIMES
|
||||
extern uint32_t sectionTimes[2][4];
|
||||
|
||||
#define TIME_SECTION_BEGIN(index) { \
|
||||
extern uint32_t sectionTimes[2][4]; \
|
||||
sectionTimes[0][index] = micros(); \
|
||||
}
|
||||
|
||||
#define TIME_SECTION_END(index) { \
|
||||
extern uint32_t sectionTimes[2][4]; \
|
||||
sectionTimes[1][index] = micros(); \
|
||||
debug[index] = sectionTimes[1][index] - sectionTimes[0][index]; \
|
||||
}
|
||||
#else
|
||||
|
||||
#define TIME_SECTION_BEGIN(index) {}
|
||||
#define TIME_SECTION_END(index) {}
|
||||
|
||||
#endif
|
|
@ -19,8 +19,8 @@
|
|||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
|
@ -32,8 +32,6 @@
|
|||
#include "accgyro.h"
|
||||
#include "accgyro_l3gd20.h"
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
||||
#define READ_CMD ((uint8_t)0x80)
|
||||
#define MULTIPLEBYTE_CMD ((uint8_t)0x40)
|
||||
#define DUMMY_BYTE ((uint8_t)0x00)
|
||||
|
|
|
@ -19,6 +19,8 @@
|
|||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -31,8 +33,6 @@
|
|||
#include "accgyro.h"
|
||||
#include "accgyro_lsm303dlhc.h"
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
||||
// Addresses (7 bit address format)
|
||||
|
||||
#define LSM303DLHC_ACCEL_ADDRESS 0x19
|
||||
|
|
|
@ -20,6 +20,8 @@
|
|||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
|
@ -196,7 +198,8 @@ void MPU_DATA_READY_EXTI_Handler(void)
|
|||
uint32_t now = micros();
|
||||
callDelta = now - lastCalledAt;
|
||||
|
||||
UNUSED(callDelta);
|
||||
//UNUSED(callDelta);
|
||||
debug[0] = callDelta;
|
||||
|
||||
lastCalledAt = now;
|
||||
#endif
|
||||
|
@ -225,6 +228,13 @@ void configureMPUDataReadyInterruptHandling(void)
|
|||
gpioExtiLineConfig(mpu6050Config->exti_port_source, mpu6050Config->exti_pin_source);
|
||||
#endif
|
||||
|
||||
#ifdef ENSURE_MPU_DATA_READY_IS_LOW
|
||||
uint8_t status = GPIO_ReadInputDataBit(mpu6050Config->gpioPort, mpu6050Config->gpioPin);
|
||||
if (status) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
registerExti15_10_CallbackHandler(MPU_DATA_READY_EXTI_Handler);
|
||||
|
||||
EXTI_ClearITPendingBit(mpu6050Config->exti_line);
|
||||
|
|
|
@ -18,9 +18,10 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "system.h"
|
||||
|
||||
#include "adc.h"
|
||||
|
@ -32,7 +33,6 @@
|
|||
adc_config_t adcConfig[ADC_CHANNEL_COUNT];
|
||||
volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
||||
uint16_t adcGetChannel(uint8_t channel)
|
||||
{
|
||||
|
|
|
@ -209,6 +209,10 @@ bool bmp085Detect(const bmp085Config_t *config, baro_t *baro)
|
|||
return true;
|
||||
}
|
||||
|
||||
#ifdef BARO_EOC_GPIO
|
||||
unregisterExti15_10_CallbackHandler(BMP085_EOC_EXTI_Handler);
|
||||
#endif
|
||||
|
||||
BMP085_OFF;
|
||||
|
||||
return false;
|
||||
|
|
|
@ -487,6 +487,11 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
if (init->useOneshot) {
|
||||
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM4);
|
||||
}
|
||||
#endif
|
||||
#ifdef SPARKY
|
||||
if (init->useOneshot) {
|
||||
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2);
|
||||
}
|
||||
#endif
|
||||
ppmInConfig(timerHardwarePtr);
|
||||
} else if (type == MAP_TO_PWM_INPUT) {
|
||||
|
|
|
@ -44,7 +44,19 @@ void registerExti15_10_CallbackHandler(extiCallbackHandler *fn)
|
|||
extiCallbackHandler *candidate = exti15_10_handlers[index];
|
||||
if (!candidate) {
|
||||
exti15_10_handlers[index] = fn;
|
||||
break;
|
||||
return;
|
||||
}
|
||||
}
|
||||
failureMode(15); // EXTI15_10_CALLBACK_HANDLER_COUNT is too low for the amount of handlers required.
|
||||
}
|
||||
|
||||
void unregisterExti15_10_CallbackHandler(extiCallbackHandler *fn)
|
||||
{
|
||||
for (int index = 0; index < EXTI15_10_CALLBACK_HANDLER_COUNT; index++) {
|
||||
extiCallbackHandler *candidate = exti15_10_handlers[index];
|
||||
if (candidate == fn) {
|
||||
exti15_10_handlers[index] = 0;
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -127,7 +139,7 @@ void systemInit(void)
|
|||
cycleCounterInit();
|
||||
|
||||
|
||||
memset(exti15_10_handlers, 0, sizeof(exti15_10_handlers));
|
||||
memset(&exti15_10_handlers, 0x00, sizeof(exti15_10_handlers));
|
||||
// SysTick
|
||||
SysTick_Config(SystemCoreClock / 1000);
|
||||
}
|
||||
|
|
|
@ -39,3 +39,4 @@ extern uint32_t hse_value;
|
|||
typedef void extiCallbackHandler(void);
|
||||
|
||||
void registerExti15_10_CallbackHandler(extiCallbackHandler *fn);
|
||||
void unregisterExti15_10_CallbackHandler(extiCallbackHandler *fn);
|
||||
|
|
|
@ -23,6 +23,7 @@
|
|||
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -46,8 +47,6 @@
|
|||
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
||||
int32_t setVelocity = 0;
|
||||
uint8_t velocityControl = 0;
|
||||
int32_t errorVelocityI = 0;
|
||||
|
@ -90,10 +89,10 @@ static void applyMultirotorAltHold(void)
|
|||
// multirotor alt hold
|
||||
if (rcControlsConfig->alt_hold_fast_change) {
|
||||
// rapid alt changes
|
||||
if (ABS(rcCommand[THROTTLE] - initialThrottleHold) > rcControlsConfig->alt_hold_deadband) {
|
||||
if (ABS(rcData[THROTTLE] - initialThrottleHold) > rcControlsConfig->alt_hold_deadband) {
|
||||
errorVelocityI = 0;
|
||||
isAltHoldChanged = 1;
|
||||
rcCommand[THROTTLE] += (rcCommand[THROTTLE] > initialThrottleHold) ? -rcControlsConfig->alt_hold_deadband : rcControlsConfig->alt_hold_deadband;
|
||||
rcCommand[THROTTLE] += (rcData[THROTTLE] > initialThrottleHold) ? -rcControlsConfig->alt_hold_deadband : rcControlsConfig->alt_hold_deadband;
|
||||
} else {
|
||||
if (isAltHoldChanged) {
|
||||
AltHold = EstAlt;
|
||||
|
@ -103,9 +102,9 @@ static void applyMultirotorAltHold(void)
|
|||
}
|
||||
} else {
|
||||
// slow alt changes, mostly used for aerial photography
|
||||
if (ABS(rcCommand[THROTTLE] - initialThrottleHold) > rcControlsConfig->alt_hold_deadband) {
|
||||
if (ABS(rcData[THROTTLE] - initialThrottleHold) > rcControlsConfig->alt_hold_deadband) {
|
||||
// set velocity proportional to stick movement +100 throttle gives ~ +50 cm/s
|
||||
setVelocity = (rcCommand[THROTTLE] - initialThrottleHold) / 2;
|
||||
setVelocity = (rcData[THROTTLE] - initialThrottleHold) / 2;
|
||||
velocityControl = 1;
|
||||
isAltHoldChanged = 1;
|
||||
} else if (isAltHoldChanged) {
|
||||
|
@ -146,7 +145,7 @@ void updateAltHoldState(void)
|
|||
if (!FLIGHT_MODE(BARO_MODE)) {
|
||||
ENABLE_FLIGHT_MODE(BARO_MODE);
|
||||
AltHold = EstAlt;
|
||||
initialThrottleHold = rcCommand[THROTTLE];
|
||||
initialThrottleHold = rcData[THROTTLE];
|
||||
errorVelocityI = 0;
|
||||
altHoldThrottleAdjustment = 0;
|
||||
}
|
||||
|
@ -163,7 +162,7 @@ void updateSonarAltHoldState(void)
|
|||
if (!FLIGHT_MODE(SONAR_MODE)) {
|
||||
ENABLE_FLIGHT_MODE(SONAR_MODE);
|
||||
AltHold = EstAlt;
|
||||
initialThrottleHold = rcCommand[THROTTLE];
|
||||
initialThrottleHold = rcData[THROTTLE];
|
||||
errorVelocityI = 0;
|
||||
altHoldThrottleAdjustment = 0;
|
||||
}
|
||||
|
|
|
@ -21,6 +21,8 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
#ifdef AUTOTUNE
|
||||
|
||||
|
@ -40,8 +42,6 @@
|
|||
#include "config/config.h"
|
||||
#include "blackbox/blackbox.h"
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
||||
/*
|
||||
* Authors
|
||||
* Brad Quick - initial implementation in BradWii
|
||||
|
|
|
@ -151,7 +151,7 @@ void failsafeOnRxCycle(void)
|
|||
|
||||
#define REQUIRED_CHANNEL_MASK 0x0F // first 4 channels
|
||||
|
||||
// pulse duration is in micro secons (usec)
|
||||
// pulse duration is in micro seconds (usec)
|
||||
void failsafeCheckPulse(uint8_t channel, uint16_t pulseDuration)
|
||||
{
|
||||
static uint8_t goodChannelMask = 0;
|
||||
|
|
|
@ -23,7 +23,8 @@
|
|||
|
||||
#include "common/maths.h"
|
||||
|
||||
#include <platform.h>
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
|
@ -45,9 +46,6 @@
|
|||
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
||||
int16_t accSmooth[XYZ_AXIS_COUNT];
|
||||
int32_t accSum[XYZ_AXIS_COUNT];
|
||||
int16_t gyroData[FLIGHT_DYNAMICS_INDEX_COUNT] = { 0, 0, 0 };
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
|
@ -57,8 +58,6 @@
|
|||
|
||||
//#define MIXER_DEBUG
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
||||
uint8_t motorCount = 0;
|
||||
int16_t motor[MAX_SUPPORTED_MOTORS];
|
||||
int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
||||
|
|
|
@ -23,6 +23,7 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -53,8 +54,6 @@ extern int16_t magHold;
|
|||
|
||||
#ifdef GPS
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
||||
bool areSticksInApModePosition(uint16_t ap_mode);
|
||||
|
||||
// **********************
|
||||
|
|
|
@ -23,8 +23,8 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -51,9 +51,6 @@
|
|||
|
||||
#ifdef GPS
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
||||
|
||||
#define LOG_ERROR '?'
|
||||
#define LOG_IGNORED '!'
|
||||
#define LOG_SKIPPED '>'
|
||||
|
|
|
@ -385,12 +385,12 @@ const clivalue_t valueTable[] = {
|
|||
|
||||
{ "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, -1, 1 },
|
||||
|
||||
{ "pid_at_min_throttle", VAR_UINT8 | MASTER_VALUE, &masterConfig.mixerConfig.pid_at_min_throttle, 0, 1 },
|
||||
{ "yaw_direction", VAR_INT8 | PROFILE_VALUE, &masterConfig.mixerConfig.yaw_direction, -1, 1 },
|
||||
{ "pid_at_min_throttle", VAR_UINT8 | MASTER_VALUE, &masterConfig.mixerConfig.pid_at_min_throttle, 0, 1 },
|
||||
{ "yaw_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_direction, -1, 1 },
|
||||
#ifdef USE_SERVOS
|
||||
{ "tri_unarmed_servo", VAR_INT8 | PROFILE_VALUE, &masterConfig.mixerConfig.tri_unarmed_servo, 0, 1 },
|
||||
{ "servo_lowpass_freq", VAR_INT16 | PROFILE_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, 10, 400},
|
||||
{ "servo_lowpass_enable", VAR_INT8 | PROFILE_VALUE, &masterConfig.mixerConfig.servo_lowpass_enable, 0, 1 },
|
||||
{ "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.tri_unarmed_servo, 0, 1 },
|
||||
{ "servo_lowpass_freq", VAR_INT16 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, 10, 400},
|
||||
{ "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_enable, 0, 1 },
|
||||
#endif
|
||||
|
||||
{ "default_rate_profile", VAR_UINT8 | PROFILE_VALUE , &masterConfig.profile[0].defaultRateProfileIndex, 0, MAX_CONTROL_RATE_PROFILE_COUNT - 1 },
|
||||
|
|
|
@ -22,6 +22,7 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
|
@ -88,7 +89,6 @@ static serialPort_t *mspSerialPort;
|
|||
|
||||
extern uint16_t cycleTime; // FIXME dependency on mw.c
|
||||
extern uint16_t rssi; // FIXME dependency on mw.c
|
||||
extern int16_t debug[4]; // FIXME dependency on mw.c
|
||||
|
||||
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
|
||||
|
||||
|
@ -1077,10 +1077,12 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
break;
|
||||
#endif
|
||||
case MSP_DEBUG:
|
||||
headSerialReply(8);
|
||||
// make use of this crap, output some useful QA statistics
|
||||
//debug[3] = ((hse_value / 1000000) * 1000) + (SystemCoreClock / 1000000); // XX0YY [crystal clock : core clock]
|
||||
for (i = 0; i < 4; i++)
|
||||
headSerialReply(DEBUG16_VALUE_COUNT * sizeof(debug[0]));
|
||||
|
||||
// output some useful QA statistics
|
||||
// debug[x] = ((hse_value / 1000000) * 1000) + (SystemCoreClock / 1000000); // XX0YY [crystal clock : core clock]
|
||||
|
||||
for (i = 0; i < DEBUG16_VALUE_COUNT; i++)
|
||||
serialize16(debug[i]); // 4 variables are here for general monitoring purpose
|
||||
break;
|
||||
|
||||
|
|
|
@ -87,10 +87,8 @@
|
|||
#endif
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
#ifdef DEBUG_SECTION_TIMES
|
||||
uint32_t sectionTimes[2][4];
|
||||
#endif
|
||||
extern uint32_t previousTime;
|
||||
|
||||
#ifdef SOFTSERIAL_LOOPBACK
|
||||
|
|
|
@ -90,7 +90,6 @@ enum {
|
|||
/* for VBAT monitoring frequency */
|
||||
#define VBATFREQ 6 // to read battery voltage - nth number of loop iterations
|
||||
|
||||
int16_t debug[4];
|
||||
uint32_t currentTime = 0;
|
||||
uint32_t previousTime = 0;
|
||||
uint16_t cycleTime = 0; // this is the number in micro second to achieve a full loop, it can differ a little and is taken into account in the PID loop
|
||||
|
|
|
@ -21,9 +21,10 @@
|
|||
|
||||
#include <string.h>
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
|
@ -48,8 +49,6 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
||||
void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||
|
||||
bool sbusInit(rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||
|
|
|
@ -97,6 +97,8 @@
|
|||
#define ADC_DMA_CHANNEL DMA2_Channel1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_1
|
||||
|
|
|
@ -20,6 +20,8 @@
|
|||
#define TARGET_BOARD_IDENTIFIER "AFNA" // AFroNAze - NAZE might be considered misleading on Naze clones like the flip32.
|
||||
#define USE_HARDWARE_REVISION_DETECTION
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_3 // PB3 (LED)
|
||||
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
|
@ -27,7 +29,6 @@
|
|||
#define LED1_PIN Pin_4 // PB4 (LED)
|
||||
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
|
||||
|
||||
#define BEEP_GPIO GPIOA
|
||||
#define BEEP_PIN Pin_12 // PA12 (Beeper)
|
||||
#define BEEP_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
|
@ -69,6 +70,7 @@
|
|||
|
||||
#define USE_FLASH_M25P16
|
||||
|
||||
#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU data ready and BMP085 EOC
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define GYRO
|
||||
|
|
|
@ -106,6 +106,8 @@
|
|||
#define M25P16_SPI_INSTANCE SPI2
|
||||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define ADC_DMA_CHANNEL DMA2_Channel1
|
||||
|
|
|
@ -242,11 +242,12 @@ static void sendSpeed(void)
|
|||
if (!STATE(GPS_FIX)) {
|
||||
return;
|
||||
}
|
||||
//Speed should be sent in m/s (GPS speed is in cm/s)
|
||||
//Speed should be sent in knots (GPS speed is in cm/s)
|
||||
sendDataHead(ID_GPS_SPEED_BP);
|
||||
serialize16((GPS_speed * 0.01 + 0.5));
|
||||
//convert to knots: 1cm/s = 0.0194384449 knots
|
||||
serialize16(GPS_speed * 1944 / 10000);
|
||||
sendDataHead(ID_GPS_SPEED_AP);
|
||||
serialize16(0); //Not dipslayed
|
||||
serialize16((GPS_speed * 1944 / 100) % 100);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -57,8 +57,8 @@
|
|||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
#ifdef TELEMETRY
|
||||
|
||||
|
@ -81,8 +81,6 @@
|
|||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/hott.h"
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
||||
//#define HOTT_DEBUG
|
||||
|
||||
#define HOTT_MESSAGE_PREPARATION_FREQUENCY_5_HZ ((1000 * 1000) / 5)
|
||||
|
|
|
@ -322,8 +322,7 @@ void handleSmartPortTelemetry(void)
|
|||
break;
|
||||
#endif
|
||||
case FSSP_DATAID_VFAS :
|
||||
smartPortSendPackage(id, vbat * 83); // supposedly given in 0.1V, unknown requested unit
|
||||
// multiplying by 83 seems to make Taranis read correctly
|
||||
smartPortSendPackage(id, vbat * 10); // given in 0.1V, convert to volts
|
||||
smartPortHasRequest = 0;
|
||||
break;
|
||||
case FSSP_DATAID_CURRENT :
|
||||
|
|
|
@ -25,6 +25,8 @@
|
|||
#define BARO
|
||||
|
||||
extern "C" {
|
||||
#include "debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
|
@ -132,6 +134,7 @@ TEST(AltitudeHoldTest, TestCalculateTiltAngle)
|
|||
extern "C" {
|
||||
uint32_t rcModeActivationMask;
|
||||
int16_t rcCommand[4];
|
||||
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||
|
||||
uint32_t accTimeSum ; // keep track for integration of acc
|
||||
int accSumCount;
|
||||
|
@ -145,7 +148,7 @@ rollAndPitchInclination_t inclination;
|
|||
int32_t accSum[XYZ_AXIS_COUNT];
|
||||
//int16_t magADC[XYZ_AXIS_COUNT];
|
||||
int32_t BaroAlt;
|
||||
int16_t debug[4];
|
||||
int16_t debug[DEBUG16_VALUE_COUNT];
|
||||
|
||||
uint8_t stateFlags;
|
||||
uint16_t flightModeFlags;
|
||||
|
|
|
@ -23,6 +23,8 @@
|
|||
#define BARO
|
||||
|
||||
extern "C" {
|
||||
#include "debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
|
@ -37,6 +39,8 @@ extern "C" {
|
|||
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
@ -73,13 +77,14 @@ TEST(FlightImuTest, TestCalculateHeading)
|
|||
extern "C" {
|
||||
uint32_t rcModeActivationMask;
|
||||
int16_t rcCommand[4];
|
||||
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||
|
||||
uint16_t acc_1G;
|
||||
int16_t heading;
|
||||
gyro_t gyro;
|
||||
int16_t magADC[XYZ_AXIS_COUNT];
|
||||
int32_t BaroAlt;
|
||||
int16_t debug[4];
|
||||
int16_t debug[DEBUG16_VALUE_COUNT];
|
||||
|
||||
uint8_t stateFlags;
|
||||
uint16_t flightModeFlags;
|
||||
|
|
|
@ -21,6 +21,8 @@
|
|||
#include <limits.h>
|
||||
|
||||
extern "C" {
|
||||
#include "debug.h"
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
|
@ -293,7 +295,7 @@ int16_t rcCommand[4];
|
|||
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||
|
||||
uint32_t rcModeActivationMask;
|
||||
int16_t debug[4];
|
||||
int16_t debug[DEBUG16_VALUE_COUNT];
|
||||
|
||||
uint8_t stateFlags;
|
||||
uint16_t flightModeFlags;
|
||||
|
|
|
@ -22,6 +22,8 @@
|
|||
#include <limits.h>
|
||||
|
||||
extern "C" {
|
||||
#include "debug.h"
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
|
@ -148,7 +150,7 @@ TEST(TelemetryHottTest, PrepareGPSMessage_Altitude1m)
|
|||
|
||||
extern "C" {
|
||||
|
||||
int16_t debug[4];
|
||||
int16_t debug[DEBUG16_VALUE_COUNT];
|
||||
|
||||
uint8_t stateFlags;
|
||||
|
||||
|
|
Loading…
Reference in New Issue