Browse Source

move all distance sensor drivers to the same folder

sbg
Daniel Agar 7 years ago
parent
commit
67f89f51ff
  1. 4
      cmake/configs/nuttx_aerocore2_default.cmake
  2. 2
      cmake/configs/nuttx_aerofc-v1_default.cmake
  3. 10
      cmake/configs/nuttx_auav-x21_default.cmake
  4. 12
      cmake/configs/nuttx_mindpx-v2_default.cmake
  5. 11
      cmake/configs/nuttx_nxphlite-v3_default.cmake
  6. 7
      cmake/configs/nuttx_px4-same70xplained-v1_default.cmake
  7. 21
      cmake/configs/nuttx_px4fmu-v2_default.cmake
  8. 2
      cmake/configs/nuttx_px4fmu-v2_test.cmake
  9. 11
      cmake/configs/nuttx_px4fmu-v3_default.cmake
  10. 10
      cmake/configs/nuttx_px4fmu-v4_default.cmake
  11. 10
      cmake/configs/nuttx_px4fmu-v4pro_default.cmake
  12. 10
      cmake/configs/nuttx_px4fmu-v5_default.cmake
  13. 7
      cmake/configs/nuttx_px4nucleoF767ZI-v1_default.cmake
  14. 2
      cmake/configs/posix_ocpoc_ubuntu.cmake
  15. 2
      cmake/configs/posix_rpi_common.cmake
  16. 7
      cmake/configs/posix_sitl_default.cmake
  17. 43
      src/drivers/distance_sensor/CMakeLists.txt
  18. 4
      src/drivers/distance_sensor/hc_sr04/CMakeLists.txt
  19. 26
      src/drivers/distance_sensor/hc_sr04/hc_sr04.cpp
  20. 0
      src/drivers/distance_sensor/ll40ls/CMakeLists.txt
  21. 0
      src/drivers/distance_sensor/ll40ls/LidarLite.cpp
  22. 0
      src/drivers/distance_sensor/ll40ls/LidarLite.h
  23. 0
      src/drivers/distance_sensor/ll40ls/LidarLiteI2C.cpp
  24. 0
      src/drivers/distance_sensor/ll40ls/LidarLiteI2C.h
  25. 0
      src/drivers/distance_sensor/ll40ls/LidarLitePWM.cpp
  26. 0
      src/drivers/distance_sensor/ll40ls/LidarLitePWM.h
  27. 0
      src/drivers/distance_sensor/ll40ls/ll40ls.cpp
  28. 1
      src/drivers/distance_sensor/mb12xx/CMakeLists.txt
  29. 26
      src/drivers/distance_sensor/mb12xx/mb12xx.cpp
  30. 0
      src/drivers/distance_sensor/sf0x/CMakeLists.txt
  31. 28
      src/drivers/distance_sensor/sf0x/sf0x.cpp
  32. 0
      src/drivers/distance_sensor/sf0x/sf0x_parser.cpp
  33. 0
      src/drivers/distance_sensor/sf0x/sf0x_parser.h
  34. 1
      src/drivers/distance_sensor/sf0x/sf0x_tests/CMakeLists.txt
  35. 3
      src/drivers/distance_sensor/sf0x/sf0x_tests/SF0XTest.cpp
  36. 1
      src/drivers/distance_sensor/sf1xx/CMakeLists.txt
  37. 24
      src/drivers/distance_sensor/sf1xx/sf1xx.cpp
  38. 1
      src/drivers/distance_sensor/srf02/CMakeLists.txt
  39. 26
      src/drivers/distance_sensor/srf02/srf02.cpp
  40. 1
      src/drivers/distance_sensor/srf02_i2c/CMakeLists.txt
  41. 26
      src/drivers/distance_sensor/srf02_i2c/srf02_i2c.cpp
  42. 1
      src/drivers/distance_sensor/teraranger/CMakeLists.txt
  43. 24
      src/drivers/distance_sensor/teraranger/teraranger.cpp
  44. 0
      src/drivers/distance_sensor/tfmini/CMakeLists.txt
  45. 26
      src/drivers/distance_sensor/tfmini/tfmini.cpp
  46. 0
      src/drivers/distance_sensor/tfmini/tfmini_parser.cpp
  47. 0
      src/drivers/distance_sensor/tfmini/tfmini_parser.h
  48. 0
      src/drivers/distance_sensor/ulanding/CMakeLists.txt
  49. 2
      src/drivers/distance_sensor/ulanding/ulanding.cpp

4
cmake/configs/nuttx_aerocore2_default.cmake

