1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-14 11:59:58 +03:00

Merge commit 'fix_waiting_for_data_problem' into betaflight

This commit is contained in:
borisbstyle 2015-11-05 01:23:40 +01:00
commit 52868ddc00
6 changed files with 38 additions and 24 deletions

View file

@ -165,7 +165,7 @@ Re-apply any new defaults as desired.
| `vbat_warning_cell_voltage` | | 10 | 50 | 35 | Master | UINT8 | | `vbat_warning_cell_voltage` | | 10 | 50 | 35 | Master | UINT8 |
| `current_meter_scale` | This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the Überdistro with a 0.25mOhm shunt. | -10000 | 10000 | 400 | Master | INT16 | | `current_meter_scale` | This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the Überdistro with a 0.25mOhm shunt. | -10000 | 10000 | 400 | Master | INT16 |
| `current_meter_offset` | This sets the output offset voltage of the current sensor in millivolts. | 0 | 3300 | 0 | Master | UINT16 | | `current_meter_offset` | This sets the output offset voltage of the current sensor in millivolts. | 0 | 3300 | 0 | Master | UINT16 |
| `multiwii_current_meter_output` | Default current output via MSP is in 0.01A steps. Setting this to 1 causes output in default multiwii scaling (1mA steps). | 0 | 1 | None defined! | Master | UINT8 | | `multiwii_current_meter_output` | Default current output via MSP is in 0.01A steps. Setting this to 1 causes output in default multiwii scaling (1mA steps). | 0 | 1 | 0 | Master | UINT8 |
| `current_meter_type` | | 0 | 2 | 1 | Master | UINT8 | | `current_meter_type` | | 0 | 2 | 1 | Master | UINT8 |
| `align_gyro` | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. Default of zero means the driver determines alignment (and this generally means it's configured for standard hardware). Default orientation of X forward, Y right, Z up is 1. After that, the numbers are as follows, and mean sensor is rotated. CW0_DEG=1, CW90_DEG=2, CW180_DEG=3, CW270_DEG=4, CW0_DEG_FLIP=5, CW90_DEG_FLIP=6, CW180_DEG_FLIP=7, CW270_DEG_FLIP=8. This should cover all orientations. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. | 0 | 8 | 0 | Master | UINT8 | | `align_gyro` | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. Default of zero means the driver determines alignment (and this generally means it's configured for standard hardware). Default orientation of X forward, Y right, Z up is 1. After that, the numbers are as follows, and mean sensor is rotated. CW0_DEG=1, CW90_DEG=2, CW180_DEG=3, CW270_DEG=4, CW0_DEG_FLIP=5, CW90_DEG_FLIP=6, CW180_DEG_FLIP=7, CW270_DEG_FLIP=8. This should cover all orientations. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. | 0 | 8 | 0 | Master | UINT8 |
| `align_acc` | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. Default of zero means the driver determines alignment (and this generally means it's configured for standard hardware). Default orientation of X forward, Y right, Z up is 1. After that, the numbers are as follows, and mean sensor is rotated. CW0_DEG=1, CW90_DEG=2, CW180_DEG=3, CW270_DEG=4, CW0_DEG_FLIP=5, CW90_DEG_FLIP=6, CW180_DEG_FLIP=7, CW270_DEG_FLIP=8. This should cover all orientations. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. | 0 | 8 | 0 | Master | UINT8 | | `align_acc` | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. Default of zero means the driver determines alignment (and this generally means it's configured for standard hardware). Default orientation of X forward, Y right, Z up is 1. After that, the numbers are as follows, and mean sensor is rotated. CW0_DEG=1, CW90_DEG=2, CW180_DEG=3, CW270_DEG=4, CW0_DEG_FLIP=5, CW90_DEG_FLIP=6, CW180_DEG_FLIP=7, CW270_DEG_FLIP=8. This should cover all orientations. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. | 0 | 8 | 0 | Master | UINT8 |
@ -185,7 +185,7 @@ Re-apply any new defaults as desired.
| `throttle_correction_value` | The throttle_correction_value will be added to the throttle input. It will be maximal at the throttle_correction_angle and over, null when the copter is leveled and proportional in bewteen. The angle is set with 0.1 deg steps from 1 to 900, ie : 300 = 30.0 deg, 225 = 22.5 deg. | 0 | 150 | 0 | Profile | UINT8 | | `throttle_correction_value` | The throttle_correction_value will be added to the throttle input. It will be maximal at the throttle_correction_angle and over, null when the copter is leveled and proportional in bewteen. The angle is set with 0.1 deg steps from 1 to 900, ie : 300 = 30.0 deg, 225 = 22.5 deg. | 0 | 150 | 0 | Profile | UINT8 |
| `throttle_correction_angle` | The throttle_correction_value will be added to the throttle input. It will be maximal at the throttle_correction_angle and over, null when the copter is leveled and proportional in bewteen. The angle is set with 0.1 deg steps from 1 to 900, ie : 300 = 30.0 deg, 225 = 22.5 deg. | 1 | 900 | 800 | Profile | UINT16 | | `throttle_correction_angle` | The throttle_correction_value will be added to the throttle input. It will be maximal at the throttle_correction_angle and over, null when the copter is leveled and proportional in bewteen. The angle is set with 0.1 deg steps from 1 to 900, ie : 300 = 30.0 deg, 225 = 22.5 deg. | 1 | 900 | 800 | Profile | UINT16 |
| `yaw_control_direction` | | -1 | 1 | 1 | Master | INT8 | | `yaw_control_direction` | | -1 | 1 | 1 | Master | INT8 |
| `yaw_motor_direction` | | -1 | 1 | 1 | Profile | INT8 | | `yaw_motor_direction` | | -1 | 1 | 1 | Profile | INT8 |
| `yaw_jump_prevention_limit` | Prevent yaw jumps during yaw stops. To disable set to 500. | 80 | 500 | 200 | Master | UINT16 | | `yaw_jump_prevention_limit` | Prevent yaw jumps during yaw stops. To disable set to 500. | 80 | 500 | 200 | Master | UINT16 |
| `tri_unarmed_servo` | On tricopter mix only, if this is set to 1, servo will always be correcting regardless of armed state. to disable this, set it to 0. | 0 | 1 | 1 | Profile | INT8 | | `tri_unarmed_servo` | On tricopter mix only, if this is set to 1, servo will always be correcting regardless of armed state. to disable this, set it to 0. | 0 | 1 | 1 | Profile | INT8 |
| `default_rate_profile` | Default = profile number | 0 | 2 | | Profile | UINT8 | | `default_rate_profile` | Default = profile number | 0 | 2 | | Profile | UINT8 |
@ -201,7 +201,7 @@ Re-apply any new defaults as desired.
| `failsafe_delay` | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). | 0 | 200 | 10 | Profile | UINT8 | | `failsafe_delay` | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). | 0 | 200 | 10 | Profile | UINT8 |
| `failsafe_off_delay` | Time in deciseconds to wait before turning off motors when failsafe is activated. See [Failsafe documentation](Failsafe.md#failsafe_off_delay). | 0 | 200 | 200 | Profile | UINT8 | | `failsafe_off_delay` | Time in deciseconds to wait before turning off motors when failsafe is activated. See [Failsafe documentation](Failsafe.md#failsafe_off_delay). | 0 | 200 | 200 | Profile | UINT8 |
| `failsafe_throttle` | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | 1000 | 2000 | 1000 | Profile | UINT16 | | `failsafe_throttle` | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | 1000 | 2000 | 1000 | Profile | UINT16 |
| `rx_min_usec` | Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of `mid_rc`. | 100 | 2000 | 985 | Profile | UINT16 | | `rx_min_usec` | Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of `mid_rc`. | 100 | 2000 | 885 | Profile | UINT16 |
| `rx_max_usec` | Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of `mid_rc`. | 100 | 3000 | 2115 | Profile | UINT16 | | `rx_max_usec` | Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of `mid_rc`. | 100 | 3000 | 2115 | Profile | UINT16 |
| `gimbal_mode` | When feature SERVO_TILT is enabled, this can be either 0=normal gimbal (default) or 1=tiltmix gimbal | 0 | 1 | 0 | Profile | UINT8 | | `gimbal_mode` | When feature SERVO_TILT is enabled, this can be either 0=normal gimbal (default) or 1=tiltmix gimbal | 0 | 1 | 0 | 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 MPU6000, 8 for MPU6500 or 1 to disable accelerometer alltogether - resulting in gyro-only operation. | 0 | 9 | 0 | Master | 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 MPU6000, 8 for MPU6500 or 1 to disable accelerometer alltogether - resulting in gyro-only operation. | 0 | 9 | 0 | Master | UINT8 |
@ -228,15 +228,15 @@ Re-apply any new defaults as desired.
| `p_yaw` | | 0 | 200 | 85 | Profile | UINT8 | | `p_yaw` | | 0 | 200 | 85 | Profile | UINT8 |
| `i_yaw` | | 0 | 200 | 45 | Profile | UINT8 | | `i_yaw` | | 0 | 200 | 45 | Profile | UINT8 |
| `d_yaw` | | 0 | 200 | 0 | Profile | UINT8 | | `d_yaw` | | 0 | 200 | 0 | Profile | UINT8 |
| `p_pitchf` | | 0 | 100 | 2.5 | Profile | FLOAT | | `p_pitchf` | | 0 | 100 | 1.5 | Profile | FLOAT |
| `i_pitchf` | | 0 | 100 | 0.6 | Profile | FLOAT | | `i_pitchf` | | 0 | 100 | 0.4 | Profile | FLOAT |
| `d_pitchf` | | 0 | 100 | 0.06 | Profile | FLOAT | | `d_pitchf` | | 0 | 100 | 0.03 | Profile | FLOAT |
| `p_rollf` | | 0 | 100 | 2.5 | Profile | FLOAT | | `p_rollf` | | 0 | 100 | 1.5 | Profile | FLOAT |
| `i_rollf` | | 0 | 100 | 0.6 | Profile | FLOAT | | `i_rollf` | | 0 | 100 | 0.4 | Profile | FLOAT |
| `d_rollf` | | 0 | 100 | 0.06 | Profile | FLOAT | | `d_rollf` | | 0 | 100 | 0.03 | Profile | FLOAT |
| `p_yawf` | | 0 | 100 | 8 | Profile | FLOAT | | `p_yawf` | | 0 | 100 | 2.5 | Profile | FLOAT |
| `i_yawf` | | 0 | 100 | 0.5 | Profile | FLOAT | | `i_yawf` | | 0 | 100 | 1.0 | Profile | FLOAT |
| `d_yawf` | | 0 | 100 | 0.05 | Profile | FLOAT | | `d_yawf` | | 0 | 100 | 0.00 | Profile | FLOAT |
| `level_horizon` | | 0 | 10 | 3 | Profile | FLOAT | | `level_horizon` | | 0 | 10 | 3 | Profile | FLOAT |
| `level_angle` | | 0 | 10 | 5 | Profile | FLOAT | | `level_angle` | | 0 | 10 | 5 | Profile | FLOAT |
| `sensitivity_horizon` | | 0 | 250 | 75 | Profile | UINT8 | | `sensitivity_horizon` | | 0 | 250 | 75 | Profile | UINT8 |

View file

@ -49,7 +49,7 @@ static uartPort_t uartPort3;
#endif #endif
// Using RX DMA disables the use of receive callbacks // Using RX DMA disables the use of receive callbacks
#define USE_USART1_RX_DMA //#define USE_USART1_RX_DMA
#if defined(CC3D) // FIXME move board specific code to target.h files. #if defined(CC3D) // FIXME move board specific code to target.h files.
#undef USE_USART1_RX_DMA #undef USE_USART1_RX_DMA

View file

@ -38,7 +38,7 @@
#include "serial_uart_impl.h" #include "serial_uart_impl.h"
// Using RX DMA disables the use of receive callbacks // Using RX DMA disables the use of receive callbacks
#define USE_USART1_RX_DMA //#define USE_USART1_RX_DMA
//#define USE_USART2_RX_DMA //#define USE_USART2_RX_DMA
//#define USE_USART2_TX_DMA //#define USE_USART2_TX_DMA
//#define USE_USART3_RX_DMA //#define USE_USART3_RX_DMA

View file

@ -159,11 +159,19 @@ void systemInit(void)
cachedRccCsrValue = RCC->CSR; cachedRccCsrValue = RCC->CSR;
RCC_ClearFlag(); RCC_ClearFlag();
enableGPIOPowerUsageAndNoiseReductions(); enableGPIOPowerUsageAndNoiseReductions();
#ifdef STM32F10X #ifdef STM32F10X
// Set USART1 TX (PA9) to output and high state to prevent a rs232 break condition on reset.
// See issue https://github.com/cleanflight/cleanflight/issues/1433
gpio_config_t gpio;
gpio.mode = Mode_Out_PP;
gpio.speed = Speed_2MHz;
gpio.pin = Pin_9;
digitalHi(GPIOA, gpio.pin);
gpioInit(GPIOA, &gpio);
// Turn off JTAG port 'cause we're using the GPIO for leds // Turn off JTAG port 'cause we're using the GPIO for leds
#define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24) #define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24)
AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW; AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW;

View file

@ -56,7 +56,7 @@
#define MAG #define MAG
#define USE_MAG_AK8975 #define USE_MAG_AK8975
#define MAG_AK8975_ALIGN CW0_DEG_FLIP #define MAG_AK8975_ALIGN CW180_DEG_FLIP
#define LED0 #define LED0
#define LED1 #define LED1

View file

@ -423,13 +423,19 @@ static void hottCheckSerialData(uint32_t currentMicros)
} }
} }
static void workAroundForHottTelemetryOnUsart(serialPort_t *instance, portMode_t mode) {
closeSerialPort(hottPort);
hottPort = openSerialPort(instance->identifier, FUNCTION_TELEMETRY_HOTT, NULL, HOTT_BAUDRATE, mode, SERIAL_NOT_INVERTED);
}
static void hottSendTelemetryData(void) { static void hottSendTelemetryData(void) {
if (!hottIsSending) { if (!hottIsSending) {
hottIsSending = true; hottIsSending = true;
// FIXME temorary workaround for HoTT not working on Hardware serial ports due to hardware/softserial serial port initialisation differences // FIXME temorary workaround for HoTT not working on Hardware serial ports due to hardware/softserial serial port initialisation differences
//serialSetMode(hottPort, MODE_TX); if ((portConfig->identifier == SERIAL_PORT_USART1) || (portConfig->identifier == SERIAL_PORT_USART2) || (portConfig->identifier == SERIAL_PORT_USART3))
closeSerialPort(hottPort); workAroundForHottTelemetryOnUsart(hottPort, MODE_TX);
hottPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_HOTT, NULL, HOTT_BAUDRATE, MODE_TX, SERIAL_NOT_INVERTED); else
serialSetMode(hottPort, MODE_TX);
hottMsgCrc = 0; hottMsgCrc = 0;
return; return;
} }
@ -437,11 +443,11 @@ static void hottSendTelemetryData(void) {
if (hottMsgRemainingBytesToSendCount == 0) { if (hottMsgRemainingBytesToSendCount == 0) {
hottMsg = NULL; hottMsg = NULL;
hottIsSending = false; hottIsSending = false;
// FIXME temorary workaround for HoTT not working on Hardware serial ports due to hardware/softserial serial port initialisation differences // FIXME temorary workaround for HoTT not working on Hardware serial ports due to hardware/softserial serial port initialisation differences
//serialSetMode(hottPort, MODE_RX); if ((portConfig->identifier == SERIAL_PORT_USART1) || (portConfig->identifier == SERIAL_PORT_USART2) || (portConfig->identifier == SERIAL_PORT_USART3))
closeSerialPort(hottPort); workAroundForHottTelemetryOnUsart(hottPort, MODE_RX);
hottPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_HOTT, NULL, HOTT_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED); else
serialSetMode(hottPort, MODE_RX);
flushHottRxBuffer(); flushHottRxBuffer();
return; return;
} }