Whitespace tidy
This commit is contained in:
parent
5eefa4e73f
commit
a86ac89448
|
@ -169,7 +169,7 @@ static bool hmc5883lRead(int16_t *magData)
|
||||||
{
|
{
|
||||||
uint8_t buf[6];
|
uint8_t buf[6];
|
||||||
#ifdef USE_MAG_SPI_HMC5883
|
#ifdef USE_MAG_SPI_HMC5883
|
||||||
bool ack = hmc5883SpiReadCommand(MAG_DATA_REGISTER, 6, buf);
|
bool ack = hmc5883SpiReadCommand(MAG_DATA_REGISTER, 6, buf);
|
||||||
#else
|
#else
|
||||||
bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf);
|
bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf);
|
||||||
#endif
|
#endif
|
||||||
|
@ -202,7 +202,7 @@ static bool hmc5883lInit(void)
|
||||||
// Note that the very first measurement after a gain change maintains the same gain as the previous setting.
|
// Note that the very first measurement after a gain change maintains the same gain as the previous setting.
|
||||||
// The new gain setting is effective from the second measurement and on.
|
// The new gain setting is effective from the second measurement and on.
|
||||||
#ifdef USE_MAG_SPI_HMC5883
|
#ifdef USE_MAG_SPI_HMC5883
|
||||||
hmc5883SpiWriteCommand(HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
|
hmc5883SpiWriteCommand(HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
|
||||||
#else
|
#else
|
||||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
|
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
|
||||||
#endif
|
#endif
|
||||||
|
@ -211,7 +211,7 @@ static bool hmc5883lInit(void)
|
||||||
|
|
||||||
for (i = 0; i < 10; i++) { // Collect 10 samples
|
for (i = 0; i < 10; i++) { // Collect 10 samples
|
||||||
#ifdef USE_MAG_SPI_HMC5883
|
#ifdef USE_MAG_SPI_HMC5883
|
||||||
hmc5883SpiWriteCommand(HMC58X3_R_MODE, 1);
|
hmc5883SpiWriteCommand(HMC58X3_R_MODE, 1);
|
||||||
#else
|
#else
|
||||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1);
|
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1);
|
||||||
#endif
|
#endif
|
||||||
|
@ -233,7 +233,7 @@ static bool hmc5883lInit(void)
|
||||||
|
|
||||||
// Apply the negative bias. (Same gain)
|
// Apply the negative bias. (Same gain)
|
||||||
#ifdef USE_MAG_SPI_HMC5883
|
#ifdef USE_MAG_SPI_HMC5883
|
||||||
hmc5883SpiWriteCommand(HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
|
hmc5883SpiWriteCommand(HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
|
||||||
#else
|
#else
|
||||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
|
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -151,7 +151,7 @@ static uint8_t loadDmaBufferDshot(motorDmaOutput_t *const motor, uint16_t packet
|
||||||
for (int i = 0; i < 16; i++) {
|
for (int i = 0; i < 16; i++) {
|
||||||
motor->dmaBuffer[i] = (packet & 0x8000) ? MOTOR_BIT_1 : MOTOR_BIT_0; // MSB first
|
motor->dmaBuffer[i] = (packet & 0x8000) ? MOTOR_BIT_1 : MOTOR_BIT_0; // MSB first
|
||||||
packet <<= 1;
|
packet <<= 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
return DSHOT_DMA_BUFFER_SIZE;
|
return DSHOT_DMA_BUFFER_SIZE;
|
||||||
}
|
}
|
||||||
|
|
|
@ -553,7 +553,7 @@ void sdcard_init(bool useDMA)
|
||||||
#ifdef SDCARD_DMA_CHANNEL_TX
|
#ifdef SDCARD_DMA_CHANNEL_TX
|
||||||
useDMAForTx = useDMA;
|
useDMAForTx = useDMA;
|
||||||
if (useDMAForTx) {
|
if (useDMAForTx) {
|
||||||
dmaInit(dmaGetIdentifier(SDCARD_DMA_CHANNEL_TX), OWNER_SDCARD, 0);
|
dmaInit(dmaGetIdentifier(SDCARD_DMA_CHANNEL_TX), OWNER_SDCARD, 0);
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
// DMA is not available
|
// DMA is not available
|
||||||
|
|
|
@ -29,13 +29,13 @@ typedef struct {
|
||||||
uint8_t rxBuffer[RX_BUFFER_SIZE];
|
uint8_t rxBuffer[RX_BUFFER_SIZE];
|
||||||
uint8_t txBuffer[TX_BUFFER_SIZE];
|
uint8_t txBuffer[TX_BUFFER_SIZE];
|
||||||
|
|
||||||
dyad_Stream *serv;
|
dyad_Stream *serv;
|
||||||
dyad_Stream *conn;
|
dyad_Stream *conn;
|
||||||
pthread_mutex_t txLock;
|
pthread_mutex_t txLock;
|
||||||
pthread_mutex_t rxLock;
|
pthread_mutex_t rxLock;
|
||||||
bool connected;
|
bool connected;
|
||||||
uint16_t clientCount;
|
uint16_t clientCount;
|
||||||
uint8_t id;
|
uint8_t id;
|
||||||
} tcpPort_t;
|
} tcpPort_t;
|
||||||
|
|
||||||
serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options);
|
serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||||
|
|
|
@ -60,7 +60,7 @@ void updateTransponderDMABufferArcitimer(transponder_t *transponder, const uint8
|
||||||
|
|
||||||
|
|
||||||
const struct transponderVTable arcitimerTansponderVTable = {
|
const struct transponderVTable arcitimerTansponderVTable = {
|
||||||
updateTransponderDMABufferArcitimer,
|
updateTransponderDMABufferArcitimer,
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -234,7 +234,7 @@ void tryArm(void)
|
||||||
pwmWriteDshotCommand(index, DSHOT_CMD_SPIN_DIRECTION_REVERSED);
|
pwmWriteDshotCommand(index, DSHOT_CMD_SPIN_DIRECTION_REVERSED);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
ENABLE_ARMING_FLAG(ARMED);
|
ENABLE_ARMING_FLAG(ARMED);
|
||||||
|
|
|
@ -427,16 +427,16 @@ static void imuCalculateEstimatedAttitude(timeUs_t currentTimeUs)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(SIMULATOR_BUILD) && defined(SKIP_IMU_CALC)
|
#if defined(SIMULATOR_BUILD) && defined(SKIP_IMU_CALC)
|
||||||
UNUSED(imuMahonyAHRSupdate);
|
UNUSED(imuMahonyAHRSupdate);
|
||||||
UNUSED(useAcc);
|
UNUSED(useAcc);
|
||||||
UNUSED(useMag);
|
UNUSED(useMag);
|
||||||
UNUSED(useYaw);
|
UNUSED(useYaw);
|
||||||
UNUSED(rawYawError);
|
UNUSED(rawYawError);
|
||||||
#else
|
#else
|
||||||
|
|
||||||
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_IMU_SYNC)
|
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_IMU_SYNC)
|
||||||
// printf("[imu]deltaT = %u, imuDeltaT = %u, currentTimeUs = %u, micros64_real = %lu\n", deltaT, imuDeltaT, currentTimeUs, micros64_real());
|
// printf("[imu]deltaT = %u, imuDeltaT = %u, currentTimeUs = %u, micros64_real = %lu\n", deltaT, imuDeltaT, currentTimeUs, micros64_real());
|
||||||
deltaT = imuDeltaT;
|
deltaT = imuDeltaT;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
imuMahonyAHRSupdate(deltaT * 1e-6f,
|
imuMahonyAHRSupdate(deltaT * 1e-6f,
|
||||||
|
|
|
@ -446,52 +446,52 @@ static void applyLedFixedLayers()
|
||||||
for (int ledIndex = 0; ledIndex < ledCounts.count; ledIndex++) {
|
for (int ledIndex = 0; ledIndex < ledCounts.count; ledIndex++) {
|
||||||
const ledConfig_t *ledConfig = &ledStripConfig()->ledConfigs[ledIndex];
|
const ledConfig_t *ledConfig = &ledStripConfig()->ledConfigs[ledIndex];
|
||||||
hsvColor_t color = *getSC(LED_SCOLOR_BACKGROUND);
|
hsvColor_t color = *getSC(LED_SCOLOR_BACKGROUND);
|
||||||
hsvColor_t nextColor = *getSC(LED_SCOLOR_BACKGROUND); //next color above the one selected, or color 0 if your are at the maximum
|
hsvColor_t nextColor = *getSC(LED_SCOLOR_BACKGROUND); //next color above the one selected, or color 0 if your are at the maximum
|
||||||
hsvColor_t previousColor = *getSC(LED_SCOLOR_BACKGROUND); //Previous color to the one selected, modulo color count
|
hsvColor_t previousColor = *getSC(LED_SCOLOR_BACKGROUND); //Previous color to the one selected, modulo color count
|
||||||
|
|
||||||
int fn = ledGetFunction(ledConfig);
|
int fn = ledGetFunction(ledConfig);
|
||||||
int hOffset = HSV_HUE_MAX;
|
int hOffset = HSV_HUE_MAX;
|
||||||
|
|
||||||
switch (fn) {
|
switch (fn) {
|
||||||
case LED_FUNCTION_COLOR:
|
case LED_FUNCTION_COLOR:
|
||||||
color = ledStripConfig()->colors[ledGetColor(ledConfig)];
|
color = ledStripConfig()->colors[ledGetColor(ledConfig)];
|
||||||
nextColor = ledStripConfig()->colors[(ledGetColor(ledConfig) + 1 + LED_CONFIGURABLE_COLOR_COUNT) % LED_CONFIGURABLE_COLOR_COUNT];
|
nextColor = ledStripConfig()->colors[(ledGetColor(ledConfig) + 1 + LED_CONFIGURABLE_COLOR_COUNT) % LED_CONFIGURABLE_COLOR_COUNT];
|
||||||
previousColor = ledStripConfig()->colors[(ledGetColor(ledConfig) - 1 + LED_CONFIGURABLE_COLOR_COUNT) % LED_CONFIGURABLE_COLOR_COUNT];
|
previousColor = ledStripConfig()->colors[(ledGetColor(ledConfig) - 1 + LED_CONFIGURABLE_COLOR_COUNT) % LED_CONFIGURABLE_COLOR_COUNT];
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case LED_FUNCTION_FLIGHT_MODE:
|
case LED_FUNCTION_FLIGHT_MODE:
|
||||||
for (unsigned i = 0; i < ARRAYLEN(flightModeToLed); i++)
|
for (unsigned i = 0; i < ARRAYLEN(flightModeToLed); i++)
|
||||||
if (!flightModeToLed[i].flightMode || FLIGHT_MODE(flightModeToLed[i].flightMode)) {
|
if (!flightModeToLed[i].flightMode || FLIGHT_MODE(flightModeToLed[i].flightMode)) {
|
||||||
const hsvColor_t *directionalColor = getDirectionalModeColor(ledIndex, &ledStripConfig()->modeColors[flightModeToLed[i].ledMode]);
|
const hsvColor_t *directionalColor = getDirectionalModeColor(ledIndex, &ledStripConfig()->modeColors[flightModeToLed[i].ledMode]);
|
||||||
if (directionalColor) {
|
if (directionalColor) {
|
||||||
color = *directionalColor;
|
color = *directionalColor;
|
||||||
}
|
|
||||||
|
|
||||||
break; // stop on first match
|
|
||||||
}
|
}
|
||||||
break;
|
|
||||||
|
|
||||||
case LED_FUNCTION_ARM_STATE:
|
break; // stop on first match
|
||||||
color = ARMING_FLAG(ARMED) ? *getSC(LED_SCOLOR_ARMED) : *getSC(LED_SCOLOR_DISARMED);
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case LED_FUNCTION_BATTERY:
|
case LED_FUNCTION_ARM_STATE:
|
||||||
color = HSV(RED);
|
color = ARMING_FLAG(ARMED) ? *getSC(LED_SCOLOR_ARMED) : *getSC(LED_SCOLOR_DISARMED);
|
||||||
hOffset += scaleRange(calculateBatteryPercentageRemaining(), 0, 100, -30, 120);
|
break;
|
||||||
break;
|
|
||||||
|
|
||||||
case LED_FUNCTION_RSSI:
|
case LED_FUNCTION_BATTERY:
|
||||||
color = HSV(RED);
|
color = HSV(RED);
|
||||||
hOffset += scaleRange(rssi * 100, 0, 1023, -30, 120);
|
hOffset += scaleRange(calculateBatteryPercentageRemaining(), 0, 100, -30, 120);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
case LED_FUNCTION_RSSI:
|
||||||
break;
|
color = HSV(RED);
|
||||||
|
hOffset += scaleRange(rssi * 100, 0, 1023, -30, 120);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (ledGetOverlayBit(ledConfig, LED_OVERLAY_THROTTLE)) //smooth fade with selected Aux channel of all HSV values from previousColor through color to nextColor
|
if (ledGetOverlayBit(ledConfig, LED_OVERLAY_THROTTLE)) //smooth fade with selected Aux channel of all HSV values from previousColor through color to nextColor
|
||||||
{
|
{
|
||||||
int centerPWM = (PWM_RANGE_MIN + PWM_RANGE_MAX) / 2;
|
int centerPWM = (PWM_RANGE_MIN + PWM_RANGE_MAX) / 2;
|
||||||
if (auxInput < centerPWM)
|
if (auxInput < centerPWM)
|
||||||
{
|
{
|
||||||
color.h = scaleRange(auxInput, PWM_RANGE_MIN, centerPWM, previousColor.h, color.h);
|
color.h = scaleRange(auxInput, PWM_RANGE_MIN, centerPWM, previousColor.h, color.h);
|
||||||
|
|
|
@ -8,11 +8,11 @@
|
||||||
*
|
*
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
|
@ -24,14 +24,14 @@
|
||||||
#include "drivers/timer_def.h"
|
#include "drivers/timer_def.h"
|
||||||
|
|
||||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM1
|
DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM1
|
||||||
DEF_TIM(TIM8, CH2, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM2
|
DEF_TIM(TIM8, CH2, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM2
|
||||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM3
|
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM3
|
||||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM4
|
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM4
|
||||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM5
|
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM5
|
||||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM6
|
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM6
|
||||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM7
|
DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM7
|
||||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM8
|
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM8
|
||||||
|
|
||||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED|TIM_USE_TRANSPONDER, TIMER_OUTPUT_ENABLED), // LED
|
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED|TIM_USE_TRANSPONDER, TIMER_OUTPUT_ENABLED), // LED
|
||||||
};
|
};
|
||||||
|
|
|
@ -81,7 +81,7 @@
|
||||||
|
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||||
|
|
||||||
#define DEFAULT_FEATURES FEATURE_OSD
|
#define DEFAULT_FEATURES FEATURE_OSD
|
||||||
|
|
||||||
#else
|
#else
|
||||||
|
|
||||||
|
|
|
@ -30,7 +30,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0),
|
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0),
|
||||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1, 0),
|
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1, 0),
|
||||||
#if defined(PLUMF4) || defined(KIWIF4V2)
|
#if defined(PLUMF4) || defined(KIWIF4V2)
|
||||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_LED, 1, 0), //LED
|
DEF_TIM(TIM2, CH1, PA0, TIM_USE_LED, 1, 0), //LED
|
||||||
#else
|
#else
|
||||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0), // LED
|
DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0), // LED
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -33,7 +33,7 @@
|
||||||
#ifdef TARGET_CONFIG
|
#ifdef TARGET_CONFIG
|
||||||
void targetConfiguration(void)
|
void targetConfiguration(void)
|
||||||
{
|
{
|
||||||
voltageSensorADCConfigMutable(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale = VBAT_SCALE;
|
voltageSensorADCConfigMutable(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale = VBAT_SCALE;
|
||||||
barometerConfigMutable()->baro_hardware = 0;
|
barometerConfigMutable()->baro_hardware = 0;
|
||||||
compassConfigMutable()->mag_hardware = 0;
|
compassConfigMutable()->mag_hardware = 0;
|
||||||
osdConfigMutable()->item_pos[OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 1) | VISIBLE_FLAG;
|
osdConfigMutable()->item_pos[OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 1) | VISIBLE_FLAG;
|
||||||
|
|
|
@ -23,9 +23,9 @@
|
||||||
|
|
||||||
void targetPreInit(void)
|
void targetPreInit(void)
|
||||||
{
|
{
|
||||||
IO_t osdChSwitch = IOGetByTag(IO_TAG(OSD_CH_SWITCH));
|
IO_t osdChSwitch = IOGetByTag(IO_TAG(OSD_CH_SWITCH));
|
||||||
IOInit(osdChSwitch, OWNER_SYSTEM, 0);
|
IOInit(osdChSwitch, OWNER_SYSTEM, 0);
|
||||||
IOConfigGPIO(osdChSwitch, IOCFG_OUT_PP);
|
IOConfigGPIO(osdChSwitch, IOCFG_OUT_PP);
|
||||||
IOLo(osdChSwitch);
|
IOLo(osdChSwitch);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -34,5 +34,5 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM6
|
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM6
|
||||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM7
|
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM7
|
||||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM8
|
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM8
|
||||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0), // LED_STRIP
|
DEF_TIM(TIM8, CH1, PC6, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0), // LED_STRIP
|
||||||
};
|
};
|
||||||
|
|
|
@ -26,14 +26,14 @@
|
||||||
|
|
||||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
|
|
||||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_PPM | TIM_USE_TRANSPONDER, TIMER_INPUT_ENABLED), // PPM IN
|
DEF_TIM(TIM2, CH2, PA1, TIM_USE_PPM | TIM_USE_TRANSPONDER, TIMER_INPUT_ENABLED), // PPM IN
|
||||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, TIMER_OUTPUT_ENABLED), // SS1Rx
|
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, TIMER_OUTPUT_ENABLED), // SS1Rx
|
||||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_PWM, TIMER_OUTPUT_ENABLED), // SS1Tx
|
DEF_TIM(TIM3, CH2, PB5, TIM_USE_PWM, TIMER_OUTPUT_ENABLED), // SS1Tx
|
||||||
|
|
||||||
DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S1
|
DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S1
|
||||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S2
|
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S2
|
||||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S3
|
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S3
|
||||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S4
|
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S4
|
||||||
|
|
||||||
DEF_TIM(TIM15, CH1, PA2, TIM_USE_LED, 1), // GPIO TIMER - LED_STRIP
|
DEF_TIM(TIM15, CH1, PA2, TIM_USE_LED, 1), // GPIO TIMER - LED_STRIP
|
||||||
};
|
};
|
||||||
|
|
|
@ -15,7 +15,7 @@
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "MCF3" // LumbaF3 Flight Controller by mC
|
#define TARGET_BOARD_IDENTIFIER "MCF3" // LumbaF3 Flight Controller by mC
|
||||||
|
|
||||||
#define LED0_PIN PB3
|
#define LED0_PIN PB3
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
|
@ -42,11 +42,11 @@
|
||||||
|
|
||||||
#define GYRO
|
#define GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW90_DEG
|
#define GYRO_MPU6000_ALIGN CW90_DEG
|
||||||
|
|
||||||
#define ACC
|
#define ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW90_DEG
|
#define ACC_MPU6000_ALIGN CW90_DEG
|
||||||
|
|
||||||
#define USE_VCP
|
#define USE_VCP
|
||||||
#define USE_UART1
|
#define USE_UART1
|
||||||
|
@ -79,7 +79,7 @@
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||||
#define DEFAULT_FEATURES FEATURE_TELEMETRY
|
#define DEFAULT_FEATURES FEATURE_TELEMETRY
|
||||||
|
|
||||||
// IO - from schematics
|
// IO - from schematics
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -25,16 +25,16 @@
|
||||||
#include "drivers/timer_def.h"
|
#include "drivers/timer_def.h"
|
||||||
|
|
||||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0), // PPM
|
DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0), // PPM
|
||||||
|
|
||||||
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S1 DMA1_ST4
|
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S1 DMA1_ST4
|
||||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // S2 DMA2_ST2
|
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // S2 DMA2_ST2
|
||||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // S3 DMA2_ST4
|
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // S3 DMA2_ST4
|
||||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S4 DMA2_ST7
|
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S4 DMA2_ST7
|
||||||
|
|
||||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S5 DMA1_ST5
|
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S5 DMA1_ST5
|
||||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S6 DMA2_ST6
|
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S6 DMA2_ST6
|
||||||
|
|
||||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0) // LED DMA1_ST0
|
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0) // LED DMA1_ST0
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -33,8 +33,8 @@
|
||||||
#define USE_SPI_DEVICE_1
|
#define USE_SPI_DEVICE_1
|
||||||
|
|
||||||
#define SPI1_SCK_PIN PA5
|
#define SPI1_SCK_PIN PA5
|
||||||
#define SPI1_MISO_PIN PA6
|
#define SPI1_MISO_PIN PA6
|
||||||
#define SPI1_MOSI_PIN PA7
|
#define SPI1_MOSI_PIN PA7
|
||||||
|
|
||||||
#define MPU6500_CS_PIN PC2
|
#define MPU6500_CS_PIN PC2
|
||||||
#define MPU6500_SPI_INSTANCE SPI1
|
#define MPU6500_SPI_INSTANCE SPI1
|
||||||
|
@ -57,8 +57,8 @@
|
||||||
|
|
||||||
#define USE_SPI_DEVICE_3
|
#define USE_SPI_DEVICE_3
|
||||||
#define SPI3_SCK_PIN PB3
|
#define SPI3_SCK_PIN PB3
|
||||||
#define SPI3_MISO_PIN PB4
|
#define SPI3_MISO_PIN PB4
|
||||||
#define SPI3_MOSI_PIN PB5
|
#define SPI3_MOSI_PIN PB5
|
||||||
|
|
||||||
#define SDCARD_SPI_INSTANCE SPI3
|
#define SDCARD_SPI_INSTANCE SPI3
|
||||||
#define SDCARD_SPI_CS_PIN PC1
|
#define SDCARD_SPI_CS_PIN PC1
|
||||||
|
@ -68,16 +68,16 @@
|
||||||
// Divide to under 25MHz for normal operation:
|
// Divide to under 25MHz for normal operation:
|
||||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
|
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
|
||||||
|
|
||||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream7
|
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream7
|
||||||
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF7
|
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF7
|
||||||
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
|
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
|
||||||
#define SDCARD_DMA_CHANNEL DMA_Channel_0
|
#define SDCARD_DMA_CHANNEL DMA_Channel_0
|
||||||
|
|
||||||
// *************** OSD *****************************
|
// *************** OSD *****************************
|
||||||
#define USE_SPI_DEVICE_2
|
#define USE_SPI_DEVICE_2
|
||||||
#define SPI2_SCK_PIN PB13
|
#define SPI2_SCK_PIN PB13
|
||||||
#define SPI2_MISO_PIN PB14
|
#define SPI2_MISO_PIN PB14
|
||||||
#define SPI2_MOSI_PIN PB15
|
#define SPI2_MOSI_PIN PB15
|
||||||
|
|
||||||
#define OSD
|
#define OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
|
|
|
@ -222,12 +222,12 @@ typedef enum
|
||||||
} FLASH_Status;
|
} FLASH_Status;
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
double timestamp; // in seconds
|
double timestamp; // in seconds
|
||||||
double imu_angular_velocity_rpy[3]; // rad/s -> range: +/- 8192; +/- 2000 deg/se
|
double imu_angular_velocity_rpy[3]; // rad/s -> range: +/- 8192; +/- 2000 deg/se
|
||||||
double imu_linear_acceleration_xyz[3]; // m/s/s NED, body frame -> sim 1G = 9.80665, FC 1G = 256
|
double imu_linear_acceleration_xyz[3]; // m/s/s NED, body frame -> sim 1G = 9.80665, FC 1G = 256
|
||||||
double imu_orientation_quat[4]; //w, x, y, z
|
double imu_orientation_quat[4]; //w, x, y, z
|
||||||
double velocity_xyz[3]; // m/s, earth frame
|
double velocity_xyz[3]; // m/s, earth frame
|
||||||
double position_xyz[3]; // meters, NED from origin
|
double position_xyz[3]; // meters, NED from origin
|
||||||
} fdm_packet;
|
} fdm_packet;
|
||||||
typedef struct {
|
typedef struct {
|
||||||
float motor_speed[4]; // normal: [0.0, 1.0], 3D: [-1.0, 1.0]
|
float motor_speed[4]; // normal: [0.0, 1.0], 3D: [-1.0, 1.0]
|
||||||
|
|
|
@ -13,56 +13,56 @@
|
||||||
#include "udplink.h"
|
#include "udplink.h"
|
||||||
|
|
||||||
int udpInit(udpLink_t* link, const char* addr, int port, bool isServer) {
|
int udpInit(udpLink_t* link, const char* addr, int port, bool isServer) {
|
||||||
int one = 1;
|
int one = 1;
|
||||||
|
|
||||||
if ((link->fd = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) == -1) {
|
if ((link->fd = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) == -1) {
|
||||||
return -2;
|
return -2;
|
||||||
}
|
}
|
||||||
|
|
||||||
setsockopt(link->fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)); // can multi-bind
|
setsockopt(link->fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)); // can multi-bind
|
||||||
fcntl(link->fd, F_SETFL, fcntl(link->fd, F_GETFL, 0) | O_NONBLOCK); // nonblock
|
fcntl(link->fd, F_SETFL, fcntl(link->fd, F_GETFL, 0) | O_NONBLOCK); // nonblock
|
||||||
|
|
||||||
link->isServer = isServer;
|
link->isServer = isServer;
|
||||||
memset(&link->si, 0, sizeof(link->si));
|
memset(&link->si, 0, sizeof(link->si));
|
||||||
link->si.sin_family = AF_INET;
|
link->si.sin_family = AF_INET;
|
||||||
link->si.sin_port = htons(port);
|
link->si.sin_port = htons(port);
|
||||||
link->port = port;
|
link->port = port;
|
||||||
|
|
||||||
if (addr == NULL) {
|
if (addr == NULL) {
|
||||||
link->si.sin_addr.s_addr = htonl(INADDR_ANY);
|
link->si.sin_addr.s_addr = htonl(INADDR_ANY);
|
||||||
}else{
|
}else{
|
||||||
link->si.sin_addr.s_addr = inet_addr(addr);
|
link->si.sin_addr.s_addr = inet_addr(addr);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (isServer) {
|
if (isServer) {
|
||||||
if (bind(link->fd, (const struct sockaddr *)&link->si, sizeof(link->si)) == -1) {
|
if (bind(link->fd, (const struct sockaddr *)&link->si, sizeof(link->si)) == -1) {
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
int udpSend(udpLink_t* link, const void* data, size_t size) {
|
int udpSend(udpLink_t* link, const void* data, size_t size) {
|
||||||
return sendto(link->fd, data, size, 0, (struct sockaddr *)&link->si, sizeof(link->si));
|
return sendto(link->fd, data, size, 0, (struct sockaddr *)&link->si, sizeof(link->si));
|
||||||
}
|
}
|
||||||
|
|
||||||
int udpRecv(udpLink_t* link, void* data, size_t size, uint32_t timeout_ms) {
|
int udpRecv(udpLink_t* link, void* data, size_t size, uint32_t timeout_ms) {
|
||||||
fd_set fds;
|
fd_set fds;
|
||||||
struct timeval tv;
|
struct timeval tv;
|
||||||
|
|
||||||
FD_ZERO(&fds);
|
FD_ZERO(&fds);
|
||||||
FD_SET(link->fd, &fds);
|
FD_SET(link->fd, &fds);
|
||||||
|
|
||||||
tv.tv_sec = timeout_ms / 1000;
|
tv.tv_sec = timeout_ms / 1000;
|
||||||
tv.tv_usec = (timeout_ms % 1000) * 1000UL;
|
tv.tv_usec = (timeout_ms % 1000) * 1000UL;
|
||||||
|
|
||||||
if (select(link->fd+1, &fds, NULL, NULL, &tv) != 1) {
|
if (select(link->fd+1, &fds, NULL, NULL, &tv) != 1) {
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
socklen_t len;
|
socklen_t len;
|
||||||
int ret;
|
int ret;
|
||||||
ret = recvfrom(link->fd, data, size, 0, (struct sockaddr *)&link->recv, &len);
|
ret = recvfrom(link->fd, data, size, 0, (struct sockaddr *)&link->recv, &len);
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue