Skip to content

Commit

Permalink
[MSP SENSOR] Apply default rotation inside of the compass MSP driver;…
Browse files Browse the repository at this point in the history
… Disable baro median filtering by default; Skip autodetection of MSP-based sensors (only manual selection is allowed)
  • Loading branch information
digitalentity committed Sep 8, 2020
1 parent 2fcc369 commit eab0ecd
Show file tree
Hide file tree
Showing 5 changed files with 30 additions and 17 deletions.
2 changes: 1 addition & 1 deletion src/main/drivers/barometer/barometer_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#if defined(USE_BARO_MSP)

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

#include "common/utils.h"
#include "common/time.h"
Expand Down Expand Up @@ -75,7 +76,6 @@ void mspBaroReceiveNewData(uint8_t * bufferPtr)

mspBaroPressure = pkt->pressurePa;
mspBaroTemperature = pkt->temp;

mspBaroLastUpdateMs = millis();
}

Expand Down
6 changes: 5 additions & 1 deletion src/main/drivers/compass/compass_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,13 @@
#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 int16_t mspMagData[XYZ_AXIS_COUNT];
static int32_t mspMagData[XYZ_AXIS_COUNT];
static timeMs_t mspMagLastUpdateMs;

static bool mspMagInit(magDev_t *magDev)
Expand All @@ -64,6 +66,8 @@ void mspMagReceiveNewData(uint8_t * bufferPtr)
mspMagData[Y] = pkt->magY;
mspMagData[Z] = pkt->magZ;

applySensorAlignment(mspMagData, mspMagData, CW90_DEG_FLIP);

mspMagLastUpdateMs = millis();
}

Expand Down
27 changes: 17 additions & 10 deletions src/main/io/gps_msp.c
Original file line number Diff line number Diff line change
@@ -1,18 +1,25 @@
/*
* This file is part of Cleanflight.
* This file is part of INAV Project.
*
* 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.
* 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/.
*
* 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.
* 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see http://www.gnu.org/licenses/.
*/

#include <stdbool.h>
Expand Down
9 changes: 5 additions & 4 deletions src/main/sensors/barometer.c
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@

baro_t baro; // barometer access functions

PG_REGISTER_WITH_RESET_TEMPLATE(barometerConfig_t, barometerConfig, PG_BAROMETER_CONFIG, 1);
PG_REGISTER_WITH_RESET_TEMPLATE(barometerConfig_t, barometerConfig, PG_BAROMETER_CONFIG, 2);

#ifdef USE_BARO
#define BARO_HARDWARE_DEFAULT BARO_AUTODETECT
Expand All @@ -65,7 +65,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(barometerConfig_t, barometerConfig, PG_BAROMETER
#endif
PG_RESET_TEMPLATE(barometerConfig_t, barometerConfig,
.baro_hardware = BARO_HARDWARE_DEFAULT,
.use_median_filtering = 1,
.use_median_filtering = 0,
.baro_calibration_tolerance = 150
);

Expand Down Expand Up @@ -190,7 +190,8 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)

case BARO_MSP:
#ifdef USE_BARO_MSP
if (mspBaroDetect(dev)) {
// Skip autodetection for MSP baro, only allow manual config
if (baroHardwareToUse != BARO_AUTODETECT && mspBaroDetect(dev)) {
baroHardware = BARO_MSP;
break;
}
Expand Down Expand Up @@ -364,7 +365,7 @@ int32_t baroCalculateAltitude(void)
#endif
// calculates height from ground via baro readings
baro.BaroAlt = pressureToAltitude(baro.baroPressure) - baroGroundAltitude;
}
}

return baro.BaroAlt;
}
Expand Down
3 changes: 2 additions & 1 deletion src/main/sensors/compass.c
Original file line number Diff line number Diff line change
Expand Up @@ -252,7 +252,8 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)

case MAG_MSP:
#ifdef USE_MAG_MSP
if (mspMagDetect(dev)) {
// Skip autodetection for MSP mag
if (magHardwareToUse != MAG_AUTODETECT && mspMagDetect(dev)) {
magHardware = MAG_MSP;
break;
}
Expand Down

0 comments on commit eab0ecd

Please sign in to comment.