39 #include <px4_platform_common/px4_config.h> 41 #include <sys/types.h> 49 #include <px4_platform_common/getopt.h> 58 #include <board_config.h> 91 int _publish(
struct baro_sensor_data &
data);
103 _baro_topic(nullptr),
104 _baro_orb_class_instance(-1),
120 PX4_ERR(
"MS5611 init fail: %d", ret);
127 PX4_ERR(
"MS5611 start fail: %d", ret);
140 PX4_ERR(
"MS5611 stop fail: %d", ret);
154 baro_report.pressure = data.pressure_pa / 100.0f;
155 baro_report.temperature = data.temperature_c;
156 baro_report.error_count = data.error_counter;
157 baro_report.device_id = m_id.dev_id;
160 if (!(m_pub_blocked)) {
191 if (g_dev ==
nullptr) {
192 PX4_ERR(
"failed instantiating DfMS5611Wrapper object");
196 int ret = g_dev->
start();
199 PX4_ERR(
"DfMS5611Wrapper start failed");
205 DevMgr::getHandle(BARO_DEVICE_PATH, h);
208 DF_LOG_INFO(
"Error: unable to obtain a valid handle for the receiver at: %s (%d)",
209 BARO_DEVICE_PATH, h.getError());
213 DevMgr::releaseHandle(h);
220 if (g_dev ==
nullptr) {
221 PX4_ERR(
"driver not running");
225 int ret = g_dev->
stop();
228 PX4_ERR(
"driver could not be stopped");
243 if (g_dev ==
nullptr) {
244 PX4_ERR(
"driver not running");
248 PX4_DEBUG(
"state @ %p", g_dev);
256 PX4_WARN(
"Usage: df_ms5611_wrapper 'start', 'info', 'stop'");
273 const char *verb = argv[myoptind];
276 if (!strcmp(verb,
"start")) {
280 else if (!strcmp(verb,
"stop")) {
284 else if (!strcmp(verb,
"info")) {
int start()
Start automatic measurement.
int stop()
Stop automatic measurement.
measure the time elapsed performing an event
__EXPORT int df_ms5611_wrapper_main(int argc, char *argv[])
void usage(const char *reason)
Print the correct usage.
perf_counter_t _baro_sample_perf
int _publish(struct baro_sensor_data &data)
void start()
Initialize the automatic measurement state machine and start it.
High-resolution timer with callouts and timekeeping.
int info()
Print a little info about the driver.
#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.
void usage()
Prints info about the driver argument usage.
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.
__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)
void stop()
Stop the automatic measurement state machine.
int start()
Attempt to start driver on all available I2C busses.
int _baro_orb_class_instance
Barometric pressure sensor driver interface.
int stop()
Stop the driver.
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).
Performance measuring tools.