Skip to content

Commit 15f6e2e

Browse files
author
henrykotze
committed
windsensor driver: ft_technologies_serial
copied paste along with formatting change Some cleanup of driver Some formatting and more debugging info
1 parent 1592aed commit 15f6e2e

11 files changed

+808
-0
lines changed

msg/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -182,6 +182,7 @@ set(msg_files
182182
SensorsStatus.msg
183183
SensorsStatusImu.msg
184184
SensorUwb.msg
185+
SensorWind.msg
185186
SystemPower.msg
186187
TakeoffStatus.msg
187188
TaskStackInfo.msg

msg/SensorWind.msg

+9
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
# GPS position in WGS84 coordinates.
2+
# the field 'timestamp' is for the position & velocity (microseconds)
3+
uint64 timestamp # time since system start (microseconds)
4+
5+
uint32 device_id # unique device ID for the sensor that does not change between power cycles
6+
7+
float32 wind_speed
8+
float32 wind_direction
9+
uint8 status
+34
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
############################################################################
2+
#
3+
# Copyright (c) 2017 PX4 Development Team. All rights reserved.
4+
#
5+
# Redistribution and use in source and binary forms, with or without
6+
# modification, are permitted provided that the following conditions
7+
# are met:
8+
#
9+
# 1. Redistributions of source code must retain the above copyright
10+
# notice, this list of conditions and the following disclaimer.
11+
# 2. Redistributions in binary form must reproduce the above copyright
12+
# notice, this list of conditions and the following disclaimer in
13+
# the documentation and/or other materials provided with the
14+
# distribution.
15+
# 3. Neither the name PX4 nor the names of its contributors may be
16+
# used to endorse or promote products derived from this software
17+
# without specific prior written permission.
18+
#
19+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20+
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21+
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22+
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23+
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24+
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25+
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26+
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27+
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28+
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29+
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30+
# POSSIBILITY OF SUCH DAMAGE.
31+
#
32+
############################################################################
33+
34+
add_subdirectory(ft_technologies)

src/drivers/wind_sensor/Kconfig

+10
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
menu "Wind Sensors"
2+
menuconfig COMMON_WIND_SENSOR
3+
bool "Common wind sensor's"
4+
default n
5+
select DRIVERS_WIND_SENSOR_FT_TECHNOLOGIES
6+
---help---
7+
Enable default set of wind sensor drivers
8+
9+
rsource "*/Kconfig"
10+
endmenu
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,46 @@
1+
############################################################################
2+
#
3+
# Copyright (c) 2023 PX4 Development Team. All rights reserved.
4+
#
5+
# Redistribution and use in source and binary forms, with or without
6+
# modification, are permitted provided that the following conditions
7+
# are met:
8+
#
9+
# 1. Redistributions of source code must retain the above copyright
10+
# notice, this list of conditions and the following disclaimer.
11+
# 2. Redistributions in binary form must reproduce the above copyright
12+
# notice, this list of conditions and the following disclaimer in
13+
# the documentation and/or other materials provided with the
14+
# distribution.
15+
# 3. Neither the name PX4 nor the names of its contributors may be
16+
# used to endorse or promote products derived from this software
17+
# without specific prior written permission.
18+
#
19+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20+
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21+
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22+
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23+
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24+
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25+
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26+
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27+
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28+
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29+
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30+
# POSSIBILITY OF SUCH DAMAGE.
31+
#
32+
############################################################################
33+
px4_add_module(
34+
MODULE drivers__wind_sensor__ft_technologies_serial
35+
MAIN ft_technologies_serial
36+
COMPILE_FLAGS
37+
-Wno-cast-align # TODO: fix and enable
38+
SRCS
39+
ft_technologies_serial.cpp
40+
ft_technologies_serial.hpp
41+
ft_technologies_serial_main.cpp
42+
DEPENDS
43+
px4_work_queue
44+
MODULE_CONFIG
45+
module.yaml
46+
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
menuconfig DRIVERS_WIND_SENSOR_FT_TECHNOLOGIES
2+
bool "ft_technologies"
3+
default n
4+
---help---
5+
Enable support for ft_technologies

0 commit comments

Comments
 (0)