Skip to content
GitLab
Menu
Projects
Groups
Snippets
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
CPS-VO
PX4-Firmware
Commits
401d3567
Commit
401d3567
authored
Aug 23, 2015
by
Lorenz Meier
Browse files
Merge branch 'beta' into stable
parents
b8517eb4
3ccb35f3
Changes
16
Hide whitespace changes
Inline
Side-by-side
ROMFS/px4fmu_common/init.d/rcS
View file @
401d3567
...
@@ -286,6 +286,7 @@ then
...
@@ -286,6 +286,7 @@ then
if [ $HIL == yes ]
if [ $HIL == yes ]
then
then
set OUTPUT_MODE hil
set OUTPUT_MODE hil
set GPS no
if ver hwcmp PX4FMU_V1
if ver hwcmp PX4FMU_V1
then
then
set FMU_MODE serial
set FMU_MODE serial
...
@@ -319,6 +320,7 @@ then
...
@@ -319,6 +320,7 @@ then
gps start
gps start
fi
fi
fi
fi
unset GPS
unset GPS_FAKE
unset GPS_FAKE
# Needs to be this early for in-air-restarts
# Needs to be this early for in-air-restarts
...
...
makefiles/config_px4fmu-v2_default.mk
View file @
401d3567
...
@@ -140,19 +140,19 @@ MODULES += examples/rover_steering_control
...
@@ -140,19 +140,19 @@ MODULES += examples/rover_steering_control
#
#
#MODULES += examples/math_demo
#MODULES += examples/math_demo
# Tutorial code from
# Tutorial code from
# https://p
ixhawk.ethz.ch/px4/dev/hello_sky
# https://p
x4.io/dev/px4_simple_app
#MODULES += examples/px4_simple_app
#MODULES += examples/px4_simple_app
# Tutorial code from
# Tutorial code from
# https://p
ixhawk.ethz.ch/px4
/dev/daemon
# https://p
x4.io
/dev/daemon
#MODULES += examples/px4_daemon_app
#MODULES += examples/px4_daemon_app
# Tutorial code from
# Tutorial code from
# https://p
ixhawk.ethz.ch/px4
/dev/debug_values
# https://p
x4.io
/dev/debug_values
#MODULES += examples/px4_mavlink_debug
#MODULES += examples/px4_mavlink_debug
# Tutorial code from
# Tutorial code from
# https://p
ixhawk.ethz.ch/px4
/dev/example_fixedwing_control
# https://p
x4.io
/dev/example_fixedwing_control
#MODULES += examples/fixedwing_control
#MODULES += examples/fixedwing_control
# Hardware test
# Hardware test
...
...
msg/tecs_status.msg
View file @
401d3567
...
@@ -23,7 +23,7 @@ float32 energyDistributionError
...
@@ -23,7 +23,7 @@ float32 energyDistributionError
float32 totalEnergyRateError
float32 totalEnergyRateError
float32 energyDistributionRateError
float32 energyDistributionRateError
float32 throttle_
sp
float32 throttle_
integ
float32 pitch_
sp
float32 pitch_
integ
uint8 mode
uint8 mode
src/drivers/airspeed/airspeed.cpp
View file @
401d3567
/****************************************************************************
/****************************************************************************
*
*
* Copyright (c) 2013
,
201
4
PX4 Development Team. All rights reserved.
* Copyright (c) 2013
-
201
5
PX4 Development Team. All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* modification, are permitted provided that the following conditions
...
@@ -32,8 +32,9 @@
...
@@ -32,8 +32,9 @@
****************************************************************************/
****************************************************************************/
/**
/**
* @file ets_airspeed.cpp
* @file airspeed.cpp
* @author Simon Wilks
* @author Simon Wilks <simon@px4.io>
* @author Lorenz Meier <lorenz@px4.io>
*
*
* Driver for the Eagle Tree Airspeed V3 connected via I2C.
* Driver for the Eagle Tree Airspeed V3 connected via I2C.
*/
*/
...
@@ -76,7 +77,7 @@
...
@@ -76,7 +77,7 @@
#include <drivers/airspeed/airspeed.h>
#include <drivers/airspeed/airspeed.h>
Airspeed
::
Airspeed
(
int
bus
,
int
address
,
unsigned
conversion_interval
,
const
char
*
path
)
:
Airspeed
::
Airspeed
(
int
bus
,
int
address
,
unsigned
conversion_interval
,
const
char
*
path
)
:
I2C
(
"Airspeed"
,
path
,
bus
,
address
,
100000
),
I2C
(
"Airspeed"
,
path
,
bus
,
address
,
100000
),
_reports
(
nullptr
),
_reports
(
nullptr
),
_buffer_overflows
(
perf_alloc
(
PC_COUNT
,
"airspeed_buffer_overflows"
)),
_buffer_overflows
(
perf_alloc
(
PC_COUNT
,
"airspeed_buffer_overflows"
)),
...
@@ -105,12 +106,14 @@ Airspeed::~Airspeed()
...
@@ -105,12 +106,14 @@ Airspeed::~Airspeed()
/* make sure we are truly inactive */
/* make sure we are truly inactive */
stop
();
stop
();
if
(
_class_instance
!=
-
1
)
if
(
_class_instance
!=
-
1
)
{
unregister_class_devname
(
AIRSPEED_BASE_DEVICE_PATH
,
_class_instance
);
unregister_class_devname
(
AIRSPEED_BASE_DEVICE_PATH
,
_class_instance
);
}
/* free any existing reports */
/* free any existing reports */
if
(
_reports
!=
nullptr
)
if
(
_reports
!=
nullptr
)
{
delete
_reports
;
delete
_reports
;
}
// free perf counters
// free perf counters
perf_free
(
_sample_perf
);
perf_free
(
_sample_perf
);
...
@@ -124,13 +127,16 @@ Airspeed::init()
...
@@ -124,13 +127,16 @@ Airspeed::init()
int
ret
=
ERROR
;
int
ret
=
ERROR
;
/* do I2C init (and probe) first */
/* do I2C init (and probe) first */
if
(
I2C
::
init
()
!=
OK
)
if
(
I2C
::
init
()
!=
OK
)
{
goto
out
;
goto
out
;
}
/* allocate basic report buffers */
/* allocate basic report buffers */
_reports
=
new
RingBuffer
(
2
,
sizeof
(
differential_pressure_s
));
_reports
=
new
RingBuffer
(
2
,
sizeof
(
differential_pressure_s
));
if
(
_reports
==
nullptr
)
if
(
_reports
==
nullptr
)
{
goto
out
;
goto
out
;
}
/* register alternate interfaces if we have to */
/* register alternate interfaces if we have to */
_class_instance
=
register_class_devname
(
AIRSPEED_BASE_DEVICE_PATH
);
_class_instance
=
register_class_devname
(
AIRSPEED_BASE_DEVICE_PATH
);
...
@@ -146,8 +152,9 @@ Airspeed::init()
...
@@ -146,8 +152,9 @@ Airspeed::init()
/* measurement will have generated a report, publish */
/* measurement will have generated a report, publish */
_airspeed_pub
=
orb_advertise
(
ORB_ID
(
differential_pressure
),
&
arp
);
_airspeed_pub
=
orb_advertise
(
ORB_ID
(
differential_pressure
),
&
arp
);
if
(
_airspeed_pub
<
0
)
if
(
_airspeed_pub
<
0
)
{
warnx
(
"uORB started?"
);
warnx
(
"uORB started?"
);
}
}
}
ret
=
OK
;
ret
=
OK
;
...
@@ -166,7 +173,7 @@ Airspeed::probe()
...
@@ -166,7 +173,7 @@ Airspeed::probe()
_retries
=
4
;
_retries
=
4
;
int
ret
=
measure
();
int
ret
=
measure
();
// drop back to 2 retries once initialised
// drop back to 2 retries once initialised
_retries
=
2
;
_retries
=
2
;
return
ret
;
return
ret
;
}
}
...
@@ -179,20 +186,20 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
...
@@ -179,20 +186,20 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
case
SENSORIOCSPOLLRATE
:
{
case
SENSORIOCSPOLLRATE
:
{
switch
(
arg
)
{
switch
(
arg
)
{
/* switching to manual polling */
/* switching to manual polling */
case
SENSOR_POLLRATE_MANUAL
:
case
SENSOR_POLLRATE_MANUAL
:
stop
();
stop
();
_measure_ticks
=
0
;
_measure_ticks
=
0
;
return
OK
;
return
OK
;
/* external signalling (DRDY) not supported */
/* external signalling (DRDY) not supported */
case
SENSOR_POLLRATE_EXTERNAL
:
case
SENSOR_POLLRATE_EXTERNAL
:
/* zero would be bad */
/* zero would be bad */
case
0
:
case
0
:
return
-
EINVAL
;
return
-
EINVAL
;
/* set default/max polling rate */
/* set default/max polling rate */
case
SENSOR_POLLRATE_MAX
:
case
SENSOR_POLLRATE_MAX
:
case
SENSOR_POLLRATE_DEFAULT
:
{
case
SENSOR_POLLRATE_DEFAULT
:
{
/* do we need to start internal polling? */
/* do we need to start internal polling? */
...
@@ -202,13 +209,14 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
...
@@ -202,13 +209,14 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
_measure_ticks
=
USEC2TICK
(
_conversion_interval
);
_measure_ticks
=
USEC2TICK
(
_conversion_interval
);
/* if we need to start the poll state machine, do it */
/* if we need to start the poll state machine, do it */
if
(
want_start
)
if
(
want_start
)
{
start
();
start
();
}
return
OK
;
return
OK
;
}
}
/* adjust to a legal polling interval in Hz */
/* adjust to a legal polling interval in Hz */
default:
{
default:
{
/* do we need to start internal polling? */
/* do we need to start internal polling? */
bool
want_start
=
(
_measure_ticks
==
0
);
bool
want_start
=
(
_measure_ticks
==
0
);
...
@@ -217,15 +225,17 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
...
@@ -217,15 +225,17 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
unsigned
ticks
=
USEC2TICK
(
1000000
/
arg
);
unsigned
ticks
=
USEC2TICK
(
1000000
/
arg
);
/* check against maximum rate */
/* check against maximum rate */
if
(
ticks
<
USEC2TICK
(
_conversion_interval
))
if
(
ticks
<
USEC2TICK
(
_conversion_interval
))
{
return
-
EINVAL
;
return
-
EINVAL
;
}
/* update interval for next measurement */
/* update interval for next measurement */
_measure_ticks
=
ticks
;
_measure_ticks
=
ticks
;
/* if we need to start the poll state machine, do it */
/* if we need to start the poll state machine, do it */
if
(
want_start
)
if
(
want_start
)
{
start
();
start
();
}
return
OK
;
return
OK
;
}
}
...
@@ -233,21 +243,25 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
...
@@ -233,21 +243,25 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
}
}
case
SENSORIOCGPOLLRATE
:
case
SENSORIOCGPOLLRATE
:
if
(
_measure_ticks
==
0
)
if
(
_measure_ticks
==
0
)
{
return
SENSOR_POLLRATE_MANUAL
;
return
SENSOR_POLLRATE_MANUAL
;
}
return
(
1000
/
_measure_ticks
);
return
(
1000
/
_measure_ticks
);
case
SENSORIOCSQUEUEDEPTH
:
{
case
SENSORIOCSQUEUEDEPTH
:
{
/* lower bound is mandatory, upper bound is a sanity check */
/* lower bound is mandatory, upper bound is a sanity check */
if
((
arg
<
1
)
||
(
arg
>
100
))
if
((
arg
<
1
)
||
(
arg
>
100
))
{
return
-
EINVAL
;
return
-
EINVAL
;
}
irqstate_t
flags
=
irqsave
();
irqstate_t
flags
=
irqsave
();
if
(
!
_reports
->
resize
(
arg
))
{
if
(
!
_reports
->
resize
(
arg
))
{
irqrestore
(
flags
);
irqrestore
(
flags
);
return
-
ENOMEM
;
return
-
ENOMEM
;
}
}
irqrestore
(
flags
);
irqrestore
(
flags
);
return
OK
;
return
OK
;
...
@@ -261,16 +275,16 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
...
@@ -261,16 +275,16 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
return
-
EINVAL
;
return
-
EINVAL
;
case
AIRSPEEDIOCSSCALE
:
{
case
AIRSPEEDIOCSSCALE
:
{
struct
airspeed_scale
*
s
=
(
struct
airspeed_scale
*
)
arg
;
struct
airspeed_scale
*
s
=
(
struct
airspeed_scale
*
)
arg
;
_diff_pres_offset
=
s
->
offset_pa
;
_diff_pres_offset
=
s
->
offset_pa
;
return
OK
;
return
OK
;
}
}
case
AIRSPEEDIOCGSCALE
:
{
case
AIRSPEEDIOCGSCALE
:
{
struct
airspeed_scale
*
s
=
(
struct
airspeed_scale
*
)
arg
;
struct
airspeed_scale
*
s
=
(
struct
airspeed_scale
*
)
arg
;
s
->
offset_pa
=
_diff_pres_offset
;
s
->
offset_pa
=
_diff_pres_offset
;
s
->
scale
=
1.0
f
;
s
->
scale
=
1.0
f
;
return
OK
;
return
OK
;
}
}
default:
default:
...
@@ -287,8 +301,9 @@ Airspeed::read(struct file *filp, char *buffer, size_t buflen)
...
@@ -287,8 +301,9 @@ Airspeed::read(struct file *filp, char *buffer, size_t buflen)
int
ret
=
0
;
int
ret
=
0
;
/* buffer must be large enough */
/* buffer must be large enough */
if
(
count
<
1
)
if
(
count
<
1
)
{
return
-
ENOSPC
;
return
-
ENOSPC
;
}
/* if automatic measurement is enabled */
/* if automatic measurement is enabled */
if
(
_measure_ticks
>
0
)
{
if
(
_measure_ticks
>
0
)
{
...
@@ -369,6 +384,7 @@ Airspeed::update_status()
...
@@ -369,6 +384,7 @@ Airspeed::update_status()
if
(
_subsys_pub
>
0
)
{
if
(
_subsys_pub
>
0
)
{
orb_publish
(
ORB_ID
(
subsystem_info
),
_subsys_pub
,
&
info
);
orb_publish
(
ORB_ID
(
subsystem_info
),
_subsys_pub
,
&
info
);
}
else
{
}
else
{
_subsys_pub
=
orb_advertise
(
ORB_ID
(
subsystem_info
),
&
info
);
_subsys_pub
=
orb_advertise
(
ORB_ID
(
subsystem_info
),
&
info
);
}
}
...
@@ -402,6 +418,7 @@ Airspeed::print_info()
...
@@ -402,6 +418,7 @@ Airspeed::print_info()
void
void
Airspeed
::
new_report
(
const
differential_pressure_s
&
report
)
Airspeed
::
new_report
(
const
differential_pressure_s
&
report
)
{
{
if
(
!
_reports
->
force
(
&
report
))
if
(
!
_reports
->
force
(
&
report
))
{
perf_count
(
_buffer_overflows
);
perf_count
(
_buffer_overflows
);
}
}
}
src/drivers/ets_airspeed/ets_airspeed.cpp
View file @
401d3567
...
@@ -94,7 +94,7 @@
...
@@ -94,7 +94,7 @@
class
ETSAirspeed
:
public
Airspeed
class
ETSAirspeed
:
public
Airspeed
{
{
public:
public:
ETSAirspeed
(
int
bus
,
int
address
=
I2C_ADDRESS
,
const
char
*
path
=
ETS_PATH
);
ETSAirspeed
(
int
bus
,
int
address
=
I2C_ADDRESS
,
const
char
*
path
=
ETS_PATH
);
protected:
protected:
...
@@ -113,8 +113,8 @@ protected:
...
@@ -113,8 +113,8 @@ protected:
*/
*/
extern
"C"
__EXPORT
int
ets_airspeed_main
(
int
argc
,
char
*
argv
[]);
extern
"C"
__EXPORT
int
ets_airspeed_main
(
int
argc
,
char
*
argv
[]);
ETSAirspeed
::
ETSAirspeed
(
int
bus
,
int
address
,
const
char
*
path
)
:
Airspeed
(
bus
,
address
,
ETSAirspeed
::
ETSAirspeed
(
int
bus
,
int
address
,
const
char
*
path
)
:
Airspeed
(
bus
,
address
,
CONVERSION_INTERVAL
,
path
)
CONVERSION_INTERVAL
,
path
)
{
{
}
}
...
@@ -155,15 +155,16 @@ ETSAirspeed::collect()
...
@@ -155,15 +155,16 @@ ETSAirspeed::collect()
}
}
uint16_t
diff_pres_pa_raw
=
val
[
1
]
<<
8
|
val
[
0
];
uint16_t
diff_pres_pa_raw
=
val
[
1
]
<<
8
|
val
[
0
];
if
(
diff_pres_pa_raw
==
0
)
{
if
(
diff_pres_pa_raw
==
0
)
{
// a zero value means the pressure sensor cannot give us a
// a zero value means the pressure sensor cannot give us a
// value. We need to return, and not report a value or the
// value. We need to return, and not report a value or the
// caller could end up using this value as part of an
// caller could end up using this value as part of an
// average
// average
perf_count
(
_comms_errors
);
perf_count
(
_comms_errors
);
log
(
"zero value from sensor"
);
log
(
"zero value from sensor"
);
return
-
1
;
return
-
1
;
}
}
// The raw value still should be compensated for the known offset
// The raw value still should be compensated for the known offset
diff_pres_pa_raw
-=
_diff_pres_offset
;
diff_pres_pa_raw
-=
_diff_pres_offset
;
...
@@ -175,7 +176,7 @@ ETSAirspeed::collect()
...
@@ -175,7 +176,7 @@ ETSAirspeed::collect()
differential_pressure_s
report
;
differential_pressure_s
report
;
report
.
timestamp
=
hrt_absolute_time
();
report
.
timestamp
=
hrt_absolute_time
();
report
.
error_count
=
perf_event_count
(
_comms_errors
);
report
.
error_count
=
perf_event_count
(
_comms_errors
);
// XXX we may want to smooth out the readings to remove noise.
// XXX we may want to smooth out the readings to remove noise.
report
.
differential_pressure_filtered_pa
=
diff_pres_pa_raw
;
report
.
differential_pressure_filtered_pa
=
diff_pres_pa_raw
;
...
@@ -210,6 +211,7 @@ ETSAirspeed::cycle()
...
@@ -210,6 +211,7 @@ ETSAirspeed::cycle()
/* perform collection */
/* perform collection */
ret
=
collect
();
ret
=
collect
();
if
(
OK
!=
ret
)
{
if
(
OK
!=
ret
)
{
perf_count
(
_comms_errors
);
perf_count
(
_comms_errors
);
/* restart the measurement state machine */
/* restart the measurement state machine */
...
@@ -239,6 +241,7 @@ ETSAirspeed::cycle()
...
@@ -239,6 +241,7 @@ ETSAirspeed::cycle()
/* measurement phase */
/* measurement phase */
ret
=
measure
();
ret
=
measure
();
if
(
OK
!=
ret
)
{
if
(
OK
!=
ret
)
{
debug
(
"measure error"
);
debug
(
"measure error"
);
}
}
...
@@ -287,26 +290,31 @@ start(int i2c_bus)
...
@@ -287,26 +290,31 @@ start(int i2c_bus)
{
{
int
fd
;
int
fd
;
if
(
g_dev
!=
nullptr
)
if
(
g_dev
!=
nullptr
)
{
errx
(
1
,
"already started"
);
errx
(
1
,
"already started"
);
}
/* create the driver */
/* create the driver */
g_dev
=
new
ETSAirspeed
(
i2c_bus
);
g_dev
=
new
ETSAirspeed
(
i2c_bus
);
if
(
g_dev
==
nullptr
)
if
(
g_dev
==
nullptr
)
{
goto
fail
;
goto
fail
;
}
if
(
OK
!=
g_dev
->
Airspeed
::
init
())
if
(
OK
!=
g_dev
->
Airspeed
::
init
())
{
goto
fail
;
goto
fail
;
}
/* set the poll rate to default, starts automatic data collection */
/* set the poll rate to default, starts automatic data collection */
fd
=
open
(
AIRSPEED0_DEVICE_PATH
,
O_RDONLY
);
fd
=
open
(
AIRSPEED0_DEVICE_PATH
,
O_RDONLY
);
if
(
fd
<
0
)
if
(
fd
<
0
)
{
goto
fail
;
goto
fail
;
}
if
(
ioctl
(
fd
,
SENSORIOCSPOLLRATE
,
SENSOR_POLLRATE_DEFAULT
)
<
0
)
if
(
ioctl
(
fd
,
SENSORIOCSPOLLRATE
,
SENSOR_POLLRATE_DEFAULT
)
<
0
)
{
goto
fail
;
goto
fail
;
}
exit
(
0
);
exit
(
0
);
...
@@ -351,21 +359,24 @@ test()
...
@@ -351,21 +359,24 @@ test()
int
fd
=
open
(
ETS_PATH
,
O_RDONLY
);
int
fd
=
open
(
ETS_PATH
,
O_RDONLY
);
if
(
fd
<
0
)
if
(
fd
<
0
)
{
err
(
1
,
"%s open failed (try 'ets_airspeed start' if the driver is not running"
,
ETS_PATH
);
err
(
1
,
"%s open failed (try 'ets_airspeed start' if the driver is not running"
,
ETS_PATH
);
}
/* do a simple demand read */
/* do a simple demand read */
sz
=
read
(
fd
,
&
report
,
sizeof
(
report
));
sz
=
read
(
fd
,
&
report
,
sizeof
(
report
));
if
(
sz
!=
sizeof
(
report
))
if
(
sz
!=
sizeof
(
report
))
{
err
(
1
,
"immediate read failed"
);
err
(
1
,
"immediate read failed"
);
}
warnx
(
"single read"
);
warnx
(
"single read"
);
warnx
(
"diff pressure: %f pa"
,
(
double
)
report
.
differential_pressure_filtered_pa
);
warnx
(
"diff pressure: %f pa"
,
(
double
)
report
.
differential_pressure_filtered_pa
);
/* start the sensor polling at 2Hz */
/* start the sensor polling at 2Hz */
if
(
OK
!=
ioctl
(
fd
,
SENSORIOCSPOLLRATE
,
2
))
if
(
OK
!=
ioctl
(
fd
,
SENSORIOCSPOLLRATE
,
2
))
{
errx
(
1
,
"failed to set 2Hz poll rate"
);
errx
(
1
,
"failed to set 2Hz poll rate"
);
}
/* read the sensor 5x and report each value */
/* read the sensor 5x and report each value */
for
(
unsigned
i
=
0
;
i
<
5
;
i
++
)
{
for
(
unsigned
i
=
0
;
i
<
5
;
i
++
)
{
...
@@ -376,22 +387,25 @@ test()
...
@@ -376,22 +387,25 @@ test()
fds
.
events
=
POLLIN
;
fds
.
events
=
POLLIN
;
ret
=
poll
(
&
fds
,
1
,
2000
);
ret
=
poll
(
&
fds
,
1
,
2000
);
if
(
ret
!=
1
)
if
(
ret
!=
1
)
{
errx
(
1
,
"timed out waiting for sensor data"
);
errx
(
1
,
"timed out waiting for sensor data"
);
}
/* now go get it */
/* now go get it */
sz
=
read
(
fd
,
&
report
,
sizeof
(
report
));
sz
=
read
(
fd
,
&
report
,
sizeof
(
report
));
if
(
sz
!=
sizeof
(
report
))
if
(
sz
!=
sizeof
(
report
))
{
err
(
1
,
"periodic read failed"
);
err
(
1
,
"periodic read failed"
);
}
warnx
(
"periodic read %u"
,
i
);
warnx
(
"periodic read %u"
,
i
);
warnx
(
"diff pressure: %f pa"
,
(
double
)
report
.
differential_pressure_filtered_pa
);
warnx
(
"diff pressure: %f pa"
,
(
double
)
report
.
differential_pressure_filtered_pa
);
}