forked from Archive/PX4-Autopilot
organize all telemetry drivers in subdirectory
This commit is contained in:
parent
681e351f62
commit
c459a04b9b
|
@ -11,6 +11,7 @@ set(config_module_list
|
|||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
#drivers/magnetometer
|
||||
drivers/telemetry
|
||||
|
||||
drivers/device
|
||||
drivers/stm32
|
||||
|
@ -24,11 +25,9 @@ set(config_module_list
|
|||
drivers/gps
|
||||
drivers/pwm_out_sim
|
||||
drivers/airspeed
|
||||
#drivers/frsky_telemetry
|
||||
modules/sensors
|
||||
#drivers/pwm_input
|
||||
#drivers/camera_trigger
|
||||
drivers/bst
|
||||
|
||||
#
|
||||
# System commands
|
||||
|
|
|
@ -11,17 +11,15 @@ set(config_module_list
|
|||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
drivers/magnetometer
|
||||
drivers/telemetry
|
||||
|
||||
drivers/airspeed
|
||||
drivers/batt_smbus
|
||||
drivers/blinkm
|
||||
drivers/boards
|
||||
drivers/bst
|
||||
drivers/camera_trigger
|
||||
drivers/device
|
||||
drivers/frsky_telemetry
|
||||
drivers/gps
|
||||
drivers/hott
|
||||
drivers/led
|
||||
drivers/mkblctrl
|
||||
drivers/imu/mpu6000
|
||||
|
|
|
@ -10,21 +10,20 @@ set(config_module_list
|
|||
drivers/barometer
|
||||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
drivers/magnetometer
|
||||
drivers/telemetry
|
||||
|
||||
drivers/airspeed
|
||||
drivers/batt_smbus
|
||||
drivers/blinkm
|
||||
drivers/boards
|
||||
drivers/bst
|
||||
drivers/camera_trigger
|
||||
drivers/device
|
||||
drivers/frsky_telemetry
|
||||
drivers/gps
|
||||
#drivers/hott
|
||||
drivers/imu/l3gd20
|
||||
drivers/led
|
||||
drivers/imu/lsm303d
|
||||
drivers/magnetometer/hmc5883
|
||||
#drivers/mkblctrl
|
||||
drivers/imu/mpu6000
|
||||
drivers/imu/mpu9250
|
||||
|
|
|
@ -11,21 +11,18 @@ set(config_module_list
|
|||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
drivers/magnetometer
|
||||
drivers/telemetry
|
||||
|
||||
drivers/airspeed
|
||||
drivers/barometer/mpl3115a2
|
||||
drivers/batt_smbus
|
||||
drivers/blinkm
|
||||
drivers/boards
|
||||
drivers/bst
|
||||
drivers/camera_trigger
|
||||
drivers/device
|
||||
drivers/frsky_telemetry
|
||||
drivers/imu/fxas21002c
|
||||
drivers/imu/fxos8701cq
|
||||
drivers/gps
|
||||
drivers/hott
|
||||
drivers/iridiumsbd
|
||||
drivers/kinetis
|
||||
drivers/kinetis/adc
|
||||
drivers/kinetis/tone_alarm
|
||||
|
|
|
@ -11,6 +11,7 @@ set(config_module_list
|
|||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
drivers/magnetometer
|
||||
drivers/telemetry
|
||||
|
||||
drivers/device
|
||||
drivers/samv7
|
||||
|
@ -26,10 +27,8 @@ set(config_module_list
|
|||
drivers/imu/l3gd20
|
||||
drivers/gps
|
||||
#WIP drivers/pwm_out_sim
|
||||
drivers/hott
|
||||
drivers/blinkm
|
||||
drivers/airspeed
|
||||
drivers/frsky_telemetry
|
||||
modules/sensors
|
||||
#drivers/mkblctrl
|
||||
drivers/px4flow
|
||||
|
@ -37,7 +36,6 @@ set(config_module_list
|
|||
## drivers/gimbal
|
||||
#WIP drivers/pwm_input
|
||||
#WIP drivers/camera_trigger
|
||||
drivers/bst
|
||||
|
||||
#
|
||||
# System commands
|
||||
|
|
|
@ -9,6 +9,7 @@ set(config_module_list
|
|||
#drivers/barometer
|
||||
drivers/differential_pressure
|
||||
#drivers/magnetometer
|
||||
#drivers/telemetry
|
||||
|
||||
#drivers/imu/adis16448
|
||||
drivers/airspeed
|
||||
|
|
|
@ -31,7 +31,6 @@ set(config_module_list
|
|||
drivers/airspeed
|
||||
drivers/barometer
|
||||
drivers/differential_pressure
|
||||
drivers/frsky_telemetry
|
||||
modules/sensors
|
||||
#drivers/mkblctrl
|
||||
drivers/px4flow
|
||||
|
|
|
@ -17,6 +17,7 @@ set(config_module_list
|
|||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
drivers/magnetometer
|
||||
drivers/telemetry
|
||||
|
||||
drivers/imu/adis16448
|
||||
drivers/airspeed
|
||||
|
@ -24,13 +25,9 @@ set(config_module_list
|
|||
drivers/blinkm
|
||||
drivers/imu/bmi160
|
||||
drivers/boards
|
||||
drivers/bst
|
||||
drivers/camera_trigger
|
||||
drivers/device
|
||||
drivers/frsky_telemetry
|
||||
drivers/gps
|
||||
drivers/hott
|
||||
drivers/iridiumsbd
|
||||
drivers/irlock
|
||||
drivers/imu/l3gd20
|
||||
drivers/led
|
||||
|
|
|
@ -11,6 +11,7 @@ set(config_module_list
|
|||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
drivers/magnetometer
|
||||
drivers/telemetry
|
||||
|
||||
drivers/airspeed
|
||||
drivers/batt_smbus
|
||||
|
@ -19,13 +20,9 @@ set(config_module_list
|
|||
drivers/imu/bmi055
|
||||
drivers/imu/bmi160
|
||||
drivers/boards
|
||||
drivers/bst
|
||||
drivers/camera_trigger
|
||||
drivers/device
|
||||
drivers/frsky_telemetry
|
||||
drivers/gps
|
||||
drivers/hott
|
||||
drivers/iridiumsbd
|
||||
drivers/irlock
|
||||
drivers/led
|
||||
drivers/mkblctrl
|
||||
|
|
|
@ -11,6 +11,7 @@ set(config_module_list
|
|||
drivers/barometer
|
||||
drivers/differential_pressure
|
||||
drivers/magnetometer
|
||||
drivers/telemetry
|
||||
|
||||
drivers/airspeed
|
||||
drivers/batt_smbus
|
||||
|
@ -18,13 +19,9 @@ set(config_module_list
|
|||
drivers/imu/bma180
|
||||
drivers/imu/bmi160
|
||||
drivers/boards
|
||||
drivers/bst
|
||||
drivers/camera_trigger
|
||||
drivers/device
|
||||
drivers/frsky_telemetry
|
||||
drivers/gps
|
||||
drivers/hott
|
||||
drivers/iridiumsbd
|
||||
drivers/irlock
|
||||
drivers/imu/l3gd20
|
||||
drivers/led
|
||||
|
|
|
@ -11,6 +11,7 @@ set(config_module_list
|
|||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
drivers/magnetometer
|
||||
drivers/telemetry
|
||||
|
||||
drivers/airspeed
|
||||
drivers/batt_smbus
|
||||
|
@ -19,13 +20,9 @@ set(config_module_list
|
|||
drivers/imu/bmi055
|
||||
drivers/imu/bmi160
|
||||
drivers/boards
|
||||
drivers/bst
|
||||
drivers/camera_trigger
|
||||
drivers/device
|
||||
drivers/frsky_telemetry
|
||||
drivers/gps
|
||||
drivers/hott
|
||||
drivers/iridiumsbd
|
||||
drivers/irlock
|
||||
drivers/led
|
||||
drivers/mkblctrl
|
||||
|
|
|
@ -11,6 +11,7 @@ set(config_module_list
|
|||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
drivers/magnetometer
|
||||
drivers/telemetry
|
||||
|
||||
drivers/imu/adis16448
|
||||
drivers/airspeed
|
||||
|
@ -18,12 +19,9 @@ set(config_module_list
|
|||
drivers/imu/bma180
|
||||
drivers/imu/bmi160
|
||||
drivers/boards
|
||||
drivers/bst
|
||||
drivers/camera_trigger
|
||||
drivers/device
|
||||
drivers/frsky_telemetry
|
||||
drivers/gps
|
||||
drivers/hott
|
||||
drivers/led
|
||||
drivers/mkblctrl
|
||||
drivers/imu/mpu6000
|
||||
|
|
|
@ -21,6 +21,7 @@ set(config_module_list
|
|||
drivers/device
|
||||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
#drivers/telemetry
|
||||
|
||||
modules/sensors
|
||||
|
||||
|
|
|
@ -5,6 +5,7 @@ set(config_module_list
|
|||
#drivers/barometer
|
||||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
#drivers/telemetry
|
||||
|
||||
drivers/airspeed
|
||||
drivers/batt_smbus
|
||||
|
|
|
@ -0,0 +1,37 @@
|
|||
############################################################################
|
||||
#
|
||||
# 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(bst)
|
||||
add_subdirectory(frsky_telemetry)
|
||||
add_subdirectory(hott)
|
||||
add_subdirectory(iridiumsbd)
|
|
@ -411,5 +411,6 @@ int bst_main(int argc, char *argv[])
|
|||
exit(0);
|
||||
}
|
||||
|
||||
errx(1, "unrecognized command\n%s", commandline_usage);
|
||||
PX4_WARN("unrecognized command\n%s", commandline_usage);
|
||||
return 1;
|
||||
}
|
|
@ -55,7 +55,8 @@ open_uart(const char *device)
|
|||
const int uart = open(device, O_RDWR | O_NOCTTY);
|
||||
|
||||
if (uart < 0) {
|
||||
err(1, "ERR: opening %s", device);
|
||||
PX4_ERR("opening %s", device);
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* Back up the original uart configuration to restore it after exit */
|
||||
|
@ -64,7 +65,8 @@ open_uart(const char *device)
|
|||
|
||||
if ((termios_state = tcgetattr(uart, &uart_config_original)) < 0) {
|
||||
close(uart);
|
||||
err(1, "ERR: %s: %d", device, termios_state);
|
||||
PX4_ERR("%s: %d", device, termios_state);
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* Fill the struct for the new configuration */
|
||||
|
@ -77,13 +79,14 @@ open_uart(const char *device)
|
|||
/* Set baud rate */
|
||||
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
|
||||
close(uart);
|
||||
err(1, "ERR: %s: %d (cfsetispeed, cfsetospeed)",
|
||||
device, termios_state);
|
||||
PX4_ERR("%s: %d (cfsetispeed, cfsetospeed)", device, termios_state);
|
||||
return 1;
|
||||
}
|
||||
|
||||
if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
|
||||
close(uart);
|
||||
err(1, "ERR: %s (tcsetattr)", device);
|
||||
PX4_ERR("%s (tcsetattr)", device);
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* Activate single wire mode */
|
|
@ -43,6 +43,7 @@
|
|||
#define MESSAGES_H
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#define POLL_TIMEOUT_IN_MSECS 3500
|
||||
|
|
@ -44,7 +44,6 @@
|
|||
#include <termios.h>
|
||||
#include <pthread.h>
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/param/param.h>
|
Loading…
Reference in New Issue