forked from Archive/PX4-Autopilot
adc: refactor into arch-specific directories
This commit is contained in:
parent
ab43a83bed
commit
1cb6c36a00
|
@ -15,6 +15,7 @@ px4_add_board(
|
|||
TEL2:/dev/ttyS2
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_trigger
|
||||
|
@ -41,7 +42,6 @@ px4_add_board(
|
|||
px4fmu
|
||||
rc_input
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -16,6 +16,7 @@ px4_add_board(
|
|||
TEL2:/dev/ttyS2
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -47,7 +48,6 @@ px4_add_board(
|
|||
px4io
|
||||
roboclaw
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -18,6 +18,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS3
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -48,7 +49,6 @@ px4_add_board(
|
|||
rc_input
|
||||
#roboclaw
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -17,6 +17,7 @@ px4_add_board(
|
|||
# /dev/ttyS5: UART7 (ESC telemetry)
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer/bmp280
|
||||
gps
|
||||
imu/mpu6000
|
||||
|
@ -26,7 +27,6 @@ px4_add_board(
|
|||
px4fmu
|
||||
rc_input
|
||||
stm32
|
||||
stm32/adc
|
||||
telemetry
|
||||
tone_alarm
|
||||
osd
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
#FRSKY:/dev/ttyS5
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
#barometer # all available barometer drivers
|
||||
#barometer/dps310
|
||||
batt_smbus
|
||||
|
@ -50,7 +51,6 @@ px4_add_board(
|
|||
roboclaw
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -15,6 +15,7 @@ px4_add_board(
|
|||
TEL2:/dev/ttyS1
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
barometer/mpl3115a2
|
||||
batt_smbus
|
||||
|
@ -31,7 +32,6 @@ px4_add_board(
|
|||
imu/mpu9250
|
||||
irlock
|
||||
kinetis
|
||||
kinetis/adc
|
||||
lights/blinkm
|
||||
lights/oreoled
|
||||
lights/rgbled
|
||||
|
|
|
@ -12,6 +12,7 @@ px4_add_board(
|
|||
URT6:/dev/ttyS2
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/bmp280
|
||||
#batt_smbus
|
||||
|
@ -36,7 +37,6 @@ px4_add_board(
|
|||
px4fmu
|
||||
rc_input
|
||||
stm32
|
||||
stm32/adc
|
||||
#tap_esc
|
||||
#telemetry # all available telemetry drivers
|
||||
telemetry/frsky_telemetry
|
||||
|
|
|
@ -20,6 +20,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS6
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/ms5611
|
||||
#batt_smbus
|
||||
|
@ -56,7 +57,6 @@ px4_add_board(
|
|||
px4io
|
||||
#roboclaw
|
||||
stm32
|
||||
stm32/adc
|
||||
#tap_esc
|
||||
#telemetry # all available telemetry drivers
|
||||
#test_ppm
|
||||
|
|
|
@ -18,6 +18,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS6
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/ms5611
|
||||
batt_smbus
|
||||
|
@ -36,7 +37,6 @@ px4_add_board(
|
|||
px4fmu
|
||||
px4io
|
||||
stm32
|
||||
stm32/adc
|
||||
#telemetry # all available telemetry drivers
|
||||
telemetry/iridiumsbd
|
||||
tone_alarm
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS6
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/ms5611
|
||||
#batt_smbus
|
||||
|
@ -52,7 +53,6 @@ px4_add_board(
|
|||
px4fmu
|
||||
px4io
|
||||
stm32
|
||||
stm32/adc
|
||||
#tap_esc
|
||||
#telemetry # all available telemetry drivers
|
||||
#test_ppm
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS6
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer/ms5611
|
||||
#batt_smbus
|
||||
camera_capture
|
||||
|
@ -36,7 +37,6 @@ px4_add_board(
|
|||
px4fmu
|
||||
px4io
|
||||
stm32
|
||||
stm32/adc
|
||||
tone_alarm
|
||||
|
||||
MODULES
|
||||
|
|
|
@ -16,6 +16,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS6
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer/ms5611
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -32,7 +33,6 @@ px4_add_board(
|
|||
px4fmu
|
||||
px4io
|
||||
stm32
|
||||
stm32/adc
|
||||
tone_alarm
|
||||
|
||||
MODULES
|
||||
|
|
|
@ -18,6 +18,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS3
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/ms5611
|
||||
#batt_smbus
|
||||
|
@ -52,7 +53,6 @@ px4_add_board(
|
|||
px4fmu
|
||||
px4io
|
||||
stm32
|
||||
stm32/adc
|
||||
#tap_esc
|
||||
#telemetry # all available telemetry drivers
|
||||
#test_ppm
|
||||
|
|
|
@ -20,6 +20,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS6
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -55,7 +56,6 @@ px4_add_board(
|
|||
px4io
|
||||
roboclaw
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -20,6 +20,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS3
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -54,7 +55,6 @@ px4_add_board(
|
|||
px4io
|
||||
roboclaw
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -20,6 +20,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS3
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -54,7 +55,6 @@ px4_add_board(
|
|||
px4io
|
||||
roboclaw
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -16,6 +16,7 @@ px4_add_board(
|
|||
TEL2:/dev/ttyS2
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -40,7 +41,6 @@ px4_add_board(
|
|||
rc_input
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -16,6 +16,7 @@ px4_add_board(
|
|||
TEL2:/dev/ttyS2
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -42,7 +43,6 @@ px4_add_board(
|
|||
rc_input
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -16,6 +16,7 @@ px4_add_board(
|
|||
TEL2:/dev/ttyS2
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -40,7 +41,6 @@ px4_add_board(
|
|||
rc_input
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS6
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -53,7 +54,6 @@ px4_add_board(
|
|||
px4io
|
||||
roboclaw
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS6
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_trigger
|
||||
|
@ -52,7 +53,6 @@ px4_add_board(
|
|||
px4io
|
||||
roboclaw
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -18,6 +18,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS3
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -54,7 +55,6 @@ px4_add_board(
|
|||
roboclaw
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -18,6 +18,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS3
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -54,7 +55,6 @@ px4_add_board(
|
|||
roboclaw
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -17,6 +17,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS3
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -38,7 +39,6 @@ px4_add_board(
|
|||
rc_input
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
telemetry # all available telemetry drivers
|
||||
tone_alarm
|
||||
uavcan
|
||||
|
|
|
@ -18,6 +18,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS3
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -54,7 +55,6 @@ px4_add_board(
|
|||
roboclaw
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -18,6 +18,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS3
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -42,7 +43,6 @@ px4_add_board(
|
|||
roboclaw
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
tone_alarm
|
||||
|
|
|
@ -17,6 +17,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS3
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -42,7 +43,6 @@ px4_add_board(
|
|||
roboclaw
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
telemetry # all available telemetry drivers
|
||||
tone_alarm
|
||||
uavcan
|
||||
|
|
|
@ -18,6 +18,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS3
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -52,7 +53,6 @@ px4_add_board(
|
|||
roboclaw
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -18,6 +18,7 @@ px4_add_board(
|
|||
TEL4:/dev/ttyS3
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -52,7 +53,6 @@ px4_add_board(
|
|||
roboclaw
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
GPS2:/dev/ttyS0
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -54,7 +55,6 @@ px4_add_board(
|
|||
roboclaw
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -18,6 +18,7 @@ px4_add_board(
|
|||
GPS2:/dev/ttyS0
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -48,7 +49,6 @@ px4_add_board(
|
|||
rc_input
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
telemetry # all available telemetry drivers
|
||||
tone_alarm
|
||||
uavcan
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
GPS2:/dev/ttyS0
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -49,7 +50,6 @@ px4_add_board(
|
|||
roboclaw
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
tone_alarm
|
||||
|
|
|
@ -18,6 +18,7 @@ px4_add_board(
|
|||
GPS2:/dev/ttyS0
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -52,7 +53,6 @@ px4_add_board(
|
|||
roboclaw
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
telemetry # all available telemetry drivers
|
||||
tone_alarm
|
||||
uavcan
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
GPS2:/dev/ttyS0
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -54,7 +55,6 @@ px4_add_board(
|
|||
roboclaw
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
GPS2:/dev/ttyS0
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -54,7 +55,6 @@ px4_add_board(
|
|||
roboclaw
|
||||
safety_button
|
||||
stm32
|
||||
stm32/adc
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -16,6 +16,7 @@ px4_add_board(
|
|||
TEL2:/dev/ttyS2
|
||||
|
||||
DRIVERS
|
||||
adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/ms5611
|
||||
batt_smbus
|
||||
|
@ -46,7 +47,6 @@ px4_add_board(
|
|||
px4fmu
|
||||
rc_input
|
||||
stm32
|
||||
stm32/adc
|
||||
#tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
#test_ppm
|
||||
|
|
|
@ -0,0 +1,40 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
#if SYSTEM_ADC_BASE == HW_REV_VER_ADC_BASE
|
||||
# define SYSTEM_ADC_COUNT 1
|
||||
#else
|
||||
# define SYSTEM_ADC_COUNT 2
|
||||
#endif
|
||||
|
|
@ -1,6 +1,6 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2015-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
|
||||
|
@ -31,9 +31,6 @@
|
|||
#
|
||||
############################################################################
|
||||
|
||||
px4_add_module(
|
||||
MODULE drivers__adc
|
||||
MAIN adc
|
||||
SRCS
|
||||
adc.cpp
|
||||
)
|
||||
px4_add_library(arch_adc
|
||||
adc.cpp
|
||||
)
|
|
@ -0,0 +1,182 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <board_config.h>
|
||||
#include <drivers/drv_adc.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include <nuttx/analog/adc.h>
|
||||
#include <kinetis.h>
|
||||
#include <chip/kinetis_sim.h>
|
||||
#include <chip/kinetis_adc.h>
|
||||
|
||||
|
||||
#define _REG(_addr) (*(volatile uint32_t *)(_addr))
|
||||
|
||||
/* ADC register accessors */
|
||||
|
||||
#define REG(a, _reg) _REG(KINETIS_ADC##a##_BASE + (_reg))
|
||||
|
||||
#define rSC1A(adc) REG(adc, KINETIS_ADC_SC1A_OFFSET) /* ADC status and control registers 1 */
|
||||
#define rSC1B(adc) REG(adc, KINETIS_ADC_SC1B_OFFSET) /* ADC status and control registers 1 */
|
||||
#define rCFG1(adc) REG(adc, KINETIS_ADC_CFG1_OFFSET) /* ADC configuration register 1 */
|
||||
#define rCFG2(adc) REG(adc, KINETIS_ADC_CFG2_OFFSET) /* Configuration register 2 */
|
||||
#define rRA(adc) REG(adc, KINETIS_ADC_RA_OFFSET) /* ADC data result register */
|
||||
#define rRB(adc) REG(adc, KINETIS_ADC_RB_OFFSET) /* ADC data result register */
|
||||
#define rCV1(adc) REG(adc, KINETIS_ADC_CV1_OFFSET) /* Compare value registers */
|
||||
#define rCV2(adc) REG(adc, KINETIS_ADC_CV2_OFFSET) /* Compare value registers */
|
||||
#define rSC2(adc) REG(adc, KINETIS_ADC_SC2_OFFSET) /* Status and control register 2 */
|
||||
#define rSC3(adc) REG(adc, KINETIS_ADC_SC3_OFFSET) /* Status and control register 3 */
|
||||
#define rOFS(adc) REG(adc, KINETIS_ADC_OFS_OFFSET) /* ADC offset correction register */
|
||||
#define rPG(adc) REG(adc, KINETIS_ADC_PG_OFFSET) /* ADC plus-side gain register */
|
||||
#define rMG(adc) REG(adc, KINETIS_ADC_MG_OFFSET) /* ADC minus-side gain register */
|
||||
#define rCLPD(adc) REG(adc, KINETIS_ADC_CLPD_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLPS(adc) REG(adc, KINETIS_ADC_CLPS_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP4(adc) REG(adc, KINETIS_ADC_CLP4_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP3(adc) REG(adc, KINETIS_ADC_CLP3_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP2(adc) REG(adc, KINETIS_ADC_CLP2_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP1(adc) REG(adc, KINETIS_ADC_CLP1_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP0(adc) REG(adc, KINETIS_ADC_CLP0_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLMD(adc) REG(adc, KINETIS_ADC_CLMD_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLMS(adc) REG(adc, KINETIS_ADC_CLMS_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM4(adc) REG(adc, KINETIS_ADC_CLM4_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM3(adc) REG(adc, KINETIS_ADC_CLM3_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM2(adc) REG(adc, KINETIS_ADC_CLM2_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM1(adc) REG(adc, KINETIS_ADC_CLM1_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM0(adc) REG(adc, KINETIS_ADC_CLM0_OFFSET) /* ADC minus-side general calibration value register */
|
||||
|
||||
int px4_arch_adc_init(uint32_t base_address)
|
||||
{
|
||||
/* Input is Buss Clock 56 Mhz We will use /8 for 7 Mhz */
|
||||
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
|
||||
_REG(KINETIS_SIM_SCGC3) |= SIM_SCGC3_ADC1;
|
||||
rCFG1(1) = ADC_CFG1_ADICLK_BUSCLK | ADC_CFG1_MODE_1213BIT | ADC_CFG1_ADIV_DIV8;
|
||||
rCFG2(1) = 0;
|
||||
rSC2(1) = ADC_SC2_REFSEL_DEFAULT;
|
||||
|
||||
px4_leave_critical_section(flags);
|
||||
|
||||
/* Clear the CALF and begin the calibration */
|
||||
|
||||
rSC3(1) = ADC_SC3_CAL | ADC_SC3_CALF;
|
||||
|
||||
while ((rSC1A(1) & ADC_SC1_COCO) == 0) {
|
||||
usleep(100);
|
||||
|
||||
if (rSC3(1) & ADC_SC3_CALF) {
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
/* dummy read to clear COCO of calibration */
|
||||
|
||||
int32_t r = rRA(1);
|
||||
|
||||
/* Check the state of CALF at the end of calibration */
|
||||
|
||||
if (rSC3(1) & ADC_SC3_CALF) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Calculate the calibration values for single ended positive */
|
||||
|
||||
r = rCLP0(1) + rCLP1(1) + rCLP2(1) + rCLP3(1) + rCLP4(1) + rCLPS(1) ;
|
||||
r = 0x8000U | (r >> 1U);
|
||||
rPG(1) = r;
|
||||
|
||||
/* Calculate the calibration values for double ended Negitive */
|
||||
|
||||
r = rCLM0(1) + rCLM1(1) + rCLM2(1) + rCLM3(1) + rCLM4(1) + rCLMS(1) ;
|
||||
r = 0x8000U | (r >> 1U);
|
||||
rMG(1) = r;
|
||||
|
||||
/* kick off a sample and wait for it to complete */
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
rSC1A(1) = ADC_SC1_ADCH(ADC_SC1_ADCH_TEMP);
|
||||
|
||||
while (!(rSC1A(1) & ADC_SC1_COCO)) {
|
||||
|
||||
/* don't wait for more than 500us, since that means something broke - should reset here if we see this */
|
||||
if ((hrt_absolute_time() - now) > 500) {
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void px4_arch_adc_uninit(uint32_t base_address)
|
||||
{
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
_REG(KINETIS_SIM_SCGC3) &= ~SIM_SCGC3_ADC1;
|
||||
px4_leave_critical_section(flags);
|
||||
}
|
||||
|
||||
uint16_t px4_arch_adc_sample(uint32_t base_address, unsigned channel)
|
||||
{
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
|
||||
/* clear any previous COCC */
|
||||
rRA(1);
|
||||
|
||||
/* run a single conversion right now - should take about 35 cycles (5 microseconds) max */
|
||||
rSC1A(1) = ADC_SC1_ADCH(channel);
|
||||
|
||||
/* wait for the conversion to complete */
|
||||
const hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
while (!(rSC1A(1) & ADC_SC1_COCO)) {
|
||||
|
||||
/* don't wait for more than 10us, since that means something broke - should reset here if we see this */
|
||||
if ((hrt_absolute_time() - now) > 10) {
|
||||
px4_leave_critical_section(flags);
|
||||
return 0xffff;
|
||||
}
|
||||
}
|
||||
|
||||
/* read the result and clear EOC */
|
||||
uint16_t result = rRA(1);
|
||||
|
||||
px4_leave_critical_section(flags);
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
uint32_t px4_arch_adc_temp_sensor_mask()
|
||||
{
|
||||
return 1 << (ADC_SC1_ADCH_TEMP >> ADC_SC1_ADCH_SHIFT);
|
||||
}
|
||||
|
|
@ -0,0 +1,41 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#define SYSTEM_ADC_BASE 0 // not used on kinetis
|
||||
|
||||
#include "../../common/px4_platform_adc.h"
|
||||
|
||||
|
|
@ -32,6 +32,7 @@
|
|||
############################################################################
|
||||
|
||||
|
||||
add_subdirectory(../common/adc adc)
|
||||
add_subdirectory(../common/tone_alarm tone_alarm)
|
||||
|
||||
|
||||
|
|
|
@ -0,0 +1,36 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
#include "../common/px4_arch_adc.h"
|
||||
|
|
@ -0,0 +1,36 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015-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(arch_adc
|
||||
adc.cpp
|
||||
)
|
|
@ -0,0 +1,229 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <board_config.h>
|
||||
#include <drivers/drv_adc.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include <stm32_adc.h>
|
||||
#include <stm32_gpio.h>
|
||||
|
||||
/*
|
||||
* Register accessors.
|
||||
* For now, no reason not to just use ADC1.
|
||||
*/
|
||||
#define REG(base, _reg) (*(volatile uint32_t *)((base) + (_reg)))
|
||||
|
||||
#define rSR(base) REG((base), STM32_ADC_SR_OFFSET)
|
||||
#define rCR1(base) REG((base), STM32_ADC_CR1_OFFSET)
|
||||
#define rCR2(base) REG((base), STM32_ADC_CR2_OFFSET)
|
||||
#define rSMPR1(base) REG((base), STM32_ADC_SMPR1_OFFSET)
|
||||
#define rSMPR2(base) REG((base), STM32_ADC_SMPR2_OFFSET)
|
||||
#define rJOFR1(base) REG((base), STM32_ADC_JOFR1_OFFSET)
|
||||
#define rJOFR2(base) REG((base), STM32_ADC_JOFR2_OFFSET)
|
||||
#define rJOFR3(base) REG((base), STM32_ADC_JOFR3_OFFSET)
|
||||
#define rJOFR4(base) REG((base), STM32_ADC_JOFR4_OFFSET)
|
||||
#define rHTR(base) REG((base), STM32_ADC_HTR_OFFSET)
|
||||
#define rLTR(base) REG((base), STM32_ADC_LTR_OFFSET)
|
||||
#define rSQR1(base) REG((base), STM32_ADC_SQR1_OFFSET)
|
||||
#define rSQR2(base) REG((base), STM32_ADC_SQR2_OFFSET)
|
||||
#define rSQR3(base) REG((base), STM32_ADC_SQR3_OFFSET)
|
||||
#define rJSQR(base) REG((base), STM32_ADC_JSQR_OFFSET)
|
||||
#define rJDR1(base) REG((base), STM32_ADC_JDR1_OFFSET)
|
||||
#define rJDR2(base) REG((base), STM32_ADC_JDR2_OFFSET)
|
||||
#define rJDR3(base) REG((base), STM32_ADC_JDR3_OFFSET)
|
||||
#define rJDR4(base) REG((base), STM32_ADC_JDR4_OFFSET)
|
||||
#define rDR(base) REG((base), STM32_ADC_DR_OFFSET)
|
||||
|
||||
|
||||
|
||||
#ifdef STM32_ADC_CCR
|
||||
# define rCCR(base) REG((base), STM32_ADC_CCR_OFFSET)
|
||||
|
||||
/* Assuming VDC 2.4 - 3.6 */
|
||||
|
||||
#define ADC_MAX_FADC 36000000
|
||||
|
||||
# if STM32_PCLK2_FREQUENCY/2 <= ADC_MAX_FADC
|
||||
# define ADC_CCR_ADCPRE_DIV ADC_CCR_ADCPRE_DIV2
|
||||
# elif STM32_PCLK2_FREQUENCY/4 <= ADC_MAX_FADC
|
||||
# define ADC_CCR_ADCPRE_DIV ADC_CCR_ADCPRE_DIV4
|
||||
# elif STM32_PCLK2_FREQUENCY/6 <= ADC_MAX_FADC
|
||||
# define ADC_CCR_ADCPRE_DIV ADC_CCR_ADCPRE_DIV6
|
||||
# elif STM32_PCLK2_FREQUENCY/8 <= ADC_MAX_FADC
|
||||
# define ADC_CCR_ADCPRE_DIV ADC_CCR_ADCPRE_DIV8
|
||||
# else
|
||||
# error "ADC PCLK2 too high - no divisor found "
|
||||
# endif
|
||||
#endif
|
||||
|
||||
|
||||
int px4_arch_adc_init(uint32_t base_address)
|
||||
{
|
||||
/* Perform ADC init once per ADC */
|
||||
|
||||
static uint32_t once[SYSTEM_ADC_COUNT] {};
|
||||
|
||||
uint32_t *free = nullptr;
|
||||
|
||||
for (uint32_t i = 0; i < SYSTEM_ADC_COUNT; i++) {
|
||||
if (once[i] == base_address) {
|
||||
|
||||
/* This one was done already */
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/* Use first free slot */
|
||||
|
||||
if (free == nullptr && once[i] == 0) {
|
||||
free = &once[i];
|
||||
}
|
||||
}
|
||||
|
||||
if (free == nullptr) {
|
||||
|
||||
/* ADC misconfigured SYSTEM_ADC_COUNT too small */;
|
||||
|
||||
PANIC();
|
||||
}
|
||||
|
||||
*free = base_address;
|
||||
|
||||
/* do calibration if supported */
|
||||
#ifdef ADC_CR2_CAL
|
||||
rCR2(base_address) |= ADC_CR2_CAL;
|
||||
px4_usleep(100);
|
||||
|
||||
if (rCR2(base_address) & ADC_CR2_CAL) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/* arbitrarily configure all channels for 55 cycle sample time */
|
||||
rSMPR1(base_address) = 0b00000011011011011011011011011011;
|
||||
rSMPR2(base_address) = 0b00011011011011011011011011011011;
|
||||
|
||||
/* XXX for F2/4, might want to select 12-bit mode? */
|
||||
rCR1(base_address) = 0;
|
||||
|
||||
/* enable the temperature sensor / Vrefint channel if supported*/
|
||||
rCR2(base_address) =
|
||||
#ifdef ADC_CR2_TSVREFE
|
||||
/* enable the temperature sensor in CR2 */
|
||||
ADC_CR2_TSVREFE |
|
||||
#endif
|
||||
0;
|
||||
|
||||
/* Soc have CCR */
|
||||
#ifdef STM32_ADC_CCR
|
||||
# ifdef ADC_CCR_TSVREFE
|
||||
/* enable temperature sensor in CCR */
|
||||
rCCR(base_address) = ADC_CCR_TSVREFE | ADC_CCR_ADCPRE_DIV;
|
||||
# else
|
||||
rCCR(base_address) = ADC_CCR_ADCPRE_DIV;
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/* configure for a single-channel sequence */
|
||||
rSQR1(base_address) = 0;
|
||||
rSQR2(base_address) = 0;
|
||||
rSQR3(base_address) = 0; /* will be updated with the channel each tick */
|
||||
|
||||
/* power-cycle the ADC and turn it on */
|
||||
rCR2(base_address) &= ~ADC_CR2_ADON;
|
||||
px4_usleep(10);
|
||||
rCR2(base_address) |= ADC_CR2_ADON;
|
||||
px4_usleep(10);
|
||||
rCR2(base_address) |= ADC_CR2_ADON;
|
||||
px4_usleep(10);
|
||||
|
||||
/* kick off a sample and wait for it to complete */
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
rCR2(base_address) |= ADC_CR2_SWSTART;
|
||||
|
||||
while (!(rSR(base_address) & ADC_SR_EOC)) {
|
||||
|
||||
/* don't wait for more than 500us, since that means something broke - should reset here if we see this */
|
||||
if ((hrt_absolute_time() - now) > 500) {
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void px4_arch_adc_uninit(uint32_t base_address)
|
||||
{
|
||||
// nothing to do
|
||||
}
|
||||
|
||||
uint16_t px4_arch_adc_sample(uint32_t base_address, unsigned channel)
|
||||
{
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
|
||||
/* clear any previous EOC */
|
||||
if (rSR(base_address) & ADC_SR_EOC) {
|
||||
rSR(base_address) &= ~ADC_SR_EOC;
|
||||
}
|
||||
|
||||
/* run a single conversion right now - should take about 60 cycles (a few microseconds) max */
|
||||
rSQR3(base_address) = channel;
|
||||
rCR2(base_address) |= ADC_CR2_SWSTART;
|
||||
|
||||
/* wait for the conversion to complete */
|
||||
const hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
while (!(rSR(base_address) & ADC_SR_EOC)) {
|
||||
|
||||
/* don't wait for more than 50us, since that means something broke - should reset here if we see this */
|
||||
if ((hrt_absolute_time() - now) > 50) {
|
||||
px4_leave_critical_section(flags);
|
||||
return 0xffff;
|
||||
}
|
||||
}
|
||||
|
||||
/* read the result and clear EOC */
|
||||
uint16_t result = rDR(base_address);
|
||||
|
||||
px4_leave_critical_section(flags);
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
uint32_t px4_arch_adc_temp_sensor_mask()
|
||||
{
|
||||
return 1 << 16;
|
||||
}
|
||||
|
|
@ -0,0 +1,57 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
|
||||
/* Historically PX4 used one ADC1 With FMUvnX this has changes.
|
||||
* These defines maintain compatibility while allowing the
|
||||
* new boards to override the ADC used from HW VER/REV and
|
||||
* the system one.
|
||||
*
|
||||
* Depending on HW configuration (VER/REV POP options) hardware detection
|
||||
* may or may NOT initialize a given ADC. SYSTEM_ADC_COUNT is used to size the
|
||||
* singleton array to ensure this is only done once per ADC.
|
||||
*/
|
||||
|
||||
#if !defined(HW_REV_VER_ADC_BASE)
|
||||
# define HW_REV_VER_ADC_BASE STM32_ADC1_BASE
|
||||
#endif
|
||||
|
||||
#if !defined(SYSTEM_ADC_BASE)
|
||||
# define SYSTEM_ADC_BASE STM32_ADC1_BASE
|
||||
#endif
|
||||
|
||||
#include "../../common/px4_platform_adc.h"
|
||||
|
|
@ -32,6 +32,7 @@
|
|||
############################################################################
|
||||
|
||||
|
||||
add_subdirectory(../stm32_common/adc adc)
|
||||
add_subdirectory(../stm32_common/tone_alarm tone_alarm)
|
||||
|
||||
add_subdirectory(px4io_serial)
|
||||
|
|
|
@ -0,0 +1,36 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
#include "../stm32_common/px4_arch_adc.h"
|
||||
|
|
@ -32,6 +32,7 @@
|
|||
############################################################################
|
||||
|
||||
|
||||
add_subdirectory(../stm32_common/adc adc)
|
||||
add_subdirectory(../stm32_common/tone_alarm tone_alarm)
|
||||
|
||||
add_subdirectory(px4io_serial)
|
||||
|
|
|
@ -0,0 +1,36 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
#include "../stm32_common/px4_arch_adc.h"
|
||||
|
|
@ -1,6 +1,6 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
# 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
|
||||
|
@ -36,4 +36,6 @@ px4_add_module(
|
|||
MAIN adc
|
||||
SRCS
|
||||
adc.cpp
|
||||
DEPENDS
|
||||
arch_adc
|
||||
)
|
|
@ -34,15 +34,10 @@
|
|||
/**
|
||||
* @file adc.cpp
|
||||
*
|
||||
* Driver for the STM32 ADC.
|
||||
* Driver for an ADC.
|
||||
*
|
||||
* This is a low-rate driver, designed for sampling things like voltages
|
||||
* and so forth. It avoids the gross complexity of the NuttX ADC driver.
|
||||
*/
|
||||
|
||||
#include <stm32_adc.h>
|
||||
#include <stm32_gpio.h>
|
||||
|
||||
#include <drivers/drv_adc.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <lib/cdev/CDev.hpp>
|
||||
|
@ -54,60 +49,15 @@
|
|||
#include <uORB/topics/adc_report.h>
|
||||
#include <uORB/topics/system_power.h>
|
||||
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
#if defined(ADC_CHANNELS)
|
||||
#ifndef ADC_CHANNELS
|
||||
#error "board needs to define ADC_CHANNELS to use this driver"
|
||||
#endif
|
||||
|
||||
#define ADC_TOTAL_CHANNELS 32
|
||||
|
||||
/*
|
||||
* Register accessors.
|
||||
* For now, no reason not to just use ADC1.
|
||||
*/
|
||||
#define REG(base, _reg) (*(volatile uint32_t *)((base) + (_reg)))
|
||||
|
||||
#define rSR(base) REG((base), STM32_ADC_SR_OFFSET)
|
||||
#define rCR1(base) REG((base), STM32_ADC_CR1_OFFSET)
|
||||
#define rCR2(base) REG((base), STM32_ADC_CR2_OFFSET)
|
||||
#define rSMPR1(base) REG((base), STM32_ADC_SMPR1_OFFSET)
|
||||
#define rSMPR2(base) REG((base), STM32_ADC_SMPR2_OFFSET)
|
||||
#define rJOFR1(base) REG((base), STM32_ADC_JOFR1_OFFSET)
|
||||
#define rJOFR2(base) REG((base), STM32_ADC_JOFR2_OFFSET)
|
||||
#define rJOFR3(base) REG((base), STM32_ADC_JOFR3_OFFSET)
|
||||
#define rJOFR4(base) REG((base), STM32_ADC_JOFR4_OFFSET)
|
||||
#define rHTR(base) REG((base), STM32_ADC_HTR_OFFSET)
|
||||
#define rLTR(base) REG((base), STM32_ADC_LTR_OFFSET)
|
||||
#define rSQR1(base) REG((base), STM32_ADC_SQR1_OFFSET)
|
||||
#define rSQR2(base) REG((base), STM32_ADC_SQR2_OFFSET)
|
||||
#define rSQR3(base) REG((base), STM32_ADC_SQR3_OFFSET)
|
||||
#define rJSQR(base) REG((base), STM32_ADC_JSQR_OFFSET)
|
||||
#define rJDR1(base) REG((base), STM32_ADC_JDR1_OFFSET)
|
||||
#define rJDR2(base) REG((base), STM32_ADC_JDR2_OFFSET)
|
||||
#define rJDR3(base) REG((base), STM32_ADC_JDR3_OFFSET)
|
||||
#define rJDR4(base) REG((base), STM32_ADC_JDR4_OFFSET)
|
||||
#define rDR(base) REG((base), STM32_ADC_DR_OFFSET)
|
||||
|
||||
|
||||
|
||||
#ifdef STM32_ADC_CCR
|
||||
# define rCCR(base) REG((base), STM32_ADC_CCR_OFFSET)
|
||||
|
||||
/* Assuming VDC 2.4 - 3.6 */
|
||||
|
||||
#define ADC_MAX_FADC 36000000
|
||||
|
||||
# if STM32_PCLK2_FREQUENCY/2 <= ADC_MAX_FADC
|
||||
# define ADC_CCR_ADCPRE_DIV ADC_CCR_ADCPRE_DIV2
|
||||
# elif STM32_PCLK2_FREQUENCY/4 <= ADC_MAX_FADC
|
||||
# define ADC_CCR_ADCPRE_DIV ADC_CCR_ADCPRE_DIV4
|
||||
# elif STM32_PCLK2_FREQUENCY/6 <= ADC_MAX_FADC
|
||||
# define ADC_CCR_ADCPRE_DIV ADC_CCR_ADCPRE_DIV6
|
||||
# elif STM32_PCLK2_FREQUENCY/8 <= ADC_MAX_FADC
|
||||
# define ADC_CCR_ADCPRE_DIV ADC_CCR_ADCPRE_DIV8
|
||||
# else
|
||||
# error "ADC PCLK2 too high - no divisor found "
|
||||
# endif
|
||||
#endif
|
||||
|
||||
class ADC : public cdev::CDev, public px4::ScheduledWorkItem
|
||||
{
|
||||
|
@ -131,8 +81,7 @@ private:
|
|||
* Sample a single channel and return the measured value.
|
||||
*
|
||||
* @param channel The channel to sample.
|
||||
* @return The sampled value, or 0xffff if
|
||||
* sampling failed.
|
||||
* @return The sampled value, or 0xffff if sampling failed.
|
||||
*/
|
||||
uint16_t sample(unsigned channel);
|
||||
|
||||
|
@ -159,7 +108,7 @@ ADC::ADC(uint32_t base_address, uint32_t channels) :
|
|||
_base_address(base_address)
|
||||
{
|
||||
/* always enable the temperature sensor */
|
||||
channels |= 1 << 16;
|
||||
channels |= px4_arch_adc_temp_sensor_mask();
|
||||
|
||||
/* allocate the sample array */
|
||||
for (unsigned i = 0; i < ADC_TOTAL_CHANNELS; i++) {
|
||||
|
@ -195,108 +144,13 @@ ADC::~ADC()
|
|||
}
|
||||
|
||||
perf_free(_sample_perf);
|
||||
}
|
||||
|
||||
int board_adc_init(uint32_t base_address)
|
||||
{
|
||||
/* Perform ADC init once per ADC */
|
||||
|
||||
static uint32_t once[SYSTEM_ADC_COUNT] {};
|
||||
|
||||
uint32_t *free = nullptr;
|
||||
|
||||
for (uint32_t i = 0; i < SYSTEM_ADC_COUNT; i++) {
|
||||
if (once[i] == base_address) {
|
||||
|
||||
/* This one was done already */
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/* Use first free slot */
|
||||
|
||||
if (free == nullptr && once[i] == 0) {
|
||||
free = &once[i];
|
||||
}
|
||||
}
|
||||
|
||||
if (free == nullptr) {
|
||||
|
||||
/* ADC misconfigured SYSTEM_ADC_COUNT too small */;
|
||||
|
||||
PANIC();
|
||||
}
|
||||
|
||||
*free = base_address;
|
||||
|
||||
/* do calibration if supported */
|
||||
#ifdef ADC_CR2_CAL
|
||||
rCR2(base_address) |= ADC_CR2_CAL;
|
||||
px4_usleep(100);
|
||||
|
||||
if (rCR2(base_address) & ADC_CR2_CAL) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/* arbitrarily configure all channels for 55 cycle sample time */
|
||||
rSMPR1(base_address) = 0b00000011011011011011011011011011;
|
||||
rSMPR2(base_address) = 0b00011011011011011011011011011011;
|
||||
|
||||
/* XXX for F2/4, might want to select 12-bit mode? */
|
||||
rCR1(base_address) = 0;
|
||||
|
||||
/* enable the temperature sensor / Vrefint channel if supported*/
|
||||
rCR2(base_address) =
|
||||
#ifdef ADC_CR2_TSVREFE
|
||||
/* enable the temperature sensor in CR2 */
|
||||
ADC_CR2_TSVREFE |
|
||||
#endif
|
||||
0;
|
||||
|
||||
/* Soc have CCR */
|
||||
#ifdef STM32_ADC_CCR
|
||||
# ifdef ADC_CCR_TSVREFE
|
||||
/* enable temperature sensor in CCR */
|
||||
rCCR(base_address) = ADC_CCR_TSVREFE | ADC_CCR_ADCPRE_DIV;
|
||||
# else
|
||||
rCCR(base_address) = ADC_CCR_ADCPRE_DIV;
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/* configure for a single-channel sequence */
|
||||
rSQR1(base_address) = 0;
|
||||
rSQR2(base_address) = 0;
|
||||
rSQR3(base_address) = 0; /* will be updated with the channel each tick */
|
||||
|
||||
/* power-cycle the ADC and turn it on */
|
||||
rCR2(base_address) &= ~ADC_CR2_ADON;
|
||||
px4_usleep(10);
|
||||
rCR2(base_address) |= ADC_CR2_ADON;
|
||||
px4_usleep(10);
|
||||
rCR2(base_address) |= ADC_CR2_ADON;
|
||||
px4_usleep(10);
|
||||
|
||||
/* kick off a sample and wait for it to complete */
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
rCR2(base_address) |= ADC_CR2_SWSTART;
|
||||
|
||||
while (!(rSR(base_address) & ADC_SR_EOC)) {
|
||||
|
||||
/* don't wait for more than 500us, since that means something broke - should reset here if we see this */
|
||||
if ((hrt_absolute_time() - now) > 500) {
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
return OK;
|
||||
px4_arch_adc_uninit(_base_address);
|
||||
}
|
||||
|
||||
int
|
||||
ADC::init()
|
||||
{
|
||||
int rv = board_adc_init(_base_address);
|
||||
int rv = px4_arch_adc_init(_base_address);
|
||||
|
||||
if (rv < 0) {
|
||||
PX4_DEBUG("sample timeout");
|
||||
|
@ -468,44 +322,11 @@ ADC::update_system_power(hrt_abstime now)
|
|||
#endif // BOARD_ADC_USB_CONNECTED
|
||||
}
|
||||
|
||||
uint16_t board_adc_sample(uint32_t base_address, unsigned channel)
|
||||
{
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
|
||||
/* clear any previous EOC */
|
||||
if (rSR(base_address) & ADC_SR_EOC) {
|
||||
rSR(base_address) &= ~ADC_SR_EOC;
|
||||
}
|
||||
|
||||
/* run a single conversion right now - should take about 60 cycles (a few microseconds) max */
|
||||
rSQR3(base_address) = channel;
|
||||
rCR2(base_address) |= ADC_CR2_SWSTART;
|
||||
|
||||
/* wait for the conversion to complete */
|
||||
const hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
while (!(rSR(base_address) & ADC_SR_EOC)) {
|
||||
|
||||
/* don't wait for more than 50us, since that means something broke - should reset here if we see this */
|
||||
if ((hrt_absolute_time() - now) > 50) {
|
||||
px4_leave_critical_section(flags);
|
||||
return 0xffff;
|
||||
}
|
||||
}
|
||||
|
||||
/* read the result and clear EOC */
|
||||
uint16_t result = rDR(base_address);
|
||||
|
||||
px4_leave_critical_section(flags);
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
uint16_t
|
||||
ADC::sample(unsigned channel)
|
||||
{
|
||||
perf_begin(_sample_perf);
|
||||
uint16_t result = board_adc_sample(_base_address, channel);
|
||||
uint16_t result = px4_arch_adc_sample(_base_address, channel);
|
||||
|
||||
if (result == 0xffff) {
|
||||
PX4_ERR("sample timeout");
|
||||
|
@ -562,7 +383,6 @@ int
|
|||
adc_main(int argc, char *argv[])
|
||||
{
|
||||
if (g_adc == nullptr) {
|
||||
/* XXX this hardcodes the default channel set for the board in board_config.h - should be configurable */
|
||||
g_adc = new ADC(SYSTEM_ADC_BASE, ADC_CHANNELS);
|
||||
|
||||
if (g_adc == nullptr) {
|
||||
|
@ -585,4 +405,3 @@ adc_main(int argc, char *argv[])
|
|||
|
||||
return 0;
|
||||
}
|
||||
#endif
|
|
@ -196,30 +196,6 @@
|
|||
# error Unsuported BOARD_NUMBER_BRICKS number.
|
||||
#endif
|
||||
|
||||
/* Historically PX4 used one ADC1 With FMUvnX this has changes.
|
||||
* These defines maintain compatibility while allowing the
|
||||
* new boards to override the ADC used from HW VER/REV and
|
||||
* the system one.
|
||||
*
|
||||
* Depending on HW configuration (VER/REV POP options) hardware detection
|
||||
* may or may NOT initialize a given ADC. SYSTEM_ADC_COUNT is used to size the
|
||||
* singleton array to ensure this is only done once per ADC.
|
||||
*/
|
||||
|
||||
#if !defined(HW_REV_VER_ADC_BASE)
|
||||
# define HW_REV_VER_ADC_BASE STM32_ADC1_BASE
|
||||
#endif
|
||||
|
||||
#if !defined(SYSTEM_ADC_BASE)
|
||||
# define SYSTEM_ADC_BASE STM32_ADC1_BASE
|
||||
#endif
|
||||
|
||||
#if SYSTEM_ADC_BASE == HW_REV_VER_ADC_BASE
|
||||
# define SYSTEM_ADC_COUNT 1
|
||||
#else
|
||||
# define SYSTEM_ADC_COUNT 2
|
||||
#endif
|
||||
|
||||
/* Choose the source for ADC_SCALED_V5_SENSE */
|
||||
#if defined(ADC_5V_RAIL_SENSE)
|
||||
#define ADC_SCALED_V5_SENSE ADC_5V_RAIL_SENSE
|
||||
|
|
|
@ -45,40 +45,6 @@
|
|||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_adc_init
|
||||
*
|
||||
* Description:
|
||||
* boards may provide this function to allow complex version-ing.
|
||||
*
|
||||
* Input Parameters:
|
||||
* base_address - base address of the ADC
|
||||
*
|
||||
* Returned Value:
|
||||
*
|
||||
* OK, or -1 if the function failed.
|
||||
*/
|
||||
|
||||
__EXPORT int board_adc_init(uint32_t base_address);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_adc_sample
|
||||
*
|
||||
* Description:
|
||||
* boards provide this function to allow complex version-ing.
|
||||
*
|
||||
* Input Parameters:
|
||||
* base_address - base address of the ADC
|
||||
* channel - The number of the adc channel to read.
|
||||
*
|
||||
* Returned Value:
|
||||
* The ADC DN read for the channel or 0xffff if there
|
||||
* is an error reading the channel.
|
||||
*/
|
||||
|
||||
__EXPORT uint16_t board_adc_sample(uint32_t base_address, unsigned channel);
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_gpio_init
|
||||
*
|
||||
|
|
|
@ -39,5 +39,7 @@ add_library(drivers_boards_common_arch
|
|||
board_critmon.c
|
||||
)
|
||||
add_dependencies(drivers_boards_common_arch prebuild_targets)
|
||||
add_dependencies(drivers_boards_common_arch arch_adc)
|
||||
target_compile_options(drivers_boards_common_arch PRIVATE -Wno-cast-align) # TODO: fix and enable
|
||||
target_link_libraries(drivers_boards_common_arch PRIVATE nuttx_arch)
|
||||
target_link_libraries(drivers_boards_common_arch PRIVATE arch_adc)
|
||||
|
|
|
@ -37,6 +37,8 @@
|
|||
* Implementation of STM32 based Board Hardware Revision and Version ID API
|
||||
*/
|
||||
|
||||
#include <drivers/drv_adc.h>
|
||||
#include <px4_arch_adc.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include "board_config.h"
|
||||
|
@ -199,11 +201,11 @@ static int read_id_dn(int *id, uint32_t gpio_drive, uint32_t gpio_sense, int adc
|
|||
|
||||
/* Yes - Fire up the ADC (it has once control) */
|
||||
|
||||
if (board_adc_init(HW_REV_VER_ADC_BASE) == OK) {
|
||||
if (px4_arch_adc_init(HW_REV_VER_ADC_BASE) == OK) {
|
||||
|
||||
/* Read the value */
|
||||
for (unsigned av = 0; av < samples; av++) {
|
||||
dn = board_adc_sample(HW_REV_VER_ADC_BASE, adc_channel);
|
||||
dn = px4_arch_adc_sample(HW_REV_VER_ADC_BASE, adc_channel);
|
||||
|
||||
if (dn == 0xffff) {
|
||||
break;
|
||||
|
|
|
@ -36,12 +36,11 @@
|
|||
*
|
||||
* ADC driver interface.
|
||||
*
|
||||
* This defines additional operations over and above the standard NuttX
|
||||
* ADC API.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <px4_arch_adc.h>
|
||||
#include <stdint.h>
|
||||
#include <sys/ioctl.h>
|
||||
|
||||
|
@ -60,6 +59,34 @@ typedef struct __attribute__((packed)) px4_adc_msg_t {
|
|||
|
||||
#define ADC0_DEVICE_PATH "/dev/adc0"
|
||||
|
||||
/*
|
||||
* ioctl definitions
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
/**
|
||||
* Initialize ADC hardware
|
||||
* @param base_address architecture-specific address to specify the ADC
|
||||
* @return 0 on success, <0 error otherwise
|
||||
*/
|
||||
int px4_arch_adc_init(uint32_t base_address);
|
||||
|
||||
/**
|
||||
* Uninitialize ADC hardware
|
||||
* @param base_address architecture-specific address to specify the ADC
|
||||
*/
|
||||
void px4_arch_adc_uninit(uint32_t base_address);
|
||||
|
||||
/**
|
||||
* Read a sample from the ADC
|
||||
* @param base_address architecture-specific address to specify the ADC
|
||||
* @param channel specify the channel
|
||||
* @return sample, 0xffff on error
|
||||
*/
|
||||
uint16_t px4_arch_adc_sample(uint32_t base_address, unsigned channel);
|
||||
|
||||
/**
|
||||
* Get the temperature sensor channel bitmask
|
||||
*/
|
||||
uint32_t px4_arch_adc_temp_sensor_mask(void);
|
||||
|
||||
__END_DECLS
|
||||
|
||||
|
|
|
@ -1,507 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016-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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file adc.cpp
|
||||
*
|
||||
* TODO:This is stubbed out leving the code intact to document the needed
|
||||
* mechinsm for porting.
|
||||
*
|
||||
* Driver for the Kinetis ADC.
|
||||
*
|
||||
* This is a low-rate driver, designed for sampling things like voltages
|
||||
* and so forth. It avoids the gross complexity of the NuttX ADC driver.
|
||||
*/
|
||||
|
||||
#include <nuttx/analog/adc.h>
|
||||
#include <kinetis.h>
|
||||
#include <chip/kinetis_sim.h>
|
||||
#include <chip/kinetis_adc.h>
|
||||
|
||||
#include <drivers/drv_adc.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <lib/cdev/CDev.hpp>
|
||||
#include <lib/perf/perf_counter.h>
|
||||
#include <px4_config.h>
|
||||
#include <px4_log.h>
|
||||
#include <px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <uORB/Publication.hpp>
|
||||
#include <uORB/topics/adc_report.h>
|
||||
#include <uORB/topics/system_power.h>
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
#if defined(ADC_CHANNELS)
|
||||
|
||||
#define ADC_TOTAL_CHANNELS 32
|
||||
|
||||
#define _REG(_addr) (*(volatile uint32_t *)(_addr))
|
||||
|
||||
/* ADC register accessors */
|
||||
|
||||
#define REG(a, _reg) _REG(KINETIS_ADC##a##_BASE + (_reg))
|
||||
|
||||
#define rSC1A(adc) REG(adc, KINETIS_ADC_SC1A_OFFSET) /* ADC status and control registers 1 */
|
||||
#define rSC1B(adc) REG(adc, KINETIS_ADC_SC1B_OFFSET) /* ADC status and control registers 1 */
|
||||
#define rCFG1(adc) REG(adc, KINETIS_ADC_CFG1_OFFSET) /* ADC configuration register 1 */
|
||||
#define rCFG2(adc) REG(adc, KINETIS_ADC_CFG2_OFFSET) /* Configuration register 2 */
|
||||
#define rRA(adc) REG(adc, KINETIS_ADC_RA_OFFSET) /* ADC data result register */
|
||||
#define rRB(adc) REG(adc, KINETIS_ADC_RB_OFFSET) /* ADC data result register */
|
||||
#define rCV1(adc) REG(adc, KINETIS_ADC_CV1_OFFSET) /* Compare value registers */
|
||||
#define rCV2(adc) REG(adc, KINETIS_ADC_CV2_OFFSET) /* Compare value registers */
|
||||
#define rSC2(adc) REG(adc, KINETIS_ADC_SC2_OFFSET) /* Status and control register 2 */
|
||||
#define rSC3(adc) REG(adc, KINETIS_ADC_SC3_OFFSET) /* Status and control register 3 */
|
||||
#define rOFS(adc) REG(adc, KINETIS_ADC_OFS_OFFSET) /* ADC offset correction register */
|
||||
#define rPG(adc) REG(adc, KINETIS_ADC_PG_OFFSET) /* ADC plus-side gain register */
|
||||
#define rMG(adc) REG(adc, KINETIS_ADC_MG_OFFSET) /* ADC minus-side gain register */
|
||||
#define rCLPD(adc) REG(adc, KINETIS_ADC_CLPD_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLPS(adc) REG(adc, KINETIS_ADC_CLPS_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP4(adc) REG(adc, KINETIS_ADC_CLP4_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP3(adc) REG(adc, KINETIS_ADC_CLP3_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP2(adc) REG(adc, KINETIS_ADC_CLP2_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP1(adc) REG(adc, KINETIS_ADC_CLP1_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP0(adc) REG(adc, KINETIS_ADC_CLP0_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLMD(adc) REG(adc, KINETIS_ADC_CLMD_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLMS(adc) REG(adc, KINETIS_ADC_CLMS_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM4(adc) REG(adc, KINETIS_ADC_CLM4_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM3(adc) REG(adc, KINETIS_ADC_CLM3_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM2(adc) REG(adc, KINETIS_ADC_CLM2_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM1(adc) REG(adc, KINETIS_ADC_CLM1_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM0(adc) REG(adc, KINETIS_ADC_CLM0_OFFSET) /* ADC minus-side general calibration value register */
|
||||
|
||||
class ADC : public cdev::CDev, public px4::ScheduledWorkItem
|
||||
{
|
||||
public:
|
||||
ADC(uint32_t channels);
|
||||
~ADC();
|
||||
|
||||
virtual int init();
|
||||
|
||||
virtual int ioctl(file *filp, int cmd, unsigned long arg);
|
||||
virtual ssize_t read(file *filp, char *buffer, size_t len);
|
||||
|
||||
protected:
|
||||
virtual int open_first(struct file *filp);
|
||||
virtual int close_last(struct file *filp);
|
||||
|
||||
private:
|
||||
void Run() override;
|
||||
|
||||
/**
|
||||
* Sample a single channel and return the measured value.
|
||||
*
|
||||
* @param channel The channel to sample.
|
||||
* @return The sampled value, or 0xffff if
|
||||
* sampling failed.
|
||||
*/
|
||||
uint16_t sample(unsigned channel);
|
||||
|
||||
void update_adc_report(hrt_abstime now);
|
||||
void update_system_power(hrt_abstime now);
|
||||
|
||||
|
||||
static const hrt_abstime kINTERVAL{10_ms}; /**< 100Hz base rate */
|
||||
|
||||
perf_counter_t _sample_perf;
|
||||
|
||||
unsigned _channel_count{0};
|
||||
px4_adc_msg_t *_samples{nullptr}; /**< sample buffer */
|
||||
|
||||
uORB::Publication<adc_report_s> _to_adc_report{ORB_ID(adc_report)};
|
||||
uORB::Publication<system_power_s> _to_system_power{ORB_ID(system_power)};
|
||||
};
|
||||
|
||||
ADC::ADC(uint32_t channels) :
|
||||
CDev(ADC0_DEVICE_PATH),
|
||||
ScheduledWorkItem(px4::wq_configurations::hp_default),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "adc_samples"))
|
||||
{
|
||||
/* always enable the temperature sensor */
|
||||
channels |= 1 << (ADC_SC1_ADCH_TEMP >> ADC_SC1_ADCH_SHIFT);
|
||||
|
||||
/* allocate the sample array */
|
||||
for (unsigned i = 0; i < ADC_TOTAL_CHANNELS; i++) {
|
||||
if (channels & (1 << i)) {
|
||||
_channel_count++;
|
||||
}
|
||||
}
|
||||
|
||||
if (_channel_count > PX4_MAX_ADC_CHANNELS) {
|
||||
PX4_ERR("PX4_MAX_ADC_CHANNELS is too small:is %d needed:%d", PX4_MAX_ADC_CHANNELS, _channel_count);
|
||||
}
|
||||
|
||||
_samples = new px4_adc_msg_t[_channel_count];
|
||||
|
||||
/* prefill the channel numbers in the sample array */
|
||||
if (_samples != nullptr) {
|
||||
unsigned index = 0;
|
||||
|
||||
for (unsigned i = 0; i < ADC_TOTAL_CHANNELS; i++) {
|
||||
if (channels & (1 << i)) {
|
||||
_samples[index].am_channel = i;
|
||||
_samples[index].am_data = 0;
|
||||
index++;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
ADC::~ADC()
|
||||
{
|
||||
if (_samples != nullptr) {
|
||||
delete _samples;
|
||||
}
|
||||
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
_REG(KINETIS_SIM_SCGC3) &= ~SIM_SCGC3_ADC1;
|
||||
px4_leave_critical_section(flags);
|
||||
|
||||
perf_free(_sample_perf);
|
||||
}
|
||||
|
||||
int board_adc_init()
|
||||
{
|
||||
/* Input is Buss Clock 56 Mhz We will use /8 for 7 Mhz */
|
||||
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
|
||||
_REG(KINETIS_SIM_SCGC3) |= SIM_SCGC3_ADC1;
|
||||
rCFG1(1) = ADC_CFG1_ADICLK_BUSCLK | ADC_CFG1_MODE_1213BIT | ADC_CFG1_ADIV_DIV8;
|
||||
rCFG2(1) = 0;
|
||||
rSC2(1) = ADC_SC2_REFSEL_DEFAULT;
|
||||
|
||||
px4_leave_critical_section(flags);
|
||||
|
||||
/* Clear the CALF and begin the calibration */
|
||||
|
||||
rSC3(1) = ADC_SC3_CAL | ADC_SC3_CALF;
|
||||
|
||||
while ((rSC1A(1) & ADC_SC1_COCO) == 0) {
|
||||
usleep(100);
|
||||
|
||||
if (rSC3(1) & ADC_SC3_CALF) {
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
/* dummy read to clear COCO of calibration */
|
||||
|
||||
int32_t r = rRA(1);
|
||||
|
||||
/* Check the state of CALF at the end of calibration */
|
||||
|
||||
if (rSC3(1) & ADC_SC3_CALF) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Calculate the calibration values for single ended positive */
|
||||
|
||||
r = rCLP0(1) + rCLP1(1) + rCLP2(1) + rCLP3(1) + rCLP4(1) + rCLPS(1) ;
|
||||
r = 0x8000U | (r >> 1U);
|
||||
rPG(1) = r;
|
||||
|
||||
/* Calculate the calibration values for double ended Negitive */
|
||||
|
||||
r = rCLM0(1) + rCLM1(1) + rCLM2(1) + rCLM3(1) + rCLM4(1) + rCLMS(1) ;
|
||||
r = 0x8000U | (r >> 1U);
|
||||
rMG(1) = r;
|
||||
|
||||
/* kick off a sample and wait for it to complete */
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
rSC1A(1) = ADC_SC1_ADCH(ADC_SC1_ADCH_TEMP);
|
||||
|
||||
while (!(rSC1A(1) & ADC_SC1_COCO)) {
|
||||
|
||||
/* don't wait for more than 500us, since that means something broke - should reset here if we see this */
|
||||
if ((hrt_absolute_time() - now) > 500) {
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int
|
||||
ADC::init()
|
||||
{
|
||||
int rv = board_adc_init();
|
||||
|
||||
if (rv < 0) {
|
||||
PX4_DEBUG("sample timeout");
|
||||
return rv;
|
||||
}
|
||||
|
||||
/* create the device node */
|
||||
return CDev::init();
|
||||
}
|
||||
|
||||
int
|
||||
ADC::ioctl(file *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
return -ENOTTY;
|
||||
}
|
||||
|
||||
ssize_t
|
||||
ADC::read(file *filp, char *buffer, size_t len)
|
||||
{
|
||||
const size_t maxsize = sizeof(px4_adc_msg_t) * _channel_count;
|
||||
|
||||
if (len > maxsize) {
|
||||
len = maxsize;
|
||||
}
|
||||
|
||||
/* block interrupts while copying samples to avoid racing with an update */
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
memcpy(buffer, _samples, len);
|
||||
px4_leave_critical_section(flags);
|
||||
|
||||
return len;
|
||||
}
|
||||
|
||||
int
|
||||
ADC::open_first(struct file *filp)
|
||||
{
|
||||
/* get fresh data */
|
||||
Run();
|
||||
|
||||
/* and schedule regular updates */
|
||||
ScheduleOnInterval(kINTERVAL, kINTERVAL);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
ADC::close_last(struct file *filp)
|
||||
{
|
||||
ScheduleClear();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void
|
||||
ADC::Run()
|
||||
{
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
/* scan the channel set and sample each */
|
||||
for (unsigned i = 0; i < _channel_count; i++) {
|
||||
_samples[i].am_data = sample(_samples[i].am_channel);
|
||||
}
|
||||
|
||||
update_adc_report(now);
|
||||
update_system_power(now);
|
||||
}
|
||||
|
||||
void
|
||||
ADC::update_adc_report(hrt_abstime now)
|
||||
{
|
||||
adc_report_s adc = {};
|
||||
adc.timestamp = now;
|
||||
|
||||
unsigned max_num = _channel_count;
|
||||
|
||||
if (max_num > (sizeof(adc.channel_id) / sizeof(adc.channel_id[0]))) {
|
||||
max_num = (sizeof(adc.channel_id) / sizeof(adc.channel_id[0]));
|
||||
}
|
||||
|
||||
for (unsigned i = 0; i < max_num; i++) {
|
||||
adc.channel_id[i] = _samples[i].am_channel;
|
||||
adc.channel_value[i] = _samples[i].am_data * 3.3f / 4096.0f;
|
||||
}
|
||||
|
||||
_to_adc_report.publish(adc);
|
||||
}
|
||||
|
||||
void
|
||||
ADC::update_system_power(hrt_abstime now)
|
||||
{
|
||||
#if defined (BOARD_ADC_USB_CONNECTED)
|
||||
system_power_s system_power {};
|
||||
system_power.timestamp = now;
|
||||
|
||||
#if defined(ADC_5V_RAIL_SENSE)
|
||||
|
||||
for (unsigned i = 0; i < _channel_count; i++) {
|
||||
|
||||
if (_samples[i].am_channel == ADC_5V_RAIL_SENSE) {
|
||||
// it is 2:1 scaled
|
||||
system_power.voltage5v_v = _samples[i].am_data * (6.6f / 4096.0f);
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/* Note once the board_config.h provides BOARD_ADC_USB_CONNECTED,
|
||||
* It must provide the true logic GPIO BOARD_ADC_xxxx macros.
|
||||
*/
|
||||
// these are not ADC related, but it is convenient to
|
||||
// publish these to the same topic
|
||||
|
||||
system_power.usb_connected = BOARD_ADC_USB_CONNECTED;
|
||||
/* If provided used the Valid signal from HW*/
|
||||
#if defined(BOARD_ADC_USB_VALID)
|
||||
system_power.usb_valid = BOARD_ADC_USB_VALID;
|
||||
#else
|
||||
/* If not provided then use connected */
|
||||
system_power.usb_valid = system_power.usb_connected;
|
||||
#endif
|
||||
|
||||
system_power.brick_valid = BOARD_ADC_BRICK_VALID;
|
||||
system_power.servo_valid = BOARD_ADC_SERVO_VALID;
|
||||
|
||||
// OC pins are active low
|
||||
system_power.periph_5v_oc = BOARD_ADC_PERIPH_5V_OC;
|
||||
system_power.hipower_5v_oc = BOARD_ADC_HIPOWER_5V_OC;
|
||||
|
||||
/* lazily publish */
|
||||
_to_system_power.publish(system_power);
|
||||
|
||||
#endif // BOARD_ADC_USB_CONNECTED
|
||||
}
|
||||
|
||||
uint16_t board_adc_sample(unsigned channel)
|
||||
{
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
|
||||
/* clear any previous COCC */
|
||||
rRA(1);
|
||||
|
||||
/* run a single conversion right now - should take about 35 cycles (5 microseconds) max */
|
||||
rSC1A(1) = ADC_SC1_ADCH(channel);
|
||||
|
||||
/* wait for the conversion to complete */
|
||||
const hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
while (!(rSC1A(1) & ADC_SC1_COCO)) {
|
||||
|
||||
/* don't wait for more than 10us, since that means something broke - should reset here if we see this */
|
||||
if ((hrt_absolute_time() - now) > 10) {
|
||||
px4_leave_critical_section(flags);
|
||||
return 0xffff;
|
||||
}
|
||||
}
|
||||
|
||||
/* read the result and clear EOC */
|
||||
uint16_t result = rRA(1);
|
||||
|
||||
px4_leave_critical_section(flags);
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
uint16_t
|
||||
ADC::sample(unsigned channel)
|
||||
{
|
||||
perf_begin(_sample_perf);
|
||||
uint16_t result = board_adc_sample(channel);
|
||||
|
||||
if (result == 0xffff) {
|
||||
PX4_ERR("sample timeout");
|
||||
}
|
||||
|
||||
perf_end(_sample_perf);
|
||||
return result;
|
||||
}
|
||||
|
||||
/*
|
||||
* Driver 'main' command.
|
||||
*/
|
||||
extern "C" __EXPORT int adc_main(int argc, char *argv[]);
|
||||
|
||||
namespace
|
||||
{
|
||||
ADC *g_adc{nullptr};
|
||||
|
||||
int
|
||||
test(void)
|
||||
{
|
||||
|
||||
int fd = open(ADC0_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
PX4_ERR("can't open ADC device %d", errno);
|
||||
return 1;
|
||||
}
|
||||
|
||||
for (unsigned i = 0; i < 50; i++) {
|
||||
px4_adc_msg_t data[ADC_TOTAL_CHANNELS];
|
||||
ssize_t count = read(fd, data, sizeof(data));
|
||||
|
||||
if (count < 0) {
|
||||
PX4_ERR("read error");
|
||||
return 1;
|
||||
}
|
||||
|
||||
unsigned channels = count / sizeof(data[0]);
|
||||
|
||||
for (unsigned j = 0; j < channels; j++) {
|
||||
printf("%d: %u ", data[j].am_channel, data[j].am_data);
|
||||
}
|
||||
|
||||
printf("\n");
|
||||
px4_usleep(500000);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
adc_main(int argc, char *argv[])
|
||||
{
|
||||
if (g_adc == nullptr) {
|
||||
/* XXX this hardcodes the default channel set for the board in board_config.h - should be configurable */
|
||||
g_adc = new ADC(ADC_CHANNELS);
|
||||
|
||||
if (g_adc == nullptr) {
|
||||
PX4_ERR("couldn't allocate the ADC driver");
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (g_adc->init() != OK) {
|
||||
delete g_adc;
|
||||
PX4_ERR("ADC init failed");
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
if (argc > 1) {
|
||||
if (!strcmp(argv[1], "test")) {
|
||||
return test();
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
#endif
|
Loading…
Reference in New Issue