1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 16:55:36 +03:00

Syncing with Cleanflight upstream

This commit is contained in:
Nicholas Sherlock 2014-12-22 23:23:26 +13:00
commit 1b1a285b4a
63 changed files with 632 additions and 20047 deletions

View file

@ -27,7 +27,10 @@
#include "common/axis.h"
#include "flight/flight.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
@ -35,6 +38,7 @@
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "io/statusindicator.h"
#include "sensors/acceleration.h"
@ -104,7 +108,7 @@ profile_t *currentProfile;
static uint8_t currentControlRateProfileIndex = 0;
controlRateConfig_t *currentControlRateProfile;
static const uint8_t EEPROM_CONF_VERSION = 86;
static const uint8_t EEPROM_CONF_VERSION = 88;
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
{
@ -216,6 +220,7 @@ void resetBatteryConfig(batteryConfig_t *batteryConfig)
batteryConfig->vbatscale = VBAT_SCALE_DEFAULT;
batteryConfig->vbatmaxcellvoltage = 43;
batteryConfig->vbatmincellvoltage = 33;
batteryConfig->vbatwarningcellvoltage = 35;
batteryConfig->currentMeterOffset = 0;
batteryConfig->currentMeterScale = 400; // for Allegro ACS758LCB-100U (40mV/A)
batteryConfig->batteryCapacity = 0;
@ -329,6 +334,8 @@ static void resetConf(void)
masterConfig.yaw_control_direction = 1;
masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32;
masterConfig.mag_hardware = MAG_DEFAULT; // default/autodetect
resetBatteryConfig(&masterConfig.batteryConfig);
resetTelemetryConfig(&masterConfig.telemetryConfig);

View file

@ -50,6 +50,8 @@ typedef struct master_t {
gyroConfig_t gyroConfig;
uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
flightDynamicsTrims_t accZero;
flightDynamicsTrims_t magZero;

View file

@ -19,9 +19,6 @@
extern uint16_t acc_1G;
typedef void (*sensorInitFuncPtr)(void); // sensor init prototype
typedef void (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype
typedef struct gyro_s {
sensorInitFuncPtr init; // initialize function
sensorReadFuncPtr read; // read 3 axis data function

View file

@ -23,6 +23,7 @@
#include "system.h"
#include "bus_i2c.h"
#include "sensor.h"
#include "accgyro.h"
#include "accgyro_adxl345.h"

View file

@ -22,6 +22,7 @@
#include "bus_i2c.h"
#include "sensor.h"
#include "accgyro.h"
#include "accgyro_bma280.h"

View file

@ -26,6 +26,7 @@
#include "common/maths.h"
#include "common/axis.h"
#include "sensor.h"
#include "accgyro.h"
#include "accgyro_l3g4200d.h"

View file

@ -26,6 +26,7 @@
#include "gpio.h"
#include "bus_spi.h"
#include "sensor.h"
#include "accgyro.h"
#include "accgyro_l3gd20.h"

View file

@ -27,6 +27,7 @@
#include "gpio.h"
#include "bus_i2c.h"
#include "sensor.h"
#include "accgyro.h"
#include "accgyro_lsm303dlhc.h"

View file

@ -24,6 +24,7 @@
#include "gpio.h"
#include "bus_i2c.h"
#include "sensor.h"
#include "accgyro.h"
#include "accgyro_mma845x.h"

View file

@ -25,6 +25,7 @@
#include "system.h"
#include "bus_i2c.h"
#include "sensor.h"
#include "accgyro.h"
#include "accgyro_mpu3050.h"

View file

@ -27,6 +27,7 @@
#include "gpio.h"
#include "bus_i2c.h"
#include "sensor.h"
#include "accgyro.h"
#include "accgyro_mpu6050.h"

View file

@ -30,10 +30,11 @@
#include "gpio.h"
#include "bus_i2c.h"
#include "sensor.h"
#include "accgyro.h"
#include "accgyro_mpu9150.h"
#define MPU9150_ADDRESS 0xD0
#define MPU9150_ADDRESS 0xD0 // (204) 1101000 // See http://www.invensense.com/mems/gyro/documents/PS-MPU-9150A-00v4_3.pdf, section 6.5.
#define DMP_MEM_START_ADDR 0x6E
#define DMP_MEM_R_W 0x6F

View file

@ -35,6 +35,7 @@
#include "gpio.h"
#include "bus_spi.h"
#include "sensor.h"
#include "accgyro.h"
#include "accgyro_spi_mpu6000.h"

View file

@ -28,6 +28,7 @@
#include "gpio.h"
#include "bus_spi.h"
#include "sensor.h"
#include "accgyro.h"
#include "accgyro_spi_mpu6500.h"

View file

@ -21,8 +21,6 @@
#include "platform.h"
#include "system.h"
#include "accgyro.h"
#include "adc.h"
adc_config_t adcConfig[ADC_CHANNEL_COUNT];

View file

@ -27,6 +27,7 @@
#include "sensors/sensors.h" // FIXME dependency into the main code
#include "sensor.h"
#include "accgyro.h"
#include "adc.h"

View file

@ -24,8 +24,7 @@
#include "gpio.h"
#include "sensors/sensors.h" // FIXME dependency into the main code
#include "sensor.h"
#include "accgyro.h"
#include "adc.h"

View file

@ -0,0 +1,23 @@
/*
* 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
typedef struct mag_s {
sensorInitFuncPtr init; // initialize function
sensorReadFuncPtr read; // read 3 axis data function
} mag_t;

View file

@ -0,0 +1,90 @@
/*
* 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 <stdbool.h>
#include <stdint.h>
#include <math.h>
#include "platform.h"
#include "common/axis.h"
#include "common/maths.h"
#include "system.h"
#include "gpio.h"
#include "bus_i2c.h"
#include "sensors/boardalignment.h"
#include "sensors/sensors.h"
#include "sensor.h"
#include "compass.h"
#include "compass_ak8975.h"
// This sensor is available in MPU-9150.
// AK8975, mag sensor address
#define AK8975_MAG_I2C_ADDRESS 0x0C
#define AK8975_MAG_ID_ADDRESS 0x00
#define AK8975_MAG_DATA_ADDRESS 0x03
#define AK8975_MAG_CONTROL_ADDRESS 0x0A
bool ak8975detect(mag_t *mag)
{
bool ack = false;
uint8_t sig = 0;
uint8_t ackCount = 0;
for (uint8_t address = 0; address < 0xff; address++) {
ack = i2cRead(address, AK8975_MAG_ID_ADDRESS, 1, &sig);
if (ack) {
ackCount++;
}
}
// device ID is in register 0 and is equal to 'H'
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_ID_ADDRESS, 1, &sig);
if (!ack || sig != 'H')
return false;
mag->init = ak8975Init;
mag->read = ak8975Read;
return true;
}
void ak8975Init()
{
i2cWrite(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_CONTROL_ADDRESS, 0x01); // start reading
}
void ak8975Read(int16_t *magData)
{
uint8_t buf[6];
i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_DATA_ADDRESS, 6, buf);
// align sensors to match MPU6050:
// x -> y
// y -> x
// z-> -z
magData[X] = -(int16_t)(buf[3] << 8 | buf[2]) * 4;
magData[Y] = -(int16_t)(buf[1] << 8 | buf[0]) * 4;
magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * 4;
i2cWrite(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_CONTROL_ADDRESS, 0x01); // start reading again
}

View file

@ -0,0 +1,22 @@
/*
* 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
bool ak8975detect(mag_t *mag);
void ak8975Init(void);
void ak8975Read(int16_t *magData);

View file

@ -17,6 +17,7 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <math.h>
@ -30,7 +31,9 @@
#include "bus_i2c.h"
#include "light_led.h"
#include "sensors/boardalignment.h"
#include "sensor.h"
#include "compass.h"
#include "sensors/sensors.h"
#include "compass_hmc5883l.h"
@ -110,19 +113,26 @@
static float magGain[3] = { 1.0f, 1.0f, 1.0f };
bool hmc5883lDetect(void)
static hmc5883Config_t *hmc5883Config = NULL;
bool hmc5883lDetect(mag_t* mag, hmc5883Config_t *hmc5883ConfigToUse)
{
bool ack = false;
uint8_t sig = 0;
hmc5883Config = hmc5883ConfigToUse;
ack = i2cRead(MAG_ADDRESS, 0x0A, 1, &sig);
if (!ack || sig != 'H')
return false;
mag->init = hmc5883lInit;
mag->read = hmc5883lRead;
return true;
}
void hmc5883lInit(hmc5883Config_t *hmc5883Config)
void hmc5883lInit(void)
{
int16_t magADC[3];
int i;

View file

@ -23,6 +23,6 @@ typedef struct hmc5883Config_s {
GPIO_TypeDef *gpioPort;
} hmc5883Config_t;
bool hmc5883lDetect(void);
void hmc5883lInit(hmc5883Config_t *hmc5883Config);
bool hmc5883lDetect(mag_t* mag, hmc5883Config_t *hmc5883ConfigToUse);
void hmc5883lInit(void);
void hmc5883lRead(int16_t *magData);

21
src/main/drivers/sensor.h Normal file
View file

@ -0,0 +1,21 @@
/*
* 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
typedef void (*sensorInitFuncPtr)(void); // sensor init prototype
typedef void (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype

View file

@ -27,6 +27,7 @@
#include "common/maths.h"
#include "common/axis.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "flight/flight.h"

View file

@ -29,9 +29,12 @@
#include "config/runtime_config.h"
#include "rx/rx.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "io/rc_controls.h"
#include "flight/flight.h"
#include "flight/navigation.h"

View file

@ -30,8 +30,12 @@
#include "drivers/system.h"
#include "sensors/sensors.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"

View file

@ -21,6 +21,8 @@
#include "platform.h"
#include "build_config.h"
#include "common/axis.h"
#include "common/maths.h"
@ -62,6 +64,14 @@ static gimbalConfig_t *gimbalConfig;
static motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS];
static MultiType currentMixerConfiguration;
static const motorMixer_t mixerQuadX[] = {
{ 1.0f, -1.0f, 1.0f, -1.0f }, // REAR_R
{ 1.0f, -1.0f, -1.0f, 1.0f }, // FRONT_R
{ 1.0f, 1.0f, 1.0f, 1.0f }, // REAR_L
{ 1.0f, 1.0f, -1.0f, -1.0f }, // FRONT_L
};
#ifndef CJMCU
static const motorMixer_t mixerTri[] = {
{ 1.0f, 0.0f, 1.333333f, 0.0f }, // REAR
{ 1.0f, -1.0f, -0.666667f, 0.0f }, // RIGHT
@ -75,13 +85,6 @@ static const motorMixer_t mixerQuadP[] = {
{ 1.0f, 0.0f, -1.0f, -1.0f }, // FRONT
};
static const motorMixer_t mixerQuadX[] = {
{ 1.0f, -1.0f, 1.0f, -1.0f }, // REAR_R
{ 1.0f, -1.0f, -1.0f, 1.0f }, // FRONT_R
{ 1.0f, 1.0f, 1.0f, 1.0f }, // REAR_L
{ 1.0f, 1.0f, -1.0f, -1.0f }, // FRONT_L
};
static const motorMixer_t mixerBi[] = {
{ 1.0f, 1.0f, 0.0f, 0.0f }, // LEFT
{ 1.0f, -1.0f, 0.0f, 0.0f }, // RIGHT
@ -161,6 +164,13 @@ static const motorMixer_t mixerVtail4[] = {
{ 1.0f, 1.0f, -1.0f, -0.0f }, // FRONT_L
};
static const motorMixer_t mixerAtail4[] = {
{ 1.0f, 0.0f, 1.0f, 1.0f }, // REAR_R
{ 1.0f, -1.0f, -1.0f, 0.0f }, // FRONT_R
{ 1.0f, 0.0f, 1.0f, -1.0f }, // REAR_L
{ 1.0f, 1.0f, -1.0f, -0.0f }, // FRONT_L
};
static const motorMixer_t mixerHex6H[] = {
{ 1.0f, -1.0f, 1.0f, -1.0f }, // REAR_R
{ 1.0f, -1.0f, -1.0f, 1.0f }, // FRONT_R
@ -200,8 +210,10 @@ const mixer_t mixers[] = {
{ 0, 1, NULL }, // * MULTITYPE_PPM_TO_SERVO
{ 2, 1, mixerDualcopter }, // MULTITYPE_DUALCOPTER
{ 1, 1, NULL }, // MULTITYPE_SINGLECOPTER
{ 4, 0, mixerAtail4 }, // MULTITYPE_ATAIL4
{ 0, 0, NULL }, // MULTITYPE_CUSTOM
};
#endif
void mixerUseConfigs(servoParam_t *servoConfToUse, flight3DConfig_t *flight3DConfigToUse, escAndServoConfig_t *escAndServoConfigToUse, mixerConfig_t *mixerConfigToUse, airplaneConfig_t *airplaneConfigToUse, rxConfig_t *rxConfigToUse, gimbalConfig_t *gimbalConfigToUse)
{
@ -245,6 +257,8 @@ int servoDirection(int nr, int lr)
static motorMixer_t *customMixers;
#ifndef CJMCU
void mixerInit(MultiType mixerConfiguration, motorMixer_t *initialCustomMixers)
{
currentMixerConfiguration = mixerConfiguration;
@ -302,6 +316,32 @@ void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfigura
mixerResetMotors();
}
#else
void mixerInit(MultiType mixerConfiguration, motorMixer_t *initialCustomMixers)
{
currentMixerConfiguration = mixerConfiguration;
customMixers = initialCustomMixers;
useServo = false;
}
void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfiguration)
{
UNUSED(pwmOutputConfiguration);
motorCount = 4;
servoCount = 0;
uint8_t i;
for (i = 0; i < motorCount; i++) {
currentMixer[i] = mixerQuadX[i];
}
mixerResetMotors();
}
#endif
void mixerResetMotors(void)
{
@ -311,6 +351,7 @@ void mixerResetMotors(void)
motor_disarmed[i] = feature(FEATURE_3D) ? flight3DConfig->neutral3d : escAndServoConfig->mincommand;
}
#ifndef CJMCU
void mixerLoadMix(int index, motorMixer_t *customMixers)
{
int i;
@ -327,6 +368,7 @@ void mixerLoadMix(int index, motorMixer_t *customMixers)
customMixers[i] = mixers[index].motor[i];
}
}
#endif
static void updateGimbalServos(void)
{

View file

@ -44,8 +44,9 @@ typedef enum MultiType
MULTITYPE_PPM_TO_SERVO = 19, // PPM -> servo relay
MULTITYPE_DUALCOPTER = 20,
MULTITYPE_SINGLECOPTER = 21,
MULTITYPE_CUSTOM = 22, // no current GUI displays this
MULTITYPE_LAST = 23
MULTITYPE_ATAIL4 = 22,
MULTITYPE_CUSTOM = 23,
MULTITYPE_LAST = 24
} MultiType;
// Custom mixer data per motor

View file

@ -24,6 +24,7 @@
#include "drivers/sound_beeper.h"
#include "drivers/system.h"
#include "flight/failsafe.h"
#include "sensors/battery.h"
#include "sensors/sensors.h"
#include "rx/rx.h"
@ -60,7 +61,7 @@ void beepcodeInit(failsafe_t *initialFailsafe)
failsafe = initialFailsafe;
}
void beepcodeUpdateState(bool warn_vbat)
void beepcodeUpdateState(batteryState_e batteryState)
{
static uint8_t beeperOnBox;
#ifdef GPS
@ -117,7 +118,9 @@ void beepcodeUpdateState(bool warn_vbat)
#endif
else if (beeperOnBox == 1)
beep_code('S','S','S','M'); // beeperon
else if (warn_vbat)
else if (batteryState == BATTERY_CRITICAL)
beep_code('S','S','M','D');
else if (batteryState == BATTERY_WARNING)
beep_code('S','M','M','D');
else if (FLIGHT_MODE(AUTOTUNE_MODE))
beep_code('S','M','S','M');

View file

@ -17,5 +17,5 @@
#pragma once
void beepcodeUpdateState(bool warn_vbat);
void beepcodeUpdateState(batteryState_e batteryState);
void queueConfirmationBeep(uint8_t duration);

View file

@ -34,6 +34,9 @@
#include "drivers/system.h"
#include "drivers/display_ug2864hsweg01.h"
#include "drivers/sensor.h"
#include "drivers/compass.h"
#include "sensors/battery.h"
#include "common/axis.h"

View file

@ -570,7 +570,7 @@ void applyLedWarningLayer(uint8_t updateNow)
if (updateNow && warningFlashCounter == 0) {
warningFlags = WARNING_FLAG_NONE;
if (feature(FEATURE_VBAT) && shouldSoundBatteryAlarm()) {
if (feature(FEATURE_VBAT) && calculateBatteryState() != BATTERY_OK) {
warningFlags |= WARNING_FLAG_LOW_BATTERY;
}
if (failsafe->vTable->hasTimerElapsed()) {

View file

@ -31,8 +31,10 @@
#include "flight/flight.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "sensors/battery.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/acceleration.h"
@ -420,16 +422,22 @@ void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustm
void changeControlRateProfile(uint8_t profileIndex);
void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position) {
void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
{
bool applied = false;
queueConfirmationBeep(position + 1);
switch(adjustmentFunction) {
case ADJUSTMENT_RATE_PROFILE:
if (getCurrentControlRateProfile() != position) {
changeControlRateProfile(position);
applied = true;
}
break;
}
if (applied) {
queueConfirmationBeep(position + 1);
}
}
#define RESET_FREQUENCY_2HZ (1000 / 2)

View file

@ -34,7 +34,11 @@
#include "common/typeconversion.h"
#include "drivers/system.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/serial.h"
#include "drivers/bus_i2c.h"
#include "drivers/gpio.h"
@ -57,6 +61,7 @@
#include "sensors/sensors.h"
#include "sensors/acceleration.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/barometer.h"
#include "telemetry/telemetry.h"
@ -87,7 +92,9 @@ static void cliMap(char *cmdline);
static void cliLed(char *cmdline);
static void cliColor(char *cmdline);
#endif
#ifndef CJMCU
static void cliMixer(char *cmdline);
#endif
static void cliMotor(char *cmdline);
static void cliProfile(char *cmdline);
static void cliRateProfile(char *cmdline);
@ -116,7 +123,7 @@ static const char * const mixerNames[] = {
"FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
"AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
"HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
"CUSTOM", NULL
"ATAIL4", "CUSTOM", NULL
};
// sync this with features_e
@ -164,7 +171,9 @@ const clicmd_t cmdTable[] = {
{ "led", "configure leds", cliLed },
#endif
{ "map", "mapping of rc channel order", cliMap },
#ifndef CJMCU
{ "mixer", "mixer name or list", cliMixer },
#endif
{ "motor", "get/set motor output value", cliMotor },
{ "profile", "index (0 to 2)", cliProfile },
{ "rateprofile", "index (0 to 2)", cliRateProfile },
@ -287,6 +296,7 @@ const clivalue_t valueTable[] = {
{ "vbat_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatscale, VBAT_SCALE_MIN, VBAT_SCALE_MAX },
{ "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmaxcellvoltage, 10, 50 },
{ "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, 10, 50 },
{ "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, 10, 50 },
{ "current_meter_scale", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, 1, 10000 },
{ "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, 0, 1650 },
{ "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, 0, 1 },
@ -351,6 +361,7 @@ const clivalue_t valueTable[] = {
{ "baro_cf_vel", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].barometerConfig.baro_cf_vel, 0, 1 },
{ "baro_cf_alt", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].barometerConfig.baro_cf_alt, 0, 1 },
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.mag_hardware, 0, MAG_NONE },
{ "mag_declination", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].mag_declination, -18000, 18000 },
{ "pid_controller", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidController, 0, 2 },
@ -566,6 +577,9 @@ static void cliAdjustmentRange(char *cmdline)
static void cliCMix(char *cmdline)
{
#ifdef CJMCU
UNUSED(cmdline);
#else
int i, check = 0;
int num_motors = 0;
uint8_t len;
@ -652,6 +666,7 @@ static void cliCMix(char *cmdline)
printf("Motor number must be between 1 and %d\r\n", MAX_SUPPORTED_MOTORS);
}
}
#endif
}
#ifdef LED_STRIP
@ -1003,6 +1018,7 @@ static void cliMap(char *cmdline)
printf("%s\r\n", out);
}
#ifndef CJMCU
static void cliMixer(char *cmdline)
{
int i;
@ -1036,6 +1052,7 @@ static void cliMixer(char *cmdline)
}
}
}
#endif
static void cliMotor(char *cmdline)
{

View file

@ -30,7 +30,11 @@
#include "common/maths.h"
#include "drivers/system.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/serial.h"
#include "drivers/bus_i2c.h"
#include "drivers/gpio.h"
@ -206,14 +210,15 @@ const char *boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define MSP_RX_MAP 64 //out message get channel map (also returns number of channels total)
#define MSP_SET_RX_MAP 65 //in message set rx map, numchannels to set comes from MSP_RX_MAP
// DO NOT IMPLEMENT "MSP_CONFIG" and MSP_SET_CONFIG in Cleanflight, isolated commands already exist
//#define MSP_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere
//#define MSP_SET_CONFIG 67 //in message baseflight-specific settings save
// FIXME - Provided for backwards compatibility with configurator code until configurator is updated.
// DEPRECATED - DO NOT USE "MSP_CONFIG" and MSP_SET_CONFIG. In Cleanflight, isolated commands already exist and should be used instead.
#define MSP_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere
#define MSP_SET_CONFIG 67 //in message baseflight-specific settings save
#define MSP_REBOOT 68 //in message reboot settings
// DEPRECATED - Use MSP_API_VERSION instead
//#define MSP_BUILD_INFO 69 //out message build date as well as some space for future expansion
#define MSP_BUILD_INFO 69 //out message build date as well as some space for future expansion
//
// Multwii original MSP commands
@ -901,18 +906,33 @@ static bool processOutCommand(uint8_t cmdMSP)
break;
case MSP_MISC:
headSerialReply(2 * 6 + 4 + 2 + 4);
serialize16(0); // intPowerTrigger1 (aka useless trash)
serialize16(masterConfig.rxConfig.midrc);
serialize16(masterConfig.escAndServoConfig.minthrottle);
serialize16(masterConfig.escAndServoConfig.maxthrottle);
serialize16(masterConfig.escAndServoConfig.mincommand);
serialize16(currentProfile->failsafeConfig.failsafe_throttle);
serialize16(0); // plog useless shit
serialize32(0); // plog useless shit
serialize16(currentProfile->mag_declination / 10); // TODO check this shit
#ifdef GPS
serialize8(masterConfig.gpsConfig.provider); // gps_type
serialize8(0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t
serialize8(masterConfig.gpsConfig.sbasMode); // gps_ubx_sbas
#else
serialize8(0); // gps_type
serialize8(0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t
serialize8(0); // gps_ubx_sbas
#endif
serialize8(masterConfig.batteryConfig.multiwiiCurrentMeterOutput);
serialize8(masterConfig.rxConfig.rssi_channel);
serialize8(0);
serialize16(currentProfile->mag_declination / 10);
serialize8(masterConfig.batteryConfig.vbatscale);
serialize8(masterConfig.batteryConfig.vbatmincellvoltage);
serialize8(masterConfig.batteryConfig.vbatmaxcellvoltage);
serialize8(0);
serialize8(masterConfig.batteryConfig.vbatwarningcellvoltage);
break;
case MSP_MOTOR_PINS:
headSerialReply(8);
@ -1030,6 +1050,22 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize8(masterConfig.rxConfig.rcmap[i]);
break;
case MSP_CONFIG:
headSerialReply(1 + 4 + 1 + 2 + 2 + 2 + 2 + 2);
serialize8(masterConfig.mixerConfiguration);
serialize32(featureMask());
serialize8(masterConfig.rxConfig.serialrx_provider);
serialize16(masterConfig.boardAlignment.rollDegrees);
serialize16(masterConfig.boardAlignment.pitchDegrees);
serialize16(masterConfig.boardAlignment.yawDegrees);
serialize16(masterConfig.batteryConfig.currentMeterScale);
serialize16(masterConfig.batteryConfig.currentMeterOffset);
break;
#ifdef LED_STRIP
case MSP_LED_COLORS:
headSerialReply(CONFIGURABLE_COLOR_COUNT * 4);
@ -1052,6 +1088,13 @@ static bool processOutCommand(uint8_t cmdMSP)
}
break;
#endif
case MSP_BUILD_INFO:
headSerialReply(11 + 4 + 4);
for (i = 0; i < 11; i++)
serialize8(buildDate[i]); // MMM DD YYYY as ascii, MMM = Jan/Feb... etc
serialize32(0); // future exp
serialize32(0); // future exp
break;
default:
return false;
@ -1062,6 +1105,7 @@ static bool processOutCommand(uint8_t cmdMSP)
static bool processInCommand(void)
{
uint32_t i;
uint16_t tmp;
#ifdef GPS
uint8_t wp_no;
int32_t lat = 0, lon = 0, alt = 0;
@ -1165,18 +1209,35 @@ static bool processInCommand(void)
currentControlRateProfile->thrExpo8 = read8();
break;
case MSP_SET_MISC:
read16(); // powerfailmeter
tmp = read16();
if (tmp < 1600 && tmp > 1400)
masterConfig.rxConfig.midrc = tmp;
masterConfig.escAndServoConfig.minthrottle = read16();
masterConfig.escAndServoConfig.maxthrottle = read16();
masterConfig.escAndServoConfig.mincommand = read16();
currentProfile->failsafeConfig.failsafe_throttle = read16();
read16();
read32();
#ifdef GPS
masterConfig.gpsConfig.provider = read8(); // gps_type
read8(); // gps_baudrate
masterConfig.gpsConfig.sbasMode = read8(); // gps_ubx_sbas
#else
read8(); // gps_type
read8(); // gps_baudrate
read8(); // gps_ubx_sbas
#endif
masterConfig.batteryConfig.multiwiiCurrentMeterOutput = read8();
masterConfig.rxConfig.rssi_channel = read8();
read8();
currentProfile->mag_declination = read16() * 10;
masterConfig.batteryConfig.vbatscale = read8(); // actual vbatscale as intended
masterConfig.batteryConfig.vbatmincellvoltage = read8(); // vbatlevel_warn1 in MWC2.3 GUI
masterConfig.batteryConfig.vbatmaxcellvoltage = read8(); // vbatlevel_warn2 in MWC2.3 GUI
read8(); // vbatlevel_crit (unused)
masterConfig.batteryConfig.vbatwarningcellvoltage = read8(); // vbatlevel when buzzer starts to alert
break;
case MSP_SET_MOTOR:
for (i = 0; i < 8; i++) // FIXME should this use MAX_MOTORS or MAX_SUPPORTED_MOTORS instead of 8
@ -1264,31 +1325,26 @@ static bool processInCommand(void)
break;
#endif
case MSP_SET_FEATURE:
headSerialReply(0);
featureClearAll();
featureSet(read32()); // features bitmap
break;
case MSP_SET_BOARD_ALIGNMENT:
headSerialReply(0);
masterConfig.boardAlignment.rollDegrees = read16();
masterConfig.boardAlignment.pitchDegrees = read16();
masterConfig.boardAlignment.yawDegrees = read16();
break;
case MSP_SET_CURRENT_METER_CONFIG:
headSerialReply(0);
masterConfig.batteryConfig.currentMeterScale = read16();
masterConfig.batteryConfig.currentMeterOffset = read16();
break;
case MSP_SET_MIXER:
headSerialReply(0);
masterConfig.mixerConfiguration = read8();
break;
case MSP_SET_RX_CONFIG:
headSerialReply(0);
masterConfig.rxConfig.serialrx_provider = read8();
masterConfig.rxConfig.maxcheck = read16();
masterConfig.rxConfig.midrc = read16();
@ -1297,21 +1353,38 @@ static bool processInCommand(void)
break;
case MSP_SET_RSSI_CONFIG:
headSerialReply(0);
masterConfig.rxConfig.rssi_channel = read8();
break;
case MSP_SET_RX_MAP:
headSerialReply(0);
for (i = 0; i < MAX_MAPPABLE_RX_INPUTS; i++) {
masterConfig.rxConfig.rcmap[i] = read8();
}
break;
case MSP_SET_CONFIG:
#ifdef CJMCU
masterConfig.mixerConfiguration = read8(); // multitype
#else
read8(); // multitype
#endif
featureClearAll();
featureSet(read32()); // features bitmap
masterConfig.rxConfig.serialrx_provider = read8(); // serialrx_type
masterConfig.boardAlignment.rollDegrees = read16(); // board_align_roll
masterConfig.boardAlignment.pitchDegrees = read16(); // board_align_pitch
masterConfig.boardAlignment.yawDegrees = read16(); // board_align_yaw
masterConfig.batteryConfig.currentMeterScale = read16();
masterConfig.batteryConfig.currentMeterOffset = read16();
break;
#ifdef LED_STRIP
case MSP_SET_LED_COLORS:
headSerialReply(0);
for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) {
hsvColor_t *color = &masterConfig.colors[i];
color->h = read16();
@ -1321,7 +1394,6 @@ static bool processInCommand(void)
break;
case MSP_SET_LED_STRIP_CONFIG:
headSerialReply(MAX_LED_STRIP_LENGTH * 6);
for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i];
uint16_t mask;
@ -1342,7 +1414,6 @@ static bool processInCommand(void)
break;
#endif
case MSP_REBOOT:
headSerialReply(0);
isRebootScheduled = true;
break;
@ -1421,6 +1492,10 @@ void mspProcess(void)
mspProcessPort();
if (isRebootScheduled) {
// pause a little while to allow response to be sent
while (!isSerialTransmitBufferEmpty(candidatePort->port)) {
delay(50);
}
systemReset();
}
}

View file

@ -27,6 +27,7 @@
#include "common/atomic.h"
#include "drivers/nvic.h"
#include "drivers/sensor.h"
#include "drivers/system.h"
#include "drivers/gpio.h"
#include "drivers/light_led.h"
@ -36,6 +37,7 @@
#include "drivers/serial_softserial.h"
#include "drivers/serial_uart.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/pwm_mapping.h"
#include "drivers/pwm_rx.h"
#include "drivers/adc.h"
@ -101,7 +103,7 @@ void rxInit(rxConfig_t *rxConfig, failsafe_t *failsafe);
void beepcodeInit(failsafe_t *initialFailsafe);
void gpsInit(serialConfig_t *serialConfig, gpsConfig_t *initialGpsConfig);
void navigationInit(gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile);
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, int16_t magDeclinationFromConfig);
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, int8_t magHardwareToUse, int16_t magDeclinationFromConfig);
void imuInit(void);
void displayInit(rxConfig_t *intialRxConfig);
void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse, failsafe_t* failsafeToUse);
@ -121,7 +123,6 @@ void init(void)
{
uint8_t i;
drv_pwm_config_t pwm_params;
drv_adc_config_t adc_params;
bool sensorsOK = false;
initPrintfSupport();
@ -216,6 +217,8 @@ void init(void)
#endif
#if !defined(SPARKY)
drv_adc_config_t adc_params;
adc_params.enableRSSI = feature(FEATURE_RSSI_ADC);
adc_params.enableCurrentMeter = feature(FEATURE_CURRENT_METER);
adc_params.enableExternal1 = false;
@ -242,7 +245,7 @@ void init(void)
// We have these sensors; SENSORS_SET defined in board.h depending on hardware platform
sensorsSet(SENSORS_SET);
// drop out any sensors that don't seem to work, init all the others. halt if gyro is dead.
sensorsOK = sensorsAutodetect(&masterConfig.sensorAlignmentConfig, masterConfig.gyro_lpf, masterConfig.acc_hardware, currentProfile->mag_declination);
sensorsOK = sensorsAutodetect(&masterConfig.sensorAlignmentConfig, masterConfig.gyro_lpf, masterConfig.acc_hardware, masterConfig.mag_hardware, currentProfile->mag_declination);
// if gyro was not detected due to whatever reason, we give up now.
if (!sensorsOK)

View file

@ -26,7 +26,9 @@
#include "common/axis.h"
#include "common/color.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/light_led.h"
#include "drivers/gpio.h"
@ -162,7 +164,7 @@ void annexCode(void)
int32_t tmp, tmp2;
int32_t axis, prop1 = 0, prop2;
static uint8_t batteryWarningEnabled = false;
static batteryState_e batteryState = BATTERY_OK;
static uint8_t vbatTimer = 0;
static int32_t vbatCycleTime = 0;
@ -232,7 +234,7 @@ void annexCode(void)
if (feature(FEATURE_VBAT)) {
updateBatteryVoltage();
batteryWarningEnabled = shouldSoundBatteryAlarm();
batteryState = calculateBatteryState();
}
if (feature(FEATURE_CURRENT_METER)) {
@ -242,7 +244,7 @@ void annexCode(void)
}
}
beepcodeUpdateState(batteryWarningEnabled);
beepcodeUpdateState(batteryState);
if (ARMING_FLAG(ARMED)) {
LED0_ON;

View file

@ -22,8 +22,12 @@
#include "common/axis.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "flight/flight.h"
#include "sensors/battery.h"
#include "sensors/sensors.h"
#include "io/beeper.h"
#include "sensors/boardalignment.h"

View file

@ -30,7 +30,7 @@ typedef enum AccelSensors {
ACC_MPU9150 = 8,
ACC_FAKE = 9,
ACC_NONE = 10
} AccelSensors;
} accelSensor_e;
extern uint8_t accHardware;
extern sensor_align_e accAlign;

View file

@ -27,7 +27,8 @@
// Battery monitoring stuff
uint8_t batteryCellCount = 3; // cell count
uint16_t batteryWarningVoltage; // annoying beeper after this one, battery ready to be dead
uint16_t batteryWarningVoltage;
uint16_t batteryCriticalVoltage;
uint8_t vbat = 0; // battery voltage in 0.1V steps
@ -62,9 +63,15 @@ void updateBatteryVoltage(void)
vbat = batteryAdcToVoltage(vbatSampleTotal / BATTERY_SAMPLE_COUNT);
}
bool shouldSoundBatteryAlarm(void)
batteryState_e calculateBatteryState(void)
{
return !((vbat > batteryWarningVoltage) || (vbat < batteryConfig->vbatmincellvoltage));
if (vbat <= batteryCriticalVoltage) {
return BATTERY_CRITICAL;
}
if (vbat <= batteryWarningVoltage) {
return BATTERY_WARNING;
}
return BATTERY_OK;
}
void batteryInit(batteryConfig_t *initialBatteryConfig)
@ -85,7 +92,8 @@ void batteryInit(batteryConfig_t *initialBatteryConfig)
}
batteryCellCount = i;
batteryWarningVoltage = batteryCellCount * batteryConfig->vbatmincellvoltage; // 3.3V per cell minimum, configurable in CLI
batteryWarningVoltage = batteryCellCount * batteryConfig->vbatwarningcellvoltage;
batteryCriticalVoltage = batteryCellCount * batteryConfig->vbatmincellvoltage;
}
#define ADCVREF 33L

View file

@ -24,7 +24,8 @@
typedef struct batteryConfig_s {
uint8_t vbatscale; // adjust this to match battery voltage to reported value
uint8_t vbatmaxcellvoltage; // maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, default is 43 (4.3V)
uint8_t vbatmincellvoltage; // minimum voltage per cell, this triggers battery out alarms, in 0.1V units, default is 33 (3.3V)
uint8_t vbatmincellvoltage; // minimum voltage per cell, this triggers battery critical alarm, in 0.1V units, default is 33 (3.3V)
uint8_t vbatwarningcellvoltage; // warning voltage per cell, this triggers battery warning alarm, in 0.1V units, default is 35 (3.5V)
uint16_t currentMeterScale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A
uint16_t currentMeterOffset; // offset of the current sensor in millivolt steps
@ -34,6 +35,12 @@ typedef struct batteryConfig_s {
uint16_t batteryCapacity; // mAh
} batteryConfig_t;
typedef enum {
BATTERY_OK = 0,
BATTERY_WARNING,
BATTERY_CRITICAL
} batteryState_e;
extern uint8_t vbat;
extern uint8_t batteryCellCount;
extern uint16_t batteryWarningVoltage;
@ -41,7 +48,7 @@ extern int32_t amperage;
extern int32_t mAhDrawn;
uint16_t batteryAdcToVoltage(uint16_t src);
bool shouldSoundBatteryAlarm(void);
batteryState_e calculateBatteryState(void);
void updateBatteryVoltage(void);
void batteryInit(batteryConfig_t *initialBatteryConfig);

View file

@ -22,6 +22,8 @@
#include "common/axis.h"
#include "drivers/sensor.h"
#include "drivers/compass.h"
#include "drivers/compass_hmc5883l.h"
#include "drivers/gpio.h"
#include "drivers/light_led.h"
@ -38,6 +40,9 @@
#include "hardware_revision.h"
#endif
mag_t mag; // mag access functions
uint8_t magHardware = MAG_DEFAULT;
extern uint32_t currentTime; // FIXME dependency on global variable, pass it in instead.
int16_t magADC[XYZ_AXIS_COUNT];
@ -49,27 +54,7 @@ void compassInit(void)
{
// initialize and calibration. turn on led during mag calibration (calibration routine blinks it)
LED1_ON;
hmc5883Config_t *hmc5883Config = 0;
#ifdef NAZE
hmc5883Config_t nazeHmc5883Config;
if (hardwareRevision < NAZE32_REV5) {
nazeHmc5883Config.gpioAPB2Peripherals = RCC_APB2Periph_GPIOB;
nazeHmc5883Config.gpioPin = Pin_12;
nazeHmc5883Config.gpioPort = GPIOB;
} else {
nazeHmc5883Config.gpioAPB2Peripherals = RCC_APB2Periph_GPIOC;
nazeHmc5883Config.gpioPin = Pin_14;
nazeHmc5883Config.gpioPort = GPIOC;
}
hmc5883Config = &nazeHmc5883Config;
#endif
hmc5883lInit(hmc5883Config);
mag.init();
LED1_OFF;
magInit = 1;
}
@ -88,7 +73,7 @@ void updateCompass(flightDynamicsTrims_t *magZero)
nextUpdateAt = currentTime + COMPASS_UPDATE_FREQUENCY_10HZ;
hmc5883lRead(magADC);
mag.read(magADC);
alignSensors(magADC, magADC, magAlign);
if (STATE(CALIBRATE_MAG)) {

View file

@ -17,10 +17,21 @@
#pragma once
// Type of accelerometer used/detected
typedef enum MagSensors {
MAG_DEFAULT = 0,
MAG_HMC5883 = 1,
MAG_AK8975 = 2,
MAG_NONE = 3
} magSensor_e;
#ifdef MAG
void compassInit(void);
void updateCompass(flightDynamicsTrims_t *magZero);
#endif
extern int16_t magADC[XYZ_AXIS_COUNT];
extern uint8_t magHardware;
extern sensor_align_e magAlign;
extern mag_t mag;

View file

@ -23,6 +23,7 @@
#include "common/axis.h"
#include "common/maths.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "flight/flight.h"
#include "sensors/sensors.h"

View file

@ -24,8 +24,9 @@
#include "common/axis.h"
#include "drivers/accgyro.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/accgyro_adxl345.h"
#include "drivers/accgyro_bma280.h"
#include "drivers/accgyro_l3g4200d.h"
@ -43,8 +44,13 @@
#include "drivers/barometer.h"
#include "drivers/barometer_bmp085.h"
#include "drivers/barometer_ms5611.h"
#include "drivers/compass.h"
#include "drivers/compass_hmc5883l.h"
#include "drivers/compass_ak8975.h"
#include "drivers/sonar_hcsr04.h"
#include "drivers/gpio.h"
#include "drivers/system.h"
@ -330,7 +336,7 @@ retry:
// Found anything? Check if error or ACC is really missing.
if (accHardware == ACC_DEFAULT) {
if (accHardwareToUse > ACC_DEFAULT) {
if (accHardwareToUse > ACC_DEFAULT && accHardwareToUse < ACC_NONE) {
// Nothing was found and we have a forced sensor that isn't present.
accHardwareToUse = ACC_DEFAULT;
goto retry;
@ -384,6 +390,77 @@ static void detectBaro()
sensorsClear(SENSOR_BARO);
}
static void detectMag(uint8_t magHardwareToUse)
{
#ifdef USE_MAG_HMC5883
static hmc5883Config_t *hmc5883Config = 0;
#ifdef NAZE
hmc5883Config_t nazeHmc5883Config;
if (hardwareRevision < NAZE32_REV5) {
nazeHmc5883Config.gpioAPB2Peripherals = RCC_APB2Periph_GPIOB;
nazeHmc5883Config.gpioPin = Pin_12;
nazeHmc5883Config.gpioPort = GPIOB;
} else {
nazeHmc5883Config.gpioAPB2Peripherals = RCC_APB2Periph_GPIOC;
nazeHmc5883Config.gpioPin = Pin_14;
nazeHmc5883Config.gpioPort = GPIOC;
}
hmc5883Config = &nazeHmc5883Config;
#endif
#endif
retry:
magAlign = ALIGN_DEFAULT;
switch(magHardwareToUse) {
case MAG_NONE: // disable MAG
sensorsClear(SENSOR_MAG);
break;
case MAG_DEFAULT: // autodetect
#ifdef USE_MAG_HMC5883
case MAG_HMC5883:
if (hmc5883lDetect(&mag, hmc5883Config)) {
#ifdef NAZE
magAlign = CW180_DEG;
#endif
magHardware = MAG_HMC5883;
if (magHardwareToUse == MAG_HMC5883)
break;
}
; // fallthrough
#endif
#ifdef USE_MAG_AK8975
case MAG_AK8975:
if (ak8975detect(&mag)) {
magHardware = MAG_AK8975;
if (magHardwareToUse == MAG_AK8975)
break;
}
; // fallthrough
#endif
; // prevent compiler error.
}
if (magHardware == MAG_DEFAULT) {
if (magHardwareToUse > MAG_DEFAULT && magHardwareToUse < MAG_NONE) {
// Nothing was found and we have a forced sensor that isn't present.
magHardwareToUse = MAG_DEFAULT;
goto retry;
} else {
// No MAG was detected
sensorsClear(SENSOR_MAG);
}
}
}
void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
{
if (sensorAlignmentConfig->gyro_align != ALIGN_DEFAULT) {
@ -397,7 +474,7 @@ void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
}
}
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, int16_t magDeclinationFromConfig)
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, uint8_t magHardwareToUse, int16_t magDeclinationFromConfig)
{
int16_t deg, min;
memset(&acc, sizeof(acc), 0);
@ -409,16 +486,7 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t
sensorsSet(SENSOR_GYRO);
detectAcc(accHardwareToUse);
detectBaro();
#ifdef MAG
if (hmc5883lDetect()) {
#ifdef NAZE
magAlign = CW180_DEG;
#endif
} else {
sensorsClear(SENSOR_MAG);
}
#endif
detectMag(magHardwareToUse);
reconfigureAlignment(sensorAlignmentConfig);

View file

@ -43,6 +43,7 @@
#define USE_GYRO_MPU6050
#define MAG
#define USE_MAG_HMC5883
#define BRUSHED_MOTORS

View file

@ -63,6 +63,10 @@
#define USE_BARO_BMP085
#define MAG
#define USE_MAG_HMC5883
#define USE_MAG_AK8975
#define SONAR
#define LED0
#define LED1

View file

@ -25,6 +25,7 @@
#include "drivers/system.h"
#include "drivers/bus_spi.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/accgyro_spi_mpu6500.h"

View file

@ -74,6 +74,8 @@
#define USE_BARO_BMP085
#define MAG
#define USE_MAG_HMC5883
#define SONAR
#define BEEPER
#define LED0

View file

@ -63,6 +63,8 @@
#define USE_BARO_BMP085
#define MAG
#define USE_MAG_HMC5883
#define SONAR
#define USE_USART1

View file

@ -36,6 +36,9 @@
#define BARO
#define USE_BARO_MS5611
#define MAG
#define USE_MAG_AK8975
#define LED0
#define LED1
@ -76,7 +79,7 @@
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
#define SENSORS_SET (SENSOR_ACC)
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
#define SERIAL_RX
#define GPS

View file

@ -31,6 +31,7 @@
#include "common/axis.h"
#include "drivers/system.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"

View file

@ -16,7 +16,9 @@
#include "common/maths.h"
#include "drivers/system.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/serial.h"
#include "drivers/bus_i2c.h"
#include "drivers/gpio.h"

View file

@ -19,7 +19,7 @@
#define FC_VERSION_MINOR 0 // increment when a minor release is made (small new feature, change etc)
#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed
#define MW_VERSION 230
#define MW_VERSION 231
extern char* targetName;