Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 13 additions & 6 deletions src/main/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,8 @@ main_sources(COMMON_SRC
drivers/barometer/barometer_ms56xx.h
drivers/barometer/barometer_spl06.c
drivers/barometer/barometer_spl06.h
drivers/barometer/barometer_msp.c
drivers/barometer/barometer_msp.h

drivers/buf_writer.c
drivers/buf_writer.h
Expand Down Expand Up @@ -148,6 +150,8 @@ main_sources(COMMON_SRC
drivers/compass/compass_mpu9250.h
drivers/compass/compass_qmc5883l.c
drivers/compass/compass_qmc5883l.h
drivers/compass/compass_msp.c
drivers/compass/compass_msp.h

drivers/display.c
drivers/display.h
Expand Down Expand Up @@ -195,12 +199,14 @@ main_sources(COMMON_SRC
drivers/osd.h
drivers/persistent.c
drivers/persistent.h
drivers/pitotmeter_adc.c
drivers/pitotmeter_adc.h
drivers/pitotmeter_ms4525.c
drivers/pitotmeter_ms4525.h
drivers/pitotmeter_virtual.c
drivers/pitotmeter_virtual.h
drivers/pitotmeter/pitotmeter_adc.c
drivers/pitotmeter/pitotmeter_adc.h
drivers/pitotmeter/pitotmeter_ms4525.c
drivers/pitotmeter/pitotmeter_ms4525.h
drivers/pitotmeter/pitotmeter_msp.c
drivers/pitotmeter/pitotmeter_msp.h
drivers/pitotmeter/pitotmeter_virtual.c
drivers/pitotmeter/pitotmeter_virtual.h
drivers/pwm_esc_detect.c
drivers/pwm_esc_detect.h
drivers/pwm_mapping.c
Expand Down Expand Up @@ -499,6 +505,7 @@ main_sources(COMMON_SRC
io/gps_ublox.c
io/gps_nmea.c
io/gps_naza.c
io/gps_msp.c
io/gps_private.h
io/ledstrip.c
io/ledstrip.h
Expand Down
102 changes: 102 additions & 0 deletions src/main/drivers/barometer/barometer_msp.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,102 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute 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.
*
* This file 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 this program. If not, see http://www.gnu.org/licenses/.
*/

#include <stdbool.h>
#include <stdint.h>

#include "platform.h"

#if defined(USE_BARO_MSP)

#include "build/build_config.h"
#include "build/debug.h"

#include "common/utils.h"
#include "common/time.h"

#include "drivers/time.h"
#include "drivers/barometer/barometer.h"
#include "drivers/barometer/barometer_msp.h"

#include "msp/msp_protocol_v2_sensor_msg.h"

#define MSP_BARO_TIMEOUT_MS 250 // Less than 4Hz updates is considered a failure

static int32_t mspBaroPressure;
static int32_t mspBaroTemperature;
static timeMs_t mspBaroLastUpdateMs;

static bool mspBaroStartGet(baroDev_t * baro)
{
UNUSED(baro);
return true;
}

static bool mspBaroCalculate(baroDev_t * baro, int32_t *pressure, int32_t *temperature)
{
UNUSED(baro);

if ((millis() - mspBaroLastUpdateMs) > MSP_BARO_TIMEOUT_MS) {
return false;
}

if (pressure)
*pressure = mspBaroPressure;

if (temperature)
*temperature = mspBaroTemperature;

return true;
}

void mspBaroReceiveNewData(uint8_t * bufferPtr)
{
const mspSensorBaroDataMessage_t * pkt = (const mspSensorBaroDataMessage_t *)bufferPtr;

mspBaroPressure = pkt->pressurePa;
mspBaroTemperature = pkt->temp;
mspBaroLastUpdateMs = millis();
}

bool mspBaroDetect(baroDev_t *baro)
{
mspBaroPressure = 101325; // pressure in Pa (0m MSL)
mspBaroTemperature = 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 = mspBaroStartGet;
baro->start_ut = mspBaroStartGet;

// only _up part is executed, and gets both temperature and pressure
baro->up_delay = 10000;
baro->start_up = mspBaroStartGet;
baro->get_up = mspBaroStartGet;

baro->calculate = mspBaroCalculate;

return true;
}

#endif
29 changes: 29 additions & 0 deletions src/main/drivers/barometer/barometer_msp.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute 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.
*
* This file 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 this program. If not, see http://www.gnu.org/licenses/.
*/

#pragma once

struct baroDev_s;
bool mspBaroDetect(struct baroDev_s *baro);
void mspBaroReceiveNewData(uint8_t * bufferPtr);
96 changes: 96 additions & 0 deletions src/main/drivers/compass/compass_msp.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,96 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute 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.
*
* This file 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 this program. If not, see http://www.gnu.org/licenses/.
*/

#include <stdbool.h>
#include <stdint.h>

#include "platform.h"

#if defined(USE_MAG_MSP)

#include "build/build_config.h"

#include "common/axis.h"
#include "common/utils.h"
#include "common/time.h"

#include "drivers/time.h"
#include "drivers/compass/compass.h"
#include "drivers/compass/compass_msp.h"

#include "sensors/boardalignment.h"

#include "msp/msp_protocol_v2_sensor_msg.h"

#define MSP_MAG_TIMEOUT_MS 250 // Less than 4Hz updates is considered a failure

static int32_t mspMagData[XYZ_AXIS_COUNT];
static timeMs_t mspMagLastUpdateMs;

static bool mspMagInit(magDev_t *magDev)
{
UNUSED(magDev);
mspMagData[X] = 0;
mspMagData[Y] = 0;
mspMagData[Z] = 0;
mspMagLastUpdateMs = 0;
return true;
}

void mspMagReceiveNewData(uint8_t * bufferPtr)
{
const mspSensorCompassDataMessage_t * pkt = (const mspSensorCompassDataMessage_t *)bufferPtr;

mspMagData[X] = pkt->magX;
mspMagData[Y] = pkt->magY;
mspMagData[Z] = pkt->magZ;

applySensorAlignment(mspMagData, mspMagData, CW90_DEG_FLIP);

mspMagLastUpdateMs = millis();
}

static bool mspMagRead(magDev_t *magDev)
{
UNUSED(magDev);

if ((millis() - mspMagLastUpdateMs) > MSP_MAG_TIMEOUT_MS) {
return false;
}

magDev->magADCRaw[X] = mspMagData[X];
magDev->magADCRaw[Y] = mspMagData[Y];
magDev->magADCRaw[Z] = mspMagData[Z];

return true;
}

bool mspMagDetect(magDev_t *mag)
{
mag->init = mspMagInit;
mag->read = mspMagRead;
return true;
}

#endif
28 changes: 28 additions & 0 deletions src/main/drivers/compass/compass_msp.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute 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.
*
* This file 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 this program. If not, see http://www.gnu.org/licenses/.
*/

#pragma once

bool mspMagDetect(struct magDev_s *mag);
void mspMagReceiveNewData(uint8_t * bufferPtr);
File renamed without changes.
6 changes: 3 additions & 3 deletions src/main/drivers/pitotmeter_adc.c → src/main/drivers/pitotmeter/pitotmeter_adc.c
100755 → 100644
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@

#include "common/utils.h"

#include "pitotmeter.h"
#include "pitotmeter_adc.h"
#include "adc.h"
#include "drivers/pitotmeter/pitotmeter.h"
#include "drivers/pitotmeter/pitotmeter_adc.h"
#include "drivers/adc.h"

#if defined(USE_ADC) && defined(USE_PITOT_ADC)

Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@
#include "common/utils.h"
#include "common/maths.h"
#include "drivers/bus_i2c.h"
#include "drivers/pitotmeter.h"
#include "drivers/time.h"
#include "drivers/pitotmeter/pitotmeter.h"

// MS4525, Standard address 0x28
#define MS4525_ADDR 0x28
Expand Down
Loading