Skip to content
Merged
Show file tree
Hide file tree
Changes from 4 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
10 changes: 10 additions & 0 deletions src/drivers/differential_pressure/asp5033/ASP5033.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
*/

#include "ASP5033.hpp"
#include <parameters/param.h>

ASP5033::ASP5033(const I2CSPIDriverConfig &config) :
I2C(config),
Expand Down Expand Up @@ -232,6 +233,15 @@ int ASP5033::collect()
differential_pressure.timestamp_sample = timestamp_sample;
differential_pressure.device_id = get_device_id();
differential_pressure.differential_pressure_pa = _pressure;
int32_t differential_press_inv = 0;
param_get(param_find("SENS_DPRES_INV"), &differential_press_inv);

//If differential pressure invert param set to 1, swap positive and negative
if (differential_press_inv == 1) {
differential_pressure.differential_pressure_pa = -1.0f * _pressure;
}


differential_pressure.temperature = _temperature ;
differential_pressure.error_count = perf_event_count(_comms_errors);
differential_pressure.timestamp = timestamp_sample;
Expand Down
9 changes: 9 additions & 0 deletions src/drivers/differential_pressure/auav/AUAV_Differential.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
****************************************************************************/

#include "AUAV_Differential.hpp"
#include <parameters/param.h>

