From f0cd79953fa396096e1a325524893724084d4c26 Mon Sep 17 00:00:00 2001
From: Daniel Agar <daniel@agar.ca>
Date: Sun, 19 May 2019 10:39:10 -0400
Subject: [PATCH] create PX4Barometer class

---
 src/lib/drivers/barometer/CMakeLists.txt   | 34 +++++++++
 src/lib/drivers/barometer/PX4Barometer.cpp | 89 ++++++++++++++++++++++
 src/lib/drivers/barometer/PX4Barometer.hpp | 64 ++++++++++++++++
 3 files changed, 187 insertions(+)
 create mode 100644 src/lib/drivers/barometer/CMakeLists.txt
 create mode 100644 src/lib/drivers/barometer/PX4Barometer.cpp
 create mode 100644 src/lib/drivers/barometer/PX4Barometer.hpp

diff --git a/src/lib/drivers/barometer/CMakeLists.txt b/src/lib/drivers/barometer/CMakeLists.txt
new file mode 100644
index 0000000000..33c2bbf05a
--- /dev/null
+++ b/src/lib/drivers/barometer/CMakeLists.txt
@@ -0,0 +1,34 @@
+############################################################################
+#
+#   Copyright (c) 2019 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+#    notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+#    notice, this list of conditions and the following disclaimer in
+#    the documentation and/or other materials provided with the
+#    distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+#    used to endorse or promote products derived from this software
+#    without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+px4_add_library(drivers_barometer PX4Barometer.cpp)
diff --git a/src/lib/drivers/barometer/PX4Barometer.cpp b/src/lib/drivers/barometer/PX4Barometer.cpp
new file mode 100644
index 0000000000..599d529382
--- /dev/null
+++ b/src/lib/drivers/barometer/PX4Barometer.cpp
@@ -0,0 +1,89 @@
+/****************************************************************************
+ *
+ *   Copyright (c) 2018 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+
+#include "PX4Barometer.hpp"
+
+#include <lib/drivers/device/Device.hpp>
+
+PX4Barometer::PX4Barometer(uint32_t device_id, uint8_t priority) :
+	CDev(nullptr),
+	_sensor_baro_pub{ORB_ID(sensor_baro), priority}
+{
+	_class_device_instance = register_class_devname(BARO_BASE_DEVICE_PATH);
+
+	_sensor_baro_pub.get().device_id = device_id;
+
+	// force initial publish to allocate uORB buffer
+	// TODO: can be removed once all drivers are in threads
+	_sensor_baro_pub.update();
+}
+
+PX4Barometer::~PX4Barometer()
+{
+	if (_class_device_instance != -1) {
+		unregister_class_devname(BARO_BASE_DEVICE_PATH, _class_device_instance);
+	}
+}
+
+void PX4Barometer::set_device_type(uint8_t devtype)
+{
+	// current DeviceStructure
+	union device::Device::DeviceId device_id;
+	device_id.devid = _sensor_baro_pub.get().device_id;
+
+	// update to new device type
+	device_id.devid_s.devtype = devtype;
+
+	// copy back to report
+	_sensor_baro_pub.get().device_id = device_id.devid;
+}
+
+void PX4Barometer::update(hrt_abstime timestamp, float pressure)
+{
+	sensor_baro_s &report = _sensor_baro_pub.get();
+
+	report.timestamp = timestamp;
+	report.pressure = pressure;
+
+	poll_notify(POLLIN);
+
+	_sensor_baro_pub.update();
+}
+
+void PX4Barometer::print_status()
+{
+	PX4_INFO(BARO_BASE_DEVICE_PATH " device instance: %d", _class_device_instance);
+
+	print_message(_sensor_baro_pub.get());
+}
diff --git a/src/lib/drivers/barometer/PX4Barometer.hpp b/src/lib/drivers/barometer/PX4Barometer.hpp
new file mode 100644
index 0000000000..87d9f10cb3
--- /dev/null
+++ b/src/lib/drivers/barometer/PX4Barometer.hpp
@@ -0,0 +1,64 @@
+/****************************************************************************
+ *
+ *   Copyright (c) 2018 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#include <drivers/drv_baro.h>
+#include <drivers/drv_hrt.h>
+#include <lib/cdev/CDev.hpp>
+#include <lib/conversion/rotation.h>
+#include <uORB/uORB.h>
+#include <uORB/Publication.hpp>
+#include <uORB/topics/sensor_baro.h>
+
+class PX4Barometer : public cdev::CDev
+{
+
+public:
+	PX4Barometer(uint32_t device_id, uint8_t priority);
+	~PX4Barometer() override;
+
+	void set_device_type(uint8_t devtype);
+	void set_error_count(uint64_t error_count) { _sensor_baro_pub.get().error_count = error_count; }
+
+	void set_temperature(float temperature) { _sensor_baro_pub.get().temperature = temperature; }
+
+	void update(hrt_abstime timestamp, float pressure);
+
+	void print_status();
+
+private:
+
+	uORB::Publication<sensor_baro_s>	_sensor_baro_pub;
+
+	int			_class_device_instance{-1};
+
+};
-- 
GitLab