@ -17,11 +17,11 @@ set(config_module_list @@ -17,11 +17,11 @@ set(config_module_list
drivers/lsm303d
drivers/l3gd20
drivers/ms5611
drivers/teraranger
drivers/gps
drivers/pwm_out_sim
drivers/airspeed
drivers/differential_pressure
drivers/distance_sensor
#drivers/frsky_telemetry
modules/sensors
#drivers/pwm_input
@ -51,7 +51,7 @@ set(config_module_list @@ -51,7 +51,7 @@ set(config_module_list
#
# Testing
#
#drivers/sf0x/sf0x_tests
#drivers/distance_sensor/sf0x/sf0x_tests
#drivers/test_ppm
#lib/rc/rc_tests
#modules/commander/commander_tests

2
cmake/configs/nuttx_aerofc-v1_default.cmake

@ -18,7 +18,7 @@ set(config_module_list @@ -18,7 +18,7 @@ set(config_module_list
drivers/hmc5883
drivers/gps
drivers/ist8310
drivers/ll40ls
drivers/distance_sensor
drivers/aerofc_adc
modules/sensors

10
cmake/configs/nuttx_auav-x21_default.cmake

@ -20,12 +20,7 @@ set(config_module_list @@ -20,12 +20,7 @@ set(config_module_list
drivers/mpu9250
drivers/hmc5883
drivers/ms5611
drivers/mb12xx
drivers/srf02
drivers/sf0x
drivers/sf1xx
drivers/ll40ls
drivers/teraranger
drivers/distance_sensor
drivers/gps
drivers/pwm_out_sim
drivers/hott
@ -44,7 +39,6 @@ set(config_module_list @@ -44,7 +39,6 @@ set(config_module_list
drivers/camera_trigger
drivers/bst
drivers/lis3mdl
drivers/tfmini
#
# System commands
@ -71,7 +65,7 @@ set(config_module_list @@ -71,7 +65,7 @@ set(config_module_list
#
# Testing
#
drivers/sf0x/sf0x_tests
drivers/distance_sensor/sf0x/sf0x_tests
drivers/test_ppm
#lib/rc/rc_tests
modules/commander/commander_tests

12
cmake/configs/nuttx_mindpx-v2_default.cmake

@ -22,14 +22,7 @@ set(config_module_list @@ -22,14 +22,7 @@ set(config_module_list
drivers/l3gd20
drivers/hmc5883
drivers/ms5611
drivers/mb12xx
drivers/srf02
drivers/srf02_i2c
#drivers/hc_sr04
drivers/sf0x
drivers/sf1xx
drivers/ll40ls
drivers/teraranger
drivers/distance_sensor
drivers/gps
drivers/pwm_out_sim
#drivers/hott
@ -47,7 +40,6 @@ set(config_module_list @@ -47,7 +40,6 @@ set(config_module_list
drivers/pwm_input
drivers/camera_trigger
drivers/bst
drivers/tfmini
#
# System commands
@ -74,7 +66,7 @@ set(config_module_list @@ -74,7 +66,7 @@ set(config_module_list
#
# Tests
#
drivers/sf0x/sf0x_tests
drivers/distance_sensor/sf0x/sf0x_tests
drivers/test_ppm
modules/commander/commander_tests
modules/mc_pos_control/mc_pos_control_tests

11
cmake/configs/nuttx_nxphlite-v3_default.cmake

@ -32,9 +32,7 @@ set(config_module_list @@ -32,9 +32,7 @@ set(config_module_list
drivers/l3gd20
drivers/led
drivers/lis3mdl
drivers/ll40ls
drivers/lsm303d
drivers/mb12xx
drivers/distance_sensor
drivers/mkblctrl
drivers/mpl3115a2
drivers/mpu6000
@ -47,14 +45,9 @@ set(config_module_list @@ -47,14 +45,9 @@ set(config_module_list
drivers/px4fmu
drivers/rgbled
drivers/rgbled_pwm
drivers/sf0x
drivers/sf1xx
drivers/srf02
drivers/tap_esc
drivers/teraranger
drivers/vmount
modules/sensors
drivers/tfmini
#
# System commands
@ -82,7 +75,7 @@ set(config_module_list @@ -82,7 +75,7 @@ set(config_module_list
#
# Testing
#
drivers/sf0x/sf0x_tests
drivers/distance_sensor/sf0x/sf0x_tests
### NOT Portable YET drivers/test_ppm
#lib/rc/rc_tests
modules/commander/commander_tests

7
cmake/configs/nuttx_px4-same70xplained-v1_default.cmake

@ -22,11 +22,7 @@ set(config_module_list @@ -22,11 +22,7 @@ set(config_module_list
drivers/l3gd20
drivers/hmc5883
drivers/ms5611
drivers/mb12xx
drivers/srf02
drivers/sf0x
drivers/ll40ls
drivers/teraranger
drivers/distance_sensor
drivers/gps
#WIP drivers/pwm_out_sim
drivers/hott
@ -44,7 +40,6 @@ set(config_module_list @@ -44,7 +40,6 @@ set(config_module_list
#WIP drivers/camera_trigger
drivers/bst
drivers/lis3mdl
drivers/tfmini
#

21
cmake/configs/nuttx_px4fmu-v2_default.cmake

@ -6,6 +6,9 @@ set(config_module_list @@ -6,6 +6,9 @@ set(config_module_list
#
# Board support modules
#
drivers/differential_pressure
drivers/distance_sensor
#drivers/adis16448
drivers/airspeed
#drivers/blinkm
@ -15,8 +18,7 @@ set(config_module_list @@ -15,8 +18,7 @@ set(config_module_list
#drivers/bst
drivers/camera_trigger
drivers/device
drivers/differential_pressure
drivers/frsky_telemetry
#drivers/frsky_telemetry
drivers/gps
drivers/hmc5883
#drivers/hott
@ -28,7 +30,6 @@ set(config_module_list @@ -28,7 +30,6 @@ set(config_module_list
drivers/l3gd20
drivers/led
drivers/lis3mdl
drivers/ll40ls
drivers/lsm303d
#drivers/mb12xx
#drivers/mkblctrl
@ -43,23 +44,17 @@ set(config_module_list @@ -43,23 +44,17 @@ set(config_module_list
drivers/px4fmu
drivers/px4io
drivers/rgbled
drivers/sf0x
drivers/sf1xx
#drivers/srf02
drivers/stm32
drivers/stm32/adc
drivers/stm32/tone_alarm
#drivers/tap_esc
drivers/teraranger
#drivers/ulanding
drivers/vmount
modules/sensors
#drivers/tfmini
#
# System commands
#
systemcmds/bl_update
#systemcmds/bl_update
#systemcmds/config
#systemcmds/dumpfile
#systemcmds/esc_calib
@ -82,7 +77,7 @@ set(config_module_list @@ -82,7 +77,7 @@ set(config_module_list
#
# Testing
#
#drivers/sf0x/sf0x_tests
#drivers/distance_sensor/sf0x/sf0x_tests
#drivers/test_ppm
#lib/controllib/controllib_test
#lib/rc/rc_tests
@ -119,8 +114,8 @@ set(config_module_list @@ -119,8 +114,8 @@ set(config_module_list
#
modules/fw_att_control
modules/fw_pos_control_l1
modules/gnd_att_control
modules/gnd_pos_control
#modules/gnd_att_control
#modules/gnd_pos_control
modules/mc_att_control
modules/mc_pos_control
modules/vtol_att_control

2
cmake/configs/nuttx_px4fmu-v2_test.cmake

@ -69,7 +69,7 @@ set(config_module_list @@ -69,7 +69,7 @@ set(config_module_list
#
# Testing
#
drivers/sf0x/sf0x_tests
drivers/distance_sensor/sf0x/sf0x_tests
drivers/test_ppm
#lib/rc/rc_tests
modules/commander/commander_tests

11
cmake/configs/nuttx_px4fmu-v3_default.cmake

@ -34,9 +34,8 @@ set(config_module_list @@ -34,9 +34,8 @@ set(config_module_list
drivers/l3gd20
drivers/led
drivers/lis3mdl
drivers/ll40ls
drivers/distance_sensor
drivers/lsm303d
drivers/mb12xx
drivers/mkblctrl
drivers/mpu6000
drivers/mpu9250
@ -49,18 +48,12 @@ set(config_module_list @@ -49,18 +48,12 @@ set(config_module_list
drivers/px4fmu
drivers/px4io
drivers/rgbled
drivers/sf0x
drivers/sf1xx
drivers/srf02
drivers/stm32
drivers/stm32/adc
drivers/stm32/tone_alarm
drivers/tap_esc
drivers/teraranger
drivers/ulanding
drivers/vmount
modules/sensors
drivers/tfmini
#
# System commands
@ -88,7 +81,7 @@ set(config_module_list @@ -88,7 +81,7 @@ set(config_module_list
#
# Testing
#
drivers/sf0x/sf0x_tests
drivers/distance_sensor/sf0x/sf0x_tests
drivers/test_ppm
lib/controllib/controllib_test
#lib/rc/rc_tests

10
cmake/configs/nuttx_px4fmu-v4_default.cmake

@ -29,8 +29,7 @@ set(config_module_list @@ -29,8 +29,7 @@ set(config_module_list
drivers/irlock
drivers/led
drivers/lis3mdl
drivers/ll40ls
drivers/mb12xx
drivers/distance_sensor
drivers/mkblctrl
drivers/mpu6000
drivers/mpu9250
@ -42,17 +41,12 @@ set(config_module_list @@ -42,17 +41,12 @@ set(config_module_list
drivers/px4flow
drivers/px4fmu
drivers/rgbled
drivers/sf0x
drivers/sf1xx
drivers/srf02
drivers/stm32
drivers/stm32/adc
drivers/stm32/tone_alarm
drivers/tap_esc
drivers/teraranger
drivers/vmount
modules/sensors
drivers/tfmini
#
# System commands
@ -79,7 +73,7 @@ set(config_module_list @@ -79,7 +73,7 @@ set(config_module_list
#
# Testing
#
drivers/sf0x/sf0x_tests
drivers/distance_sensor/sf0x/sf0x_tests
drivers/test_ppm
#lib/rc/rc_tests
modules/commander/commander_tests

10
cmake/configs/nuttx_px4fmu-v4pro_default.cmake

@ -27,9 +27,8 @@ set(config_module_list @@ -27,9 +27,8 @@ set(config_module_list
drivers/l3gd20
drivers/led
drivers/lis3mdl
drivers/ll40ls
drivers/distance_sensor
drivers/lsm303d
drivers/mb12xx
drivers/mkblctrl
drivers/mpu6000
drivers/mpu9250
@ -42,17 +41,12 @@ set(config_module_list @@ -42,17 +41,12 @@ set(config_module_list
drivers/px4fmu
drivers/px4io
drivers/rgbled
drivers/sf0x
drivers/sf1xx
drivers/srf02
drivers/stm32
drivers/stm32/adc
drivers/stm32/tone_alarm
drivers/tap_esc
drivers/teraranger
drivers/vmount
modules/sensors
drivers/tfmini
#
# System commands
@ -79,7 +73,7 @@ set(config_module_list @@ -79,7 +73,7 @@ set(config_module_list
#
# Testing
#
drivers/sf0x/sf0x_tests
drivers/distance_sensor/sf0x/sf0x_tests
drivers/test_ppm
#lib/rc/rc_tests
modules/commander/commander_tests

10
cmake/configs/nuttx_px4fmu-v5_default.cmake

@ -28,8 +28,7 @@ set(config_module_list @@ -28,8 +28,7 @@ set(config_module_list
drivers/ist8310
drivers/led
drivers/lis3mdl
drivers/ll40ls
drivers/mb12xx
drivers/distance_sensor
drivers/mkblctrl
drivers/mpu6000
drivers/mpu9250
@ -42,17 +41,12 @@ set(config_module_list @@ -42,17 +41,12 @@ set(config_module_list
drivers/px4fmu
drivers/rgbled
drivers/rgbled_pwm
drivers/sf0x
drivers/sf1xx
drivers/srf02
drivers/stm32
drivers/stm32/adc
drivers/stm32/tone_alarm
drivers/tap_esc
drivers/teraranger
drivers/vmount
modules/sensors
drivers/tfmini
#
# System commands
@ -79,7 +73,7 @@ set(config_module_list @@ -79,7 +73,7 @@ set(config_module_list
#
# Testing
#
drivers/sf0x/sf0x_tests
drivers/distance_sensor/sf0x/sf0x_tests
drivers/test_ppm
#lib/rc/rc_tests
modules/commander/commander_tests

7
cmake/configs/nuttx_px4nucleoF767ZI-v1_default.cmake

@ -24,8 +24,7 @@ set(config_module_list @@ -24,8 +24,7 @@ set(config_module_list
drivers/hott/hott_telemetry
drivers/led
drivers/lis3mdl
drivers/ll40ls
drivers/mb12xx
drivers/distance_sensor
drivers/mkblctrl
drivers/mpu6000
drivers/mpu9250
@ -37,15 +36,11 @@ set(config_module_list @@ -37,15 +36,11 @@ set(config_module_list
drivers/px4flow
drivers/px4fmu
drivers/rgbled
drivers/sf0x
drivers/srf02
drivers/stm32
drivers/stm32/adc
drivers/stm32/tone_alarm
drivers/tap_esc
drivers/teraranger
modules/sensors
drivers/tfmini
#
# System commands

2
cmake/configs/posix_ocpoc_ubuntu.cmake

@ -18,6 +18,7 @@ set(config_module_list @@ -18,6 +18,7 @@ set(config_module_list
# Board support modules
#
drivers/device
drivers/distance_sensor
modules/sensors
platforms/posix/drivers/df_mpu9250_wrapper
platforms/posix/drivers/df_ms5611_wrapper
@ -73,7 +74,6 @@ set(config_module_list @@ -73,7 +74,6 @@ set(config_module_list
drivers/linux_sbus
drivers/linux_pwm_out
drivers/rgbled
drivers/ulanding
#
# Libraries

2
cmake/configs/posix_rpi_common.cmake

@ -17,7 +17,7 @@ set(config_module_list @@ -17,7 +17,7 @@ set(config_module_list
#
drivers/airspeed
drivers/device
drivers/ll40ls
drivers/distance_sensor
drivers/differential_pressure
modules/sensors

7
cmake/configs/posix_sitl_default.cmake

@ -2,14 +2,15 @@ @@ -2,14 +2,15 @@
set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-native.cmake)
set(config_module_list
drivers/differential_pressure
drivers/distance_sensor
drivers/airspeed
drivers/boards
drivers/camera_trigger
drivers/device
drivers/gps
drivers/linux_gpio
drivers/ll40ls
drivers/differential_pressure
drivers/pwm_out_sim
drivers/vmount
@ -47,7 +48,7 @@ set(config_module_list @@ -47,7 +48,7 @@ set(config_module_list
#
# Testing
#
drivers/sf0x/sf0x_tests
drivers/distance_sensor/sf0x/sf0x_tests
#drivers/test_ppm
lib/rc/rc_tests
modules/commander/commander_tests

43
src/drivers/distance_sensor/CMakeLists.txt

@ -0,0 +1,43 @@ @@ -0,0 +1,43 @@
############################################################################
#
# Copyright (c) 2017 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.
#
############################################################################
#add_subdirectory(hc_sr04) # not currently supported
add_subdirectory(ll40ls)
add_subdirectory(mb12xx)
add_subdirectory(sf0x)
add_subdirectory(sf1xx)
add_subdirectory(srf02)
add_subdirectory(srf02_i2c)
add_subdirectory(teraranger)
add_subdirectory(tfmini)
add_subdirectory(ulanding)

4
src/drivers/hc_sr04/CMakeLists.txt → src/drivers/distance_sensor/hc_sr04/CMakeLists.txt

@ -30,6 +30,7 @@ @@ -30,6 +30,7 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__hc_sr04
MAIN hc_sr04
@ -39,5 +40,4 @@ px4_add_module( @@ -39,5 +40,4 @@ px4_add_module(
hc_sr04.cpp
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
)

26
src/drivers/hc_sr04/hc_sr04.cpp → src/drivers/distance_sensor/hc_sr04/hc_sr04.cpp

@ -37,8 +37,8 @@ @@ -37,8 +37,8 @@
* Driver for the hc_sr04 sonar range finders .
*/
#include <nuttx/config.h>
#include <px4_config.h>
#include <px4_workqueue.h>
#include <drivers/device/device.h>
#include <px4_defines.h>
@ -56,10 +56,6 @@ @@ -56,10 +56,6 @@
#include <unistd.h>
#include <vector>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@ -71,10 +67,6 @@ @@ -71,10 +67,6 @@
#include <uORB/topics/subsystem_info.h>
#include <uORB/topics/distance_sensor.h>
#include <board_config.h>
#define SR04_MAX_RANGEFINDERS 6
#define SR04_ID_BASE 0x10
@ -101,8 +93,8 @@ public: @@ -101,8 +93,8 @@ public:
virtual int init();
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
virtual ssize_t read(device::file_t *filp, char *buffer, size_t buflen);
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
/**
* Diagnostics - print some basic information about the driver.
@ -356,7 +348,7 @@ HC_SR04::interrupt(unsigned time) @@ -356,7 +348,7 @@ HC_SR04::interrupt(unsigned time)
}
int
HC_SR04::ioctl(struct file *filp, int cmd, unsigned long arg)
HC_SR04::ioctl(device::file_t *filp, int cmd, unsigned long arg)
{
switch (cmd) {
@ -433,14 +425,14 @@ HC_SR04::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -433,14 +425,14 @@ HC_SR04::ioctl(struct file *filp, int cmd, unsigned long arg)
return -EINVAL;
}
irqstate_t flags = px4_enter_critical_section();
ATOMIC_ENTER;
if (!_reports->resize(arg)) {
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return -ENOMEM;
}
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return OK;
}
@ -456,7 +448,7 @@ HC_SR04::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -456,7 +448,7 @@ HC_SR04::ioctl(struct file *filp, int cmd, unsigned long arg)
}
ssize_t
HC_SR04::read(struct file *filp, char *buffer, size_t buflen)
HC_SR04::read(device::file_t *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct distance_sensor_s);

0
src/drivers/ll40ls/CMakeLists.txt → src/drivers/distance_sensor/ll40ls/CMakeLists.txt

0
src/drivers/ll40ls/LidarLite.cpp → src/drivers/distance_sensor/ll40ls/LidarLite.cpp

0
src/drivers/ll40ls/LidarLite.h → src/drivers/distance_sensor/ll40ls/LidarLite.h

0
src/drivers/ll40ls/LidarLiteI2C.cpp → src/drivers/distance_sensor/ll40ls/LidarLiteI2C.cpp

0
src/drivers/ll40ls/LidarLiteI2C.h → src/drivers/distance_sensor/ll40ls/LidarLiteI2C.h

0
src/drivers/ll40ls/LidarLitePWM.cpp → src/drivers/distance_sensor/ll40ls/LidarLitePWM.cpp

0
src/drivers/ll40ls/LidarLitePWM.h → src/drivers/distance_sensor/ll40ls/LidarLitePWM.h

0
src/drivers/ll40ls/ll40ls.cpp → src/drivers/distance_sensor/ll40ls/ll40ls.cpp

1
src/drivers/mb12xx/CMakeLists.txt → src/drivers/distance_sensor/mb12xx/CMakeLists.txt

@ -34,6 +34,7 @@ px4_add_module( @@ -34,6 +34,7 @@ px4_add_module(
MODULE drivers__mb12xx
MAIN mb12xx
COMPILE_FLAGS
-Wno-sign-compare
SRCS
mb12xx.cpp
DEPENDS

26
src/drivers/mb12xx/mb12xx.cpp → src/drivers/distance_sensor/mb12xx/mb12xx.cpp

@ -41,6 +41,7 @@ @@ -41,6 +41,7 @@
#include <px4_config.h>
#include <px4_getopt.h>
#include <px4_workqueue.h>
#include <drivers/device/i2c.h>
@ -58,10 +59,6 @@ @@ -58,10 +59,6 @@
#include <unistd.h>
#include <vector>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@ -106,8 +103,8 @@ public: @@ -106,8 +103,8 @@ public:
virtual int init();
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
virtual ssize_t read(device::file_t *filp, char *buffer, size_t buflen);
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
/**
* Diagnostics - print some basic information about the driver.
@ -308,7 +305,7 @@ MB12XX::init() @@ -308,7 +305,7 @@ MB12XX::init()
DEVICE_LOG("sonar %d with address %d added", (i + 1), addr_ind[i]);
}
DEVICE_DEBUG("Number of sonars connected: %d", addr_ind.size());
DEVICE_DEBUG("Number of sonars connected: %lu", addr_ind.size());
ret = OK;
/* sensor is ok, but we don't really know if it is within range */
@ -348,7 +345,7 @@ MB12XX::get_maximum_distance() @@ -348,7 +345,7 @@ MB12XX::get_maximum_distance()
}
int
MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg)
MB12XX::ioctl(device::file_t *filp, int cmd, unsigned long arg)
{
switch (cmd) {
@ -425,14 +422,14 @@ MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -425,14 +422,14 @@ MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg)
return -EINVAL;
}
irqstate_t flags = px4_enter_critical_section();
ATOMIC_ENTER;
if (!_reports->resize(arg)) {
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return -ENOMEM;
}
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return OK;
}
@ -448,7 +445,7 @@ MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -448,7 +445,7 @@ MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg)
}
ssize_t
MB12XX::read(struct file *filp, char *buffer, size_t buflen)
MB12XX::read(device::file_t *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct distance_sensor_s);
@ -891,7 +888,7 @@ mb12xx_main(int argc, char *argv[]) @@ -891,7 +888,7 @@ mb12xx_main(int argc, char *argv[])
// check for optional arguments
int ch;
int myoptind = 1;
const char *myoptarg = NULL;
const char *myoptarg = nullptr;
uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
@ -942,5 +939,6 @@ mb12xx_main(int argc, char *argv[]) @@ -942,5 +939,6 @@ mb12xx_main(int argc, char *argv[])
mb12xx::info();
}
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
PX4_ERR("unrecognized command, try 'start', 'test', 'reset' or 'info'");
return PX4_ERROR;
}

0
src/drivers/sf0x/CMakeLists.txt → src/drivers/distance_sensor/sf0x/CMakeLists.txt

28
src/drivers/sf0x/sf0x.cpp → src/drivers/distance_sensor/sf0x/sf0x.cpp

@ -41,6 +41,7 @@ @@ -41,6 +41,7 @@
#include <px4_config.h>
#include <px4_getopt.h>
#include <px4_workqueue.h>
#include <sys/types.h>
#include <stdint.h>
@ -56,10 +57,6 @@ @@ -56,10 +57,6 @@
#include <unistd.h>
#include <termios.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@ -72,8 +69,6 @@ @@ -72,8 +69,6 @@
#include <uORB/topics/subsystem_info.h>
#include <uORB/topics/distance_sensor.h>
#include <board_config.h>
#include "sf0x_parser.h"
/* Configuration Constants */
@ -95,8 +90,8 @@ public: @@ -95,8 +90,8 @@ public:
virtual int init();
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
virtual ssize_t read(device::file_t *filp, char *buffer, size_t buflen);
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
/**
* Diagnostics - print some basic information about the driver.
@ -114,7 +109,6 @@ private: @@ -114,7 +109,6 @@ private:
int _conversion_interval;
work_s _work;
ringbuffer::RingBuffer *_reports;
bool _sensor_ok;
int _measure_ticks;
bool _collect_phase;
int _fd;
@ -186,7 +180,6 @@ SF0X::SF0X(const char *port, uint8_t rotation) : @@ -186,7 +180,6 @@ SF0X::SF0X(const char *port, uint8_t rotation) :
_max_distance(40.0f),
_conversion_interval(83334),
_reports(nullptr),
_sensor_ok(false),
_measure_ticks(0),
_collect_phase(false),
_fd(-1),
@ -383,7 +376,7 @@ SF0X::get_maximum_distance() @@ -383,7 +376,7 @@ SF0X::get_maximum_distance()
}
int
SF0X::ioctl(struct file *filp, int cmd, unsigned long arg)
SF0X::ioctl(device::file_t *filp, int cmd, unsigned long arg)
{
switch (cmd) {
@ -460,14 +453,14 @@ SF0X::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -460,14 +453,14 @@ SF0X::ioctl(struct file *filp, int cmd, unsigned long arg)
return -EINVAL;
}
irqstate_t flags = px4_enter_critical_section();
ATOMIC_ENTER;
if (!_reports->resize(arg)) {
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return -ENOMEM;
}
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return OK;
}
@ -483,7 +476,7 @@ SF0X::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -483,7 +476,7 @@ SF0X::ioctl(struct file *filp, int cmd, unsigned long arg)
}
ssize_t
SF0X::read(struct file *filp, char *buffer, size_t buflen)
SF0X::read(device::file_t *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct distance_sensor_s);
struct distance_sensor_s *rbuf = reinterpret_cast<struct distance_sensor_s *>(buffer);
@ -964,7 +957,7 @@ sf0x_main(int argc, char *argv[]) @@ -964,7 +957,7 @@ sf0x_main(int argc, char *argv[])
int ch;
uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
int myoptind = 1;
const char *myoptarg = NULL;
const char *myoptarg = nullptr;
while ((ch = px4_getopt(argc, argv, "R:", &myoptind, &myoptarg)) != EOF) {
@ -1019,5 +1012,6 @@ sf0x_main(int argc, char *argv[]) @@ -1019,5 +1012,6 @@ sf0x_main(int argc, char *argv[])
sf0x::info();
}
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
PX4_ERR("unrecognized command, try 'start', 'test', 'reset' or 'info'");
return PX4_ERROR;
}

0
src/drivers/sf0x/sf0x_parser.cpp → src/drivers/distance_sensor/sf0x/sf0x_parser.cpp

0
src/drivers/sf0x/sf0x_parser.h → src/drivers/distance_sensor/sf0x/sf0x_parser.h

1
src/drivers/sf0x/sf0x_tests/CMakeLists.txt → src/drivers/distance_sensor/sf0x/sf0x_tests/CMakeLists.txt

@ -41,4 +41,3 @@ px4_add_module( @@ -41,4 +41,3 @@ px4_add_module(
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :

3
src/drivers/sf0x/sf0x_tests/SF0XTest.cpp → src/drivers/distance_sensor/sf0x/sf0x_tests/SF0XTest.cpp

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
#include <unit_test.h>
#include <drivers/sf0x/sf0x_parser.h>
#include "../sf0x_parser.h"
#include <systemlib/err.h>
@ -89,4 +89,3 @@ bool SF0XTest::sf0xTest() @@ -89,4 +89,3 @@ bool SF0XTest::sf0xTest()
}
ut_declare_test_c(sf0x_tests_main, SF0XTest)

1
src/drivers/sf1xx/CMakeLists.txt → src/drivers/distance_sensor/sf1xx/CMakeLists.txt

@ -35,6 +35,7 @@ px4_add_module( @@ -35,6 +35,7 @@ px4_add_module(
MODULE drivers__sf1xx
MAIN sf1xx
COMPILE_FLAGS
-Wno-sign-compare
SRCS
sf1xx.cpp
DEPENDS

24
src/drivers/sf1xx/sf1xx.cpp → src/drivers/distance_sensor/sf1xx/sf1xx.cpp

@ -44,6 +44,7 @@ @@ -44,6 +44,7 @@
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_getopt.h>
#include <px4_workqueue.h>
#include <drivers/device/i2c.h>
@ -61,10 +62,6 @@ @@ -61,10 +62,6 @@
#include <unistd.h>
#include <vector>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@ -96,8 +93,8 @@ public: @@ -96,8 +93,8 @@ public:
virtual int init();
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
virtual ssize_t read(device::file_t *filp, char *buffer, size_t buflen);
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
/**
* Diagnostics - print some basic information about the driver.
@ -346,7 +343,7 @@ SF1XX::get_maximum_distance() @@ -346,7 +343,7 @@ SF1XX::get_maximum_distance()
}
int
SF1XX::ioctl(struct file *filp, int cmd, unsigned long arg)
SF1XX::ioctl(device::file_t *filp, int cmd, unsigned long arg)
{
switch (cmd) {
@ -423,14 +420,14 @@ SF1XX::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -423,14 +420,14 @@ SF1XX::ioctl(struct file *filp, int cmd, unsigned long arg)
return -EINVAL;
}
irqstate_t flags = px4_enter_critical_section();
ATOMIC_ENTER;
if (!_reports->resize(arg)) {
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return -ENOMEM;
}
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return OK;
}
@ -446,7 +443,7 @@ SF1XX::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -446,7 +443,7 @@ SF1XX::ioctl(struct file *filp, int cmd, unsigned long arg)
}
ssize_t
SF1XX::read(struct file *filp, char *buffer, size_t buflen)
SF1XX::read(device::file_t *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct distance_sensor_s);
struct distance_sensor_s *rbuf = reinterpret_cast<struct distance_sensor_s *>(buffer);
@ -828,7 +825,7 @@ sf1xx_main(int argc, char *argv[]) @@ -828,7 +825,7 @@ sf1xx_main(int argc, char *argv[])
// check for optional arguments
int ch;
int myoptind = 1;
const char *myoptarg = NULL;
const char *myoptarg = nullptr;
uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
@ -879,5 +876,6 @@ sf1xx_main(int argc, char *argv[]) @@ -879,5 +876,6 @@ sf1xx_main(int argc, char *argv[])
sf1xx::info();
}
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
PX4_ERR("unrecognized command, try 'start', 'test', 'reset' or 'info'");
return PX4_ERROR;
}

1
src/drivers/srf02/CMakeLists.txt → src/drivers/distance_sensor/srf02/CMakeLists.txt

@ -34,6 +34,7 @@ px4_add_module( @@ -34,6 +34,7 @@ px4_add_module(
MODULE drivers__srf02
MAIN srf02
COMPILE_FLAGS
-Wno-sign-compare
SRCS
srf02.cpp
DEPENDS

26
src/drivers/srf02/srf02.cpp → src/drivers/distance_sensor/srf02/srf02.cpp

@ -40,6 +40,7 @@ @@ -40,6 +40,7 @@
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_getopt.h>
#include <px4_workqueue.h>
#include <drivers/device/i2c.h>
@ -57,10 +58,6 @@ @@ -57,10 +58,6 @@
#include <unistd.h>
#include <vector>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@ -107,8 +104,8 @@ public: @@ -107,8 +104,8 @@ public:
virtual int init();
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
virtual ssize_t read(device::file_t *filp, char *buffer, size_t buflen);
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
/**
* Diagnostics - print some basic information about the driver.
@ -309,7 +306,7 @@ SRF02::init() @@ -309,7 +306,7 @@ SRF02::init()
DEVICE_LOG("sonar %d with address %d added", (i + 1), addr_ind[i]);
}
DEVICE_DEBUG("Number of sonars connected: %d", addr_ind.size());
DEVICE_DEBUG("Number of sonars connected: %zu", addr_ind.size());
ret = OK;
/* sensor is ok, but we don't really know if it is within range */
@ -349,7 +346,7 @@ SRF02::get_maximum_distance() @@ -349,7 +346,7 @@ SRF02::get_maximum_distance()
}
int
SRF02::ioctl(struct file *filp, int cmd, unsigned long arg)
SRF02::ioctl(device::file_t *filp, int cmd, unsigned long arg)
{
switch (cmd) {
@ -426,14 +423,14 @@ SRF02::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -426,14 +423,14 @@ SRF02::ioctl(struct file *filp, int cmd, unsigned long arg)
return -EINVAL;
}
irqstate_t flags = px4_enter_critical_section();
ATOMIC_ENTER;
if (!_reports->resize(arg)) {
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return -ENOMEM;
}
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return OK;
}
@ -449,7 +446,7 @@ SRF02::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -449,7 +446,7 @@ SRF02::ioctl(struct file *filp, int cmd, unsigned long arg)
}
ssize_t
SRF02::read(struct file *filp, char *buffer, size_t buflen)
SRF02::read(device::file_t *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct distance_sensor_s);
@ -895,7 +892,7 @@ srf02_main(int argc, char *argv[]) @@ -895,7 +892,7 @@ srf02_main(int argc, char *argv[])
// check for optional arguments
int ch;
int myoptind = 1;
const char *myoptarg = NULL;
const char *myoptarg = nullptr;
uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
@ -946,5 +943,6 @@ srf02_main(int argc, char *argv[]) @@ -946,5 +943,6 @@ srf02_main(int argc, char *argv[])
srf02::info();
}
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
PX4_ERR("unrecognized command, try 'start', 'test', 'reset' or 'info'");
return PX4_ERROR;
}

1
src/drivers/srf02_i2c/CMakeLists.txt → src/drivers/distance_sensor/srf02_i2c/CMakeLists.txt

@ -34,6 +34,7 @@ px4_add_module( @@ -34,6 +34,7 @@ px4_add_module(
MODULE drivers__srf02_i2c
MAIN srf02_i2c
COMPILE_FLAGS
-Wno-sign-compare
SRCS
srf02_i2c.cpp
DEPENDS

26
src/drivers/srf02_i2c/srf02_i2c.cpp → src/drivers/distance_sensor/srf02_i2c/srf02_i2c.cpp

@ -39,6 +39,7 @@ @@ -39,6 +39,7 @@
* Driver for the Maxbotix sonar range finders connected via I2C.
*/
#include <px4_workqueue.h>
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_getopt.h>
@ -59,10 +60,6 @@ @@ -59,10 +60,6 @@
#include <unistd.h>
#include <vector>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@ -108,8 +105,8 @@ public: @@ -108,8 +105,8 @@ public:
virtual int init();
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
virtual ssize_t read(device::file_t *filp, char *buffer, size_t buflen);
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
/**
* Diagnostics - print some basic information about the driver.
@ -310,7 +307,7 @@ SRF02_I2C::init() @@ -310,7 +307,7 @@ SRF02_I2C::init()
DEVICE_LOG("sonar %d with address %d added", (i + 1), addr_ind[i]);
}
DEVICE_DEBUG("Number of sonars connected: %d", addr_ind.size());
DEVICE_DEBUG("Number of sonars connected: %zu", addr_ind.size());
ret = OK;
/* sensor is ok, but we don't really know if it is within range */
@ -350,7 +347,7 @@ SRF02_I2C::get_maximum_distance() @@ -350,7 +347,7 @@ SRF02_I2C::get_maximum_distance()
}
int
SRF02_I2C::ioctl(struct file *filp, int cmd, unsigned long arg)
SRF02_I2C::ioctl(device::file_t *filp, int cmd, unsigned long arg)
{
switch (cmd) {
@ -427,14 +424,14 @@ SRF02_I2C::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -427,14 +424,14 @@ SRF02_I2C::ioctl(struct file *filp, int cmd, unsigned long arg)
return -EINVAL;
}
irqstate_t flags = px4_enter_critical_section();
ATOMIC_ENTER;
if (!_reports->resize(arg)) {
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return -ENOMEM;
}
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return OK;
}
@ -450,7 +447,7 @@ SRF02_I2C::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -450,7 +447,7 @@ SRF02_I2C::ioctl(struct file *filp, int cmd, unsigned long arg)
}
ssize_t
SRF02_I2C::read(struct file *filp, char *buffer, size_t buflen)
SRF02_I2C::read(device::file_t *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct distance_sensor_s);
@ -895,7 +892,7 @@ srf02_i2c_main(int argc, char *argv[]) @@ -895,7 +892,7 @@ srf02_i2c_main(int argc, char *argv[])
// check for optional arguments
int ch;
int myoptind = 1;
const char *myoptarg = NULL;
const char *myoptarg = nullptr;
uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
@ -946,5 +943,6 @@ srf02_i2c_main(int argc, char *argv[]) @@ -946,5 +943,6 @@ srf02_i2c_main(int argc, char *argv[])
srf02_i2c::info();
}
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
PX4_ERR("unrecognized command, try 'start', 'test', 'reset' or 'info'");
return PX4_ERROR;
}

1
src/drivers/teraranger/CMakeLists.txt → src/drivers/distance_sensor/teraranger/CMakeLists.txt

@ -35,6 +35,7 @@ px4_add_module( @@ -35,6 +35,7 @@ px4_add_module(
MAIN teraranger
STACK_MAIN 1200
COMPILE_FLAGS
-Wno-sign-compare
SRCS
teraranger.cpp
DEPENDS

24
src/drivers/teraranger/teraranger.cpp → src/drivers/distance_sensor/teraranger/teraranger.cpp

@ -41,6 +41,7 @@ @@ -41,6 +41,7 @@
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_getopt.h>
#include <px4_workqueue.h>
#include <drivers/device/i2c.h>
@ -57,10 +58,6 @@ @@ -57,10 +58,6 @@
#include <math.h>
#include <unistd.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@ -108,8 +105,8 @@ public: @@ -108,8 +105,8 @@ public:
virtual int init();
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
virtual ssize_t read(device::file_t *filp, char *buffer, size_t buflen);
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
/**
* Diagnostics - print some basic information about the driver.
@ -414,7 +411,7 @@ TERARANGER::get_maximum_distance() @@ -414,7 +411,7 @@ TERARANGER::get_maximum_distance()
}
int
TERARANGER::ioctl(struct file *filp, int cmd, unsigned long arg)
TERARANGER::ioctl(device::file_t *filp, int cmd, unsigned long arg)
{
switch (cmd) {
@ -490,14 +487,14 @@ TERARANGER::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -490,14 +487,14 @@ TERARANGER::ioctl(struct file *filp, int cmd, unsigned long arg)
return -EINVAL;
}
irqstate_t flags = px4_enter_critical_section();
ATOMIC_ENTER;
if (!_reports->resize(arg)) {
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return -ENOMEM;
}
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return OK;
}
@ -513,7 +510,7 @@ TERARANGER::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -513,7 +510,7 @@ TERARANGER::ioctl(struct file *filp, int cmd, unsigned long arg)
}
ssize_t
TERARANGER::read(struct file *filp, char *buffer, size_t buflen)
TERARANGER::read(device::file_t *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct distance_sensor_s);
struct distance_sensor_s *rbuf = reinterpret_cast<struct distance_sensor_s *>(buffer);
@ -936,7 +933,7 @@ teraranger_main(int argc, char *argv[]) @@ -936,7 +933,7 @@ teraranger_main(int argc, char *argv[])
{
int ch;
int myoptind = 1;
const char *myoptarg = NULL;
const char *myoptarg = nullptr;
uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
while ((ch = px4_getopt(argc, argv, "R:", &myoptind, &myoptarg)) != EOF) {
@ -986,5 +983,6 @@ teraranger_main(int argc, char *argv[]) @@ -986,5 +983,6 @@ teraranger_main(int argc, char *argv[])
teraranger::info();
}
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
PX4_ERR("unrecognized command, try 'start', 'test', 'reset' or 'info'");
return PX4_ERROR;
}

0
src/drivers/tfmini/CMakeLists.txt → src/drivers/distance_sensor/tfmini/CMakeLists.txt

26
src/drivers/tfmini/tfmini.cpp → src/drivers/distance_sensor/tfmini/tfmini.cpp

@ -41,6 +41,7 @@ @@ -41,6 +41,7 @@
*/
#include <px4_config.h>
#include <px4_workqueue.h>
#include <px4_getopt.h>
#include <sys/types.h>
@ -57,10 +58,6 @@ @@ -57,10 +58,6 @@
#include <unistd.h>
#include <termios.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@ -94,8 +91,8 @@ public: @@ -94,8 +91,8 @@ public:
virtual int init();
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
virtual ssize_t read(device::file_t *filp, char *buffer, size_t buflen);
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
/**
* Diagnostics - print some basic information about the driver.
@ -110,7 +107,6 @@ private: @@ -110,7 +107,6 @@ private:
int _conversion_interval;
work_s _work;
ringbuffer::RingBuffer *_reports;
bool _sensor_ok;
int _measure_ticks;
bool _collect_phase;
int _fd;
@ -183,7 +179,6 @@ TFMINI::TFMINI(const char *port, uint8_t rotation) : @@ -183,7 +179,6 @@ TFMINI::TFMINI(const char *port, uint8_t rotation) :
_max_distance(12.0f),
_conversion_interval(10000),
_reports(nullptr),
_sensor_ok(false),
_measure_ticks(0),
_collect_phase(false),
_fd(-1),
@ -362,7 +357,7 @@ TFMINI::get_maximum_distance() @@ -362,7 +357,7 @@ TFMINI::get_maximum_distance()
}
int
TFMINI::ioctl(struct file *filp, int cmd, unsigned long arg)
TFMINI::ioctl(device::file_t *filp, int cmd, unsigned long arg)
{
switch (cmd) {
@ -439,14 +434,14 @@ TFMINI::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -439,14 +434,14 @@ TFMINI::ioctl(struct file *filp, int cmd, unsigned long arg)
return -EINVAL;
}
irqstate_t flags = px4_enter_critical_section();
ATOMIC_ENTER;
if (!_reports->resize(arg)) {
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return -ENOMEM;
}
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return OK;
}
@ -462,7 +457,7 @@ TFMINI::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -462,7 +457,7 @@ TFMINI::ioctl(struct file *filp, int cmd, unsigned long arg)
}
ssize_t
TFMINI::read(struct file *filp, char *buffer, size_t buflen)
TFMINI::read(device::file_t *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct distance_sensor_s);
struct distance_sensor_s *rbuf = reinterpret_cast<struct distance_sensor_s *>(buffer);
@ -912,7 +907,7 @@ tfmini_main(int argc, char *argv[]) @@ -912,7 +907,7 @@ tfmini_main(int argc, char *argv[])
int ch;
uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
int myoptind = 1;
const char *myoptarg = NULL;
const char *myoptarg = nullptr;
while ((ch = px4_getopt(argc, argv, "R:", &myoptind, &myoptarg)) != EOF) {
@ -967,5 +962,6 @@ tfmini_main(int argc, char *argv[]) @@ -967,5 +962,6 @@ tfmini_main(int argc, char *argv[])
tfmini::info();
}
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
PX4_ERR("unrecognized command, try 'start', 'test', 'reset' or 'info'");
return PX4_ERROR;
}

0
src/drivers/tfmini/tfmini_parser.cpp → src/drivers/distance_sensor/tfmini/tfmini_parser.cpp

0
src/drivers/tfmini/tfmini_parser.h → src/drivers/distance_sensor/tfmini/tfmini_parser.h

0
src/drivers/ulanding/CMakeLists.txt → src/drivers/distance_sensor/ulanding/CMakeLists.txt

2
src/drivers/ulanding/ulanding.cpp → src/drivers/distance_sensor/ulanding/ulanding.cpp

@ -491,7 +491,7 @@ int ulanding_radar_main(int argc, char *argv[]) @@ -491,7 +491,7 @@ int ulanding_radar_main(int argc, char *argv[])
// check for optional arguments
int ch;
int myoptind = 1;
const char *myoptarg = NULL;
const char *myoptarg = nullptr;
uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
Loading…
Cancel
Save