AUAV_Differential::AUAV_Differential(const I2CSPIDriverConfig &config) :
AUAV(config)
Expand All @@ -46,6 +47,14 @@ void AUAV_Differential::publish_pressure(const float pressure_p, const float tem
differential_pressure.timestamp_sample = timestamp_sample;
differential_pressure.device_id = get_device_id();
differential_pressure.differential_pressure_pa = pressure_p;
int32_t differential_press_inv = 0;
param_get(param_find("SENS_DPRES_INV"), &differential_press_inv);

//If differential pressure invert param set to 1, swap positive and negative
if (differential_press_inv == 1) {
differential_pressure.differential_pressure_pa = -1.0f * pressure_p;
}

differential_pressure.temperature = temperature_c;
differential_pressure.error_count = perf_event_count(_comms_errors);
_differential_pressure_pub.publish(differential_pressure);
Expand Down
9 changes: 9 additions & 0 deletions src/drivers/differential_pressure/ets/ETSAirspeed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
****************************************************************************/

#include "ETSAirspeed.hpp"
#include <parameters/param.h>

ETSAirspeed::ETSAirspeed(const I2CSPIDriverConfig &config) :
I2C(config),
Expand Down Expand Up @@ -113,6 +114,14 @@ int ETSAirspeed::collect()
differential_pressure.timestamp_sample = timestamp_sample;
differential_pressure.device_id = get_device_id();
differential_pressure.differential_pressure_pa = diff_press_pa;
int32_t differential_press_inv = 0;
param_get(param_find("SENS_DPRES_INV"), &differential_press_inv);

//If differential pressure invert param set to 1, swap positive and negative
if (differential_press_inv == 1) {
differential_pressure.differential_pressure_pa = -1.0f * diff_press_pa;
}

differential_pressure.temperature = NAN;
differential_pressure.error_count = perf_event_count(_comms_errors);
differential_pressure.timestamp = hrt_absolute_time();
Expand Down
9 changes: 9 additions & 0 deletions src/drivers/differential_pressure/ms4515/MS4515.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
****************************************************************************/

#include "MS4515.hpp"
#include <parameters/param.h>

MS4515::MS4515(const I2CSPIDriverConfig &config) :
I2C(config),
Expand Down Expand Up @@ -163,6 +164,14 @@ int MS4515::collect()
differential_pressure.timestamp_sample = timestamp_sample;
differential_pressure.device_id = get_device_id();
differential_pressure.differential_pressure_pa = diff_press_pa;
int32_t differential_press_inv = 0;
param_get(param_find("SENS_DPRES_INV"), &differential_press_inv);

//If differential pressure invert param set to 1, swap positive and negative
if (differential_press_inv == 1) {
differential_pressure.differential_pressure_pa = -1.0f * diff_press_pa;
}

differential_pressure.temperature = temperature_c;
differential_pressure.error_count = perf_event_count(_comms_errors);
differential_pressure.timestamp = hrt_absolute_time();
Expand Down
9 changes: 9 additions & 0 deletions src/drivers/differential_pressure/ms4525do/MS4525DO.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
****************************************************************************/

#include "MS4525DO.hpp"
#include <parameters/param.h>

using namespace time_literals;

Expand Down Expand Up @@ -200,6 +201,14 @@ void MS4525DO::RunImpl()
differential_pressure.timestamp_sample = _timestamp_sample;
differential_pressure.device_id = get_device_id();
differential_pressure.differential_pressure_pa = diff_press_pa;
int32_t differential_press_inv = 0;
param_get(param_find("SENS_DPRES_INV"), &differential_press_inv);

//If differential pressure invert param set to 1, swap positive and negative
if (differential_press_inv == 1) {
differential_pressure.differential_pressure_pa = -1.0f * diff_press_pa;
}

differential_pressure.temperature = temperature_c;
differential_pressure.error_count = perf_event_count(_comms_errors);
differential_pressure.timestamp = hrt_absolute_time();
Expand Down
9 changes: 9 additions & 0 deletions src/drivers/differential_pressure/ms5525dso/MS5525DSO.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
****************************************************************************/

#include "MS5525DSO.hpp"
#include <parameters/param.h>

MS5525DSO::MS5525DSO(const I2CSPIDriverConfig &config) :
I2C(config),
Expand Down Expand Up @@ -308,6 +309,14 @@ int MS5525DSO::collect()
differential_pressure.timestamp_sample = timestamp_sample;
differential_pressure.device_id = get_device_id();
differential_pressure.differential_pressure_pa = diff_press_pa;
int32_t differential_press_inv = 0;
param_get(param_find("SENS_DPRES_INV"), &differential_press_inv);

//If differential pressure invert param set to 1, swap positive and negative
if (differential_press_inv == 1) {
differential_pressure.differential_pressure_pa = -1.0f * diff_press_pa;
}

differential_pressure.temperature = temperature_c;
differential_pressure.error_count = perf_event_count(_comms_errors);
differential_pressure.timestamp = hrt_absolute_time();
Expand Down
9 changes: 9 additions & 0 deletions src/drivers/differential_pressure/sdp3x/SDP3X.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
****************************************************************************/

#include "SDP3X.hpp"
#include <parameters/param.h>

using namespace time_literals;

Expand Down Expand Up @@ -187,6 +188,14 @@ int SDP3X::collect()
differential_pressure.timestamp_sample = timestamp_sample;
differential_pressure.device_id = get_device_id();
differential_pressure.differential_pressure_pa = diff_press_pa;
int32_t differential_press_inv = 0;
param_get(param_find("SENS_DPRES_INV"), &differential_press_inv);

//If differential pressure invert param set to 1, swap positive and negative
if (differential_press_inv == 1) {
differential_pressure.differential_pressure_pa = -1.0f * diff_press_pa;
}

differential_pressure.temperature = temperature_c;
differential_pressure.error_count = perf_event_count(_comms_errors);
differential_pressure.timestamp = hrt_absolute_time();
Expand Down
9 changes: 8 additions & 1 deletion src/drivers/uavcan/sensors/differential_pressure.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,8 +69,15 @@ void UavcanDifferentialPressureBridge::air_sub_cb(const

_device_id.devid_s.devtype = DRV_DIFF_PRESS_DEVTYPE_UAVCAN;
_device_id.devid_s.address = msg.getSrcNodeID().get() & 0xFF;

float diff_press_pa = msg.differential_pressure;
int32_t differential_press_inv = 0;
param_get(param_find("SENS_DPRES_INV"), &differential_press_inv);

//If differential pressure invert param set to 1, swap positive and negative
if (differential_press_inv == 1) {
diff_press_pa = -1.0f * msg.differential_pressure;
}

float temperature_c = msg.static_air_temperature + atmosphere::kAbsoluteNullCelsius;

differential_pressure_s report{};
Expand Down
4 changes: 2 additions & 2 deletions src/modules/commander/airspeed_calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,10 +165,10 @@ int do_airspeed_calibration(orb_advert_t *mavlink_log_pub)
break;

} else {
/* do not allow negative values */
/* do not allow negative values if SENS_DPRES_INV not set */
calibration_log_critical(mavlink_log_pub, "[cal] Negative pressure difference detected (%d Pa)",
(int)differential_pressure_pa);
calibration_log_critical(mavlink_log_pub, "[cal] Swap static and dynamic ports!");
calibration_log_critical(mavlink_log_pub, "[cal] Swap static and dynamic ports or set SENS_DPRES_INV to 1");

/* the user setup is wrong, wipe the calibration to force a proper re-calibration */
diff_pres_offset = 0.0f;
Expand Down
13 changes: 13 additions & 0 deletions src/modules/sensors/sensor_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,19 @@ PARAM_DEFINE_FLOAT(CAL_AIR_TUBED_MM, 1.5f);
*/
PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 0.0f);

/**
* Differential pressure sensor invert
*
* Set to 1 to enable inverted values for all differential pressure sensors.
* This should be done if differential pressure sensors have had static and dynamic ports swapped.
* Setting this parameter to 1 makes it difficult to detect pitot-static pressure leaks; only
* set this parameter if static and dynamic tubes are inaccessible.
*
* @category system
* @group Sensor Calibration
*/
PARAM_DEFINE_INT32(SENS_DPRES_INV, 0);

/**
* Differential pressure sensor analog scaling
*
Expand Down
1 change: 1 addition & 0 deletions src/modules/sensors/sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@ Sensors::Sensors(bool hil_enabled) :
#if defined(CONFIG_SENSORS_VEHICLE_AIRSPEED)
/* Differential pressure offset */
_parameter_handles.diff_pres_offset_pa = param_find("SENS_DPRES_OFF");
_parameter_handles.diff_pres_inv = param_find("SENS_DPRES_INV");
#ifdef ADC_AIRSPEED_VOLTAGE_CHANNEL
_parameter_handles.diff_pres_analog_scale = param_find("SENS_DPRES_ANSC");
#endif /* ADC_AIRSPEED_VOLTAGE_CHANNEL */
Expand Down
2 changes: 2 additions & 0 deletions src/modules/sensors/sensors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -198,6 +198,7 @@ class Sensors : public ModuleBase<Sensors>, public ModuleParams, public px4::Sch

struct Parameters {
float diff_pres_offset_pa;
int32_t diff_pres_inv;
#ifdef ADC_AIRSPEED_VOLTAGE_CHANNEL
float diff_pres_analog_scale;
#endif /* ADC_AIRSPEED_VOLTAGE_CHANNEL */
Expand All @@ -209,6 +210,7 @@ class Sensors : public ModuleBase<Sensors>, public ModuleParams, public px4::Sch

struct ParameterHandles {
param_t diff_pres_offset_pa;
param_t diff_pres_inv;
#ifdef ADC_AIRSPEED_VOLTAGE_CHANNEL
param_t diff_pres_analog_scale;
#endif /* ADC_AIRSPEED_VOLTAGE_CHANNEL */
Expand Down
Loading