41 #include <px4_platform_common/px4_config.h> 43 #include <sys/types.h> 51 #include <px4_platform_common/getopt.h> 60 #include <board_config.h> 94 int _publish(
struct baro_sensor_data &
data);
106 _baro_topic(nullptr),
107 _baro_orb_class_instance(-1),
123 PX4_ERR(
"BMP280 init fail: %d", ret);
130 PX4_ERR(
"BMP280 start fail: %d", ret);
134 #if defined(__DF_BBBLUE) 135 PX4_INFO(
"BMP280 started");
147 PX4_ERR(
"BMP280 stop fail: %d", ret);
162 baro_report.
pressure = data.pressure_pa / 100.0f;
166 if (!(m_pub_blocked)) {
197 if (g_dev ==
nullptr) {
198 PX4_ERR(
"failed instantiating DfBmp280Wrapper object");
202 int ret = g_dev->
start();
205 PX4_ERR(
"DfBmp280Wrapper start failed");
211 DevMgr::getHandle(BARO_DEVICE_PATH, h);
214 DF_LOG_INFO(
"Error: unable to obtain a valid handle for the receiver at: %s (%d)",
215 BARO_DEVICE_PATH, h.getError());
219 DevMgr::releaseHandle(h);
226 if (g_dev ==
nullptr) {
227 PX4_ERR(
"driver not running");
231 int ret = g_dev->
stop();
234 PX4_ERR(
"driver could not be stopped");
249 if (g_dev ==
nullptr) {
250 PX4_ERR(
"driver not running");
254 PX4_DEBUG(
"state @ %p", g_dev);
262 PX4_WARN(
"Usage: df_bmp280_wrapper 'start', 'info', 'stop'");
279 const char *verb = argv[myoptind];
282 if (!strcmp(verb,
"start")) {
286 else if (!strcmp(verb,
"stop")) {
290 else if (!strcmp(verb,
"info")) {
measure the time elapsed performing an event
void usage(const char *reason)
Print the correct usage.
int _publish(struct baro_sensor_data &data)
High-resolution timer with callouts and timekeeping.
void usage()
Prints info about the driver argument usage.
__EXPORT int df_bmp280_wrapper_main(int argc, char *argv[])
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
void perf_free(perf_counter_t handle)
Free a counter.
int start()
Start automatic measurement.
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
void perf_end(perf_counter_t handle)
End a performance event.
int _baro_orb_class_instance
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
int info()
Print a little info about the driver.
int stop()
Stop the driver.
int stop()
Stop automatic measurement.
int start()
Attempt to start driver on all available I2C busses.
Barometric pressure sensor driver interface.
orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, int priority)
void perf_begin(perf_counter_t handle)
Begin a performance event.
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
perf_counter_t _baro_sample_perf
Performance measuring tools.