Moved faked sensors into their own driver files
This commit is contained in:
parent
5411b0489f
commit
4bee6193e8
|
@ -0,0 +1,110 @@
|
||||||
|
/*
|
||||||
|
* 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 "platform.h"
|
||||||
|
|
||||||
|
#include "common/axis.h"
|
||||||
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "accgyro.h"
|
||||||
|
#include "accgyro_fake.h"
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef USE_FAKE_GYRO
|
||||||
|
|
||||||
|
static int16_t fakeGyroADC[XYZ_AXIS_COUNT];
|
||||||
|
|
||||||
|
static void fakeGyroInit(gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
UNUSED(gyro);
|
||||||
|
}
|
||||||
|
|
||||||
|
void fakeGyroSet(int16_t x, int16_t y, int16_t z)
|
||||||
|
{
|
||||||
|
fakeGyroADC[X] = x;
|
||||||
|
fakeGyroADC[Y] = y;
|
||||||
|
fakeGyroADC[Z] = z;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool fakeGyroRead(gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
gyro->gyroADCRaw[X] = fakeGyroADC[X];
|
||||||
|
gyro->gyroADCRaw[Y] = fakeGyroADC[Y];
|
||||||
|
gyro->gyroADCRaw[Z] = fakeGyroADC[Z];
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool fakeGyroReadTemperature(int16_t *tempData)
|
||||||
|
{
|
||||||
|
UNUSED(tempData);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool fakeGyroInitStatus(gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
UNUSED(gyro);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool fakeGyroDetect(gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
gyro->init = fakeGyroInit;
|
||||||
|
gyro->intStatus = fakeGyroInitStatus;
|
||||||
|
gyro->read = fakeGyroRead;
|
||||||
|
gyro->temperature = fakeGyroReadTemperature;
|
||||||
|
gyro->scale = 1.0f;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif // USE_FAKE_GYRO
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef USE_FAKE_ACC
|
||||||
|
|
||||||
|
static int16_t fakeAccData[XYZ_AXIS_COUNT];
|
||||||
|
|
||||||
|
static void fakeAccInit(accDev_t *acc)
|
||||||
|
{
|
||||||
|
UNUSED(acc);
|
||||||
|
}
|
||||||
|
|
||||||
|
void fakeAccSet(int16_t x, int16_t y, int16_t z)
|
||||||
|
{
|
||||||
|
fakeAccData[X] = x;
|
||||||
|
fakeAccData[Y] = y;
|
||||||
|
fakeAccData[Z] = z;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool fakeAccRead(int16_t *accData)
|
||||||
|
{
|
||||||
|
accData[X] = fakeAccData[X];
|
||||||
|
accData[Y] = fakeAccData[Y];
|
||||||
|
accData[Z] = fakeAccData[Z];
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool fakeAccDetect(accDev_t *acc)
|
||||||
|
{
|
||||||
|
acc->init = fakeAccInit;
|
||||||
|
acc->read = fakeAccRead;
|
||||||
|
acc->revisionCode = 0;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif // USE_FAKE_ACC
|
||||||
|
|
|
@ -0,0 +1,26 @@
|
||||||
|
/*
|
||||||
|
* 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
|
||||||
|
|
||||||
|
struct accDev_s;
|
||||||
|
bool fakeAccDetect(struct accDev_s *acc);
|
||||||
|
void fakeAccSet(int16_t x, int16_t y, int16_t z);
|
||||||
|
|
||||||
|
struct gyroDev_s;
|
||||||
|
bool fakeGyroDetect(struct gyroDev_s *gyro);
|
||||||
|
void fakeGyroSet(int16_t x, int16_t y, int16_t z);
|
|
@ -0,0 +1,70 @@
|
||||||
|
/*
|
||||||
|
* 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 <platform.h>
|
||||||
|
|
||||||
|
#ifdef USE_FAKE_BARO
|
||||||
|
|
||||||
|
#include "barometer.h"
|
||||||
|
#include "barometer_fake.h"
|
||||||
|
|
||||||
|
|
||||||
|
static int32_t fakePressure;
|
||||||
|
static int32_t fakeTemperature;
|
||||||
|
|
||||||
|
|
||||||
|
static void fakeBaroStartGet(void)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
static void fakeBaroCalculate(int32_t *pressure, int32_t *temperature)
|
||||||
|
{
|
||||||
|
if (pressure)
|
||||||
|
*pressure = fakePressure;
|
||||||
|
if (temperature)
|
||||||
|
*temperature = fakeTemperature;
|
||||||
|
}
|
||||||
|
|
||||||
|
void fakeBaroSet(int32_t pressure, int32_t temperature)
|
||||||
|
{
|
||||||
|
fakePressure = pressure;
|
||||||
|
fakeTemperature = temperature;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool fakeBaroDetect(baroDev_t *baro)
|
||||||
|
{
|
||||||
|
fakePressure = 101325; // pressure in Pa (0m MSL)
|
||||||
|
fakeTemperature = 2500; // temperature in 0.01 C = 25 deg
|
||||||
|
|
||||||
|
// these are dummy as temperature is measured as part of pressure
|
||||||
|
baro->ut_delay = 10000;
|
||||||
|
baro->get_ut = fakeBaroStartGet;
|
||||||
|
baro->start_ut = fakeBaroStartGet;
|
||||||
|
|
||||||
|
// only _up part is executed, and gets both temperature and pressure
|
||||||
|
baro->up_delay = 10000;
|
||||||
|
baro->start_up = fakeBaroStartGet;
|
||||||
|
baro->get_up = fakeBaroStartGet;
|
||||||
|
baro->calculate = fakeBaroCalculate;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif // USE_FAKE_BARO
|
||||||
|
|
|
@ -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
|
||||||
|
|
||||||
|
struct baroDev_s;
|
||||||
|
bool fakeBaroDetect(struct baroDev_s *baro);
|
||||||
|
void fakeBaroSet(int32_t pressure, int32_t temperature);
|
||||||
|
|
|
@ -0,0 +1,66 @@
|
||||||
|
/*
|
||||||
|
* 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 "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_FAKE_MAG
|
||||||
|
|
||||||
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
#include "common/axis.h"
|
||||||
|
|
||||||
|
#include "compass.h"
|
||||||
|
#include "compass_fake.h"
|
||||||
|
|
||||||
|
|
||||||
|
static int16_t fakeMagData[XYZ_AXIS_COUNT];
|
||||||
|
|
||||||
|
static bool fakeMagInit(void)
|
||||||
|
{
|
||||||
|
// initially point north
|
||||||
|
fakeMagData[X] = 4096;
|
||||||
|
fakeMagData[Y] = 0;
|
||||||
|
fakeMagData[Z] = 0;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void fakeMagSet(int16_t x, int16_t y, int16_t z)
|
||||||
|
{
|
||||||
|
fakeMagData[X] = x;
|
||||||
|
fakeMagData[Y] = y;
|
||||||
|
fakeMagData[Z] = z;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool fakeMagRead(int16_t *magData)
|
||||||
|
{
|
||||||
|
magData[X] = fakeMagData[X];
|
||||||
|
magData[Y] = fakeMagData[Y];
|
||||||
|
magData[Z] = fakeMagData[Z];
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool fakeMagDetect(magDev_t *mag)
|
||||||
|
{
|
||||||
|
mag->init = fakeMagInit;
|
||||||
|
mag->read = fakeMagRead;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif // USE_FAKE_MAG
|
||||||
|
|
|
@ -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
|
||||||
|
|
||||||
|
struct magDev_s;
|
||||||
|
bool fakeMagDetect(struct magDev_s *mag);
|
||||||
|
void fakeMagSet(int16_t x, int16_t y, int16_t z);
|
|
@ -35,6 +35,7 @@
|
||||||
#include "drivers/accgyro.h"
|
#include "drivers/accgyro.h"
|
||||||
#include "drivers/accgyro_adxl345.h"
|
#include "drivers/accgyro_adxl345.h"
|
||||||
#include "drivers/accgyro_bma280.h"
|
#include "drivers/accgyro_bma280.h"
|
||||||
|
#include "drivers/accgyro_fake.h"
|
||||||
#include "drivers/accgyro_l3g4200d.h"
|
#include "drivers/accgyro_l3g4200d.h"
|
||||||
#include "drivers/accgyro_mma845x.h"
|
#include "drivers/accgyro_mma845x.h"
|
||||||
#include "drivers/accgyro_mpu.h"
|
#include "drivers/accgyro_mpu.h"
|
||||||
|
@ -54,12 +55,14 @@
|
||||||
#include "drivers/barometer.h"
|
#include "drivers/barometer.h"
|
||||||
#include "drivers/barometer_bmp085.h"
|
#include "drivers/barometer_bmp085.h"
|
||||||
#include "drivers/barometer_bmp280.h"
|
#include "drivers/barometer_bmp280.h"
|
||||||
|
#include "drivers/barometer_fake.h"
|
||||||
#include "drivers/barometer_ms5611.h"
|
#include "drivers/barometer_ms5611.h"
|
||||||
|
|
||||||
#include "drivers/compass.h"
|
#include "drivers/compass.h"
|
||||||
#include "drivers/compass_hmc5883l.h"
|
|
||||||
#include "drivers/compass_ak8975.h"
|
#include "drivers/compass_ak8975.h"
|
||||||
#include "drivers/compass_ak8963.h"
|
#include "drivers/compass_ak8963.h"
|
||||||
|
#include "drivers/compass_fake.h"
|
||||||
|
#include "drivers/compass_hmc5883l.h"
|
||||||
|
|
||||||
#include "drivers/sonar_hcsr04.h"
|
#include "drivers/sonar_hcsr04.h"
|
||||||
|
|
||||||
|
@ -94,69 +97,6 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_FAKE_GYRO
|
|
||||||
int16_t fake_gyro_values[XYZ_AXIS_COUNT] = { 0,0,0 };
|
|
||||||
static void fakeGyroInit(gyroDev_t *gyro)
|
|
||||||
{
|
|
||||||
UNUSED(gyro);
|
|
||||||
}
|
|
||||||
|
|
||||||
static bool fakeGyroRead(gyroDev_t *gyro)
|
|
||||||
{
|
|
||||||
for (int i = 0; i < XYZ_AXIS_COUNT; ++i) {
|
|
||||||
gyro->gyroADCRaw[X] = fake_gyro_values[i];
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
static bool fakeGyroReadTemp(int16_t *tempData)
|
|
||||||
{
|
|
||||||
UNUSED(tempData);
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
static bool fakeGyroInitStatus(gyroDev_t *gyro)
|
|
||||||
{
|
|
||||||
UNUSED(gyro);
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool fakeGyroDetect(gyroDev_t *gyro)
|
|
||||||
{
|
|
||||||
gyro->init = fakeGyroInit;
|
|
||||||
gyro->intStatus = fakeGyroInitStatus;
|
|
||||||
gyro->read = fakeGyroRead;
|
|
||||||
gyro->temperature = fakeGyroReadTemp;
|
|
||||||
gyro->scale = 1.0f / 16.4f;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_FAKE_ACC
|
|
||||||
int16_t fake_acc_values[XYZ_AXIS_COUNT] = {0,0,0};
|
|
||||||
|
|
||||||
static void fakeAccInit(accDev_t *acc) {UNUSED(acc);}
|
|
||||||
|
|
||||||
static bool fakeAccRead(int16_t *accData) {
|
|
||||||
for(int i=0;i<XYZ_AXIS_COUNT;++i) {
|
|
||||||
accData[i] = fake_acc_values[i];
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool fakeAccDetect(accDev_t *acc)
|
|
||||||
{
|
|
||||||
acc->init = fakeAccInit;
|
|
||||||
acc->read = fakeAccRead;
|
|
||||||
acc->acc_1G = 512*8;
|
|
||||||
acc->revisionCode = 0;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
bool gyroDetect(gyroDev_t *dev)
|
bool gyroDetect(gyroDev_t *dev)
|
||||||
{
|
{
|
||||||
gyroSensor_e gyroHardware = GYRO_DEFAULT;
|
gyroSensor_e gyroHardware = GYRO_DEFAULT;
|
||||||
|
|
|
@ -7,8 +7,8 @@ TARGET_SRC = \
|
||||||
drivers/accgyro_l3gd20.c \
|
drivers/accgyro_l3gd20.c \
|
||||||
drivers/accgyro_l3g4200d.c \
|
drivers/accgyro_l3g4200d.c \
|
||||||
drivers/accgyro_lsm303dlhc.c \
|
drivers/accgyro_lsm303dlhc.c \
|
||||||
drivers/compass_hmc5883l.c \
|
|
||||||
drivers/accgyro_adxl345.c \
|
drivers/accgyro_adxl345.c \
|
||||||
|
drivers/accgyro_fake.c \
|
||||||
drivers/accgyro_bma280.c \
|
drivers/accgyro_bma280.c \
|
||||||
drivers/accgyro_mma845x.c \
|
drivers/accgyro_mma845x.c \
|
||||||
drivers/accgyro_mpu.c \
|
drivers/accgyro_mpu.c \
|
||||||
|
@ -20,9 +20,11 @@ TARGET_SRC = \
|
||||||
drivers/accgyro_spi_mpu9250.c \
|
drivers/accgyro_spi_mpu9250.c \
|
||||||
drivers/barometer_bmp085.c \
|
drivers/barometer_bmp085.c \
|
||||||
drivers/barometer_bmp280.c \
|
drivers/barometer_bmp280.c \
|
||||||
|
drivers/barometer_fake.c \
|
||||||
drivers/barometer_ms5611.c \
|
drivers/barometer_ms5611.c \
|
||||||
drivers/compass_ak8963.c \
|
drivers/compass_ak8963.c \
|
||||||
drivers/compass_ak8975.c \
|
drivers/compass_ak8975.c \
|
||||||
|
drivers/compass_fake.c \
|
||||||
drivers/compass_hmc5883l.c \
|
drivers/compass_hmc5883l.c \
|
||||||
drivers/flash_m25p16.c \
|
drivers/flash_m25p16.c \
|
||||||
drivers/max7456.c
|
drivers/max7456.c
|
||||||
|
|
Loading…
Reference in New Issue