mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
linux boards (ocpoc, bbblue, navio2) replace custom adc drivers with simple px4_arch implementation
This commit is contained in:
parent
fc9df31653
commit
d19f18d40b
4
.gitignore
vendored
4
.gitignore
vendored
@ -109,3 +109,7 @@ src/lib/parameters/px4_parameters_public.h
|
||||
src/lib/version/build_git_version.h
|
||||
src/modules/simulator/simulator_config.h
|
||||
src/systemcmds/topic_listener/listener_generated.cpp
|
||||
|
||||
# SITL
|
||||
dataman
|
||||
eeprom/
|
||||
|
||||
@ -31,4 +31,4 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_subdirectory(ocpoc_adc)
|
||||
add_subdirectory(adc)
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015-2017 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2020 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__ocpoc_adc
|
||||
MAIN ocpoc_adc
|
||||
SRCS
|
||||
ocpoc_adc.cpp
|
||||
)
|
||||
px4_add_library(arch_adc
|
||||
adc.cpp
|
||||
)
|
||||
98
boards/aerotenna/ocpoc/adc/adc.cpp
Normal file
98
boards/aerotenna/ocpoc/adc/adc.cpp
Normal file
@ -0,0 +1,98 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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 <px4_platform_common/log.h>
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <stdint.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#define ADC_SYSFS_PATH "/sys/bus/iio/devices/iio:device0"
|
||||
#define ADC_MAX_CHAN 9
|
||||
int _channels_fd[ADC_MAX_CHAN];
|
||||
|
||||
int px4_arch_adc_init(uint32_t base_address)
|
||||
{
|
||||
for (int i = 0; i < ADC_MAX_CHAN; i++) {
|
||||
_channels_fd[i] = -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void px4_arch_adc_uninit(uint32_t base_address)
|
||||
{
|
||||
for (int i = 0; i < ADC_MAX_CHAN; i++) {
|
||||
::close(_channels_fd[i]);
|
||||
_channels_fd[i] = -1;
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t px4_arch_adc_sample(uint32_t base_address, unsigned channel)
|
||||
{
|
||||
if (channel > ADC_MAX_CHAN) {
|
||||
PX4_ERR("channel %d out of range: %d", channel, ADC_MAX_CHAN);
|
||||
return UINT32_MAX; // error
|
||||
}
|
||||
|
||||
// open channel if necessary
|
||||
if (_channels_fd[channel] == -1) {
|
||||
// ADC_SYSFS_PATH
|
||||
char channel_path[strlen(ADC_SYSFS_PATH) + 20] {};
|
||||
|
||||
if (sprintf(channel_path, "%s/in_voltage%d_raw", ADC_SYSFS_PATH, channel) == -1) {
|
||||
PX4_ERR("adc channel: %d\n", channel);
|
||||
return UINT32_MAX; // error
|
||||
}
|
||||
|
||||
_channels_fd[channel] = ::open(channel_path, O_RDONLY);
|
||||
}
|
||||
|
||||
char buffer[10] {};
|
||||
|
||||
if (::pread(_channels_fd[channel], buffer, sizeof(buffer), 0) < 0) {
|
||||
PX4_ERR("read channel %d failed", channel);
|
||||
return UINT32_MAX; // error
|
||||
}
|
||||
|
||||
return atoi(buffer);
|
||||
}
|
||||
|
||||
uint32_t px4_arch_adc_dn_fullcount()
|
||||
{
|
||||
return 1 << 12; // 12 bit ADC
|
||||
}
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2019 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2020 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,8 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <drivers/drv_adc.h>
|
||||
#pragma once
|
||||
|
||||
uint32_t px4_arch_adc_dn_fullcount(void)
|
||||
{
|
||||
return 1 << 12; // 12 bit ADC
|
||||
}
|
||||
#define SYSTEM_ADC_BASE 0 // not used
|
||||
|
||||
#define px4_arch_adc_temp_sensor_mask() (0)
|
||||
@ -1,253 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file ocpoc_adc.cpp
|
||||
*
|
||||
* OcPoC ADC Driver
|
||||
*
|
||||
* @author Lianying Ji <ji@aerotenna.com>
|
||||
* @author Dave Royer <dave@aerotenna.com>
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/tasks.h>
|
||||
#include <px4_platform_common/posix.h>
|
||||
#include <drivers/drv_adc.h>
|
||||
|
||||
#include <VirtDevObj.hpp>
|
||||
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <poll.h>
|
||||
#include <string.h>
|
||||
|
||||
#define ADC_BASE_DEV_PATH "/dev/adc"
|
||||
#define ADC_VOLTAGE_PATH "/sys/bus/iio/devices/iio:device0/in_voltage8_raw"
|
||||
|
||||
__BEGIN_DECLS
|
||||
__EXPORT int ocpoc_adc_main(int argc, char *argv[]);
|
||||
__END_DECLS
|
||||
|
||||
class OcpocADC: public DriverFramework::VirtDevObj
|
||||
{
|
||||
public:
|
||||
OcpocADC();
|
||||
virtual ~OcpocADC();
|
||||
|
||||
virtual int init();
|
||||
|
||||
virtual ssize_t devRead(void *buf, size_t count) override;
|
||||
virtual int devIOCTL(unsigned long request, unsigned long arg) override;
|
||||
|
||||
protected:
|
||||
virtual void _measure() override;
|
||||
|
||||
private:
|
||||
int read(px4_adc_msg_t(*buf)[PX4_MAX_ADC_CHANNELS], unsigned int len);
|
||||
|
||||
pthread_mutex_t _samples_lock;
|
||||
px4_adc_msg_t _samples;
|
||||
};
|
||||
|
||||
OcpocADC::OcpocADC()
|
||||
: DriverFramework::VirtDevObj("ocpoc_adc", ADC0_DEVICE_PATH, ADC_BASE_DEV_PATH, 1e6 / 100)
|
||||
{
|
||||
pthread_mutex_init(&_samples_lock, NULL);
|
||||
}
|
||||
|
||||
OcpocADC::~OcpocADC()
|
||||
{
|
||||
pthread_mutex_destroy(&_samples_lock);
|
||||
}
|
||||
|
||||
void OcpocADC::_measure()
|
||||
{
|
||||
px4_adc_msg_t tmp_samples[PX4_MAX_ADC_CHANNELS];
|
||||
|
||||
int ret = read(&tmp_samples, sizeof(tmp_samples));
|
||||
|
||||
if (ret != 0) {
|
||||
PX4_ERR("ocpoc_adc_read: %d", ret);
|
||||
}
|
||||
|
||||
pthread_mutex_lock(&_samples_lock);
|
||||
memcpy(&_samples, &tmp_samples, sizeof(tmp_samples));
|
||||
pthread_mutex_unlock(&_samples_lock);
|
||||
}
|
||||
|
||||
int OcpocADC::init()
|
||||
{
|
||||
int ret;
|
||||
|
||||
ret = DriverFramework::VirtDevObj::init();
|
||||
|
||||
if (ret != PX4_OK) {
|
||||
PX4_ERR("init failed");
|
||||
return ret;
|
||||
}
|
||||
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
int OcpocADC::devIOCTL(unsigned long request, unsigned long arg)
|
||||
{
|
||||
return -ENOTTY;
|
||||
}
|
||||
|
||||
ssize_t OcpocADC::devRead(void *buf, size_t count)
|
||||
{
|
||||
const size_t maxsize = sizeof(_samples);
|
||||
int ret;
|
||||
|
||||
if (count > maxsize) {
|
||||
count = maxsize;
|
||||
}
|
||||
|
||||
ret = pthread_mutex_trylock(&_samples_lock);
|
||||
|
||||
if (ret != 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
memcpy(buf, &_samples, count);
|
||||
pthread_mutex_unlock(&_samples_lock);
|
||||
|
||||
return count;
|
||||
}
|
||||
|
||||
int OcpocADC::read(px4_adc_msg_t(*buf)[PX4_MAX_ADC_CHANNELS], unsigned int len)
|
||||
{
|
||||
uint32_t buff[1];
|
||||
int ret = 0;
|
||||
|
||||
FILE *xadc_fd = fopen(ADC_VOLTAGE_PATH, "r");
|
||||
|
||||
if (xadc_fd != NULL) {
|
||||
int ret_tmp = fscanf(xadc_fd, "%d", buff);
|
||||
|
||||
if (ret_tmp < 0) {
|
||||
ret = ret_tmp;
|
||||
}
|
||||
|
||||
fclose(xadc_fd);
|
||||
|
||||
(*buf)[0].am_data = buff[0];
|
||||
|
||||
} else {
|
||||
(*buf)[0].am_data = 0;
|
||||
ret = -1;
|
||||
}
|
||||
|
||||
(*buf)[0].am_channel = ADC_BATTERY_VOLTAGE_CHANNEL;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static OcpocADC *instance = nullptr;
|
||||
|
||||
int ocpoc_adc_main(int argc, char *argv[])
|
||||
{
|
||||
int ret;
|
||||
|
||||
if (argc < 2) {
|
||||
PX4_WARN("usage: {start|stop|test}");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
if (instance) {
|
||||
PX4_WARN("already started");
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
instance = new OcpocADC;
|
||||
|
||||
if (!instance) {
|
||||
PX4_WARN("not enough memory");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
if (instance->init() != PX4_OK) {
|
||||
delete instance;
|
||||
instance = nullptr;
|
||||
PX4_WARN("init failed");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
return PX4_OK;
|
||||
|
||||
} else if (!strcmp(argv[1], "stop")) {
|
||||
if (!instance) {
|
||||
PX4_WARN("already stopped");
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
delete instance;
|
||||
instance = nullptr;
|
||||
return PX4_OK;
|
||||
|
||||
} else if (!strcmp(argv[1], "test")) {
|
||||
if (!instance) {
|
||||
PX4_ERR("start first");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
px4_adc_msg_t adc_msgs[PX4_MAX_ADC_CHANNELS];
|
||||
|
||||
ret = instance->devRead((char *)&adc_msgs, sizeof(adc_msgs));
|
||||
|
||||
if (ret < 0) {
|
||||
PX4_ERR("ret: %s (%d)\n", strerror(ret), ret);
|
||||
return ret;
|
||||
|
||||
} else {
|
||||
PX4_INFO("ADC Data: %d", adc_msgs[0].am_data);
|
||||
}
|
||||
|
||||
return PX4_OK;
|
||||
|
||||
} else {
|
||||
PX4_WARN("action (%s) not supported", argv[1]);
|
||||
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
return PX4_OK;
|
||||
|
||||
}
|
||||
// This is a replacement for the hardcoded 4096
|
||||
uint32_t px4_arch_adc_dn_fullcount(void)
|
||||
{
|
||||
return 1 << 12; // 12 bit ADC
|
||||
}
|
||||
@ -49,15 +49,14 @@
|
||||
|
||||
#define BOARD_MAX_LEDS 1 // Number of external LED's this board has
|
||||
|
||||
/*
|
||||
* I2C busses
|
||||
*/
|
||||
|
||||
// I2C
|
||||
#define PX4_I2C_BUS_EXPANSION 2 // i2c-2: Air Data Probe or I2C Splitter
|
||||
#define PX4_I2C_BUS_EXPANSION1 4 // i2c-4: GPS/Compass #1
|
||||
#define PX4_I2C_BUS_EXPANSION2 5 // i2c-5: GPS/Compass #2
|
||||
#define PX4_I2C_BUS_EXPANSION3 3 // i2c-3: GPS/Compass #3
|
||||
|
||||
#define PX4_NUMBER_I2C_BUSES 4
|
||||
#define PX4_NUMBER_I2C_BUSES 4
|
||||
|
||||
#define PX4_I2C_BUS_LED 1
|
||||
|
||||
@ -69,10 +68,13 @@
|
||||
|
||||
#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS
|
||||
|
||||
// Battery ADC channels
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 10
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
|
||||
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
|
||||
|
||||
// ADC channels:
|
||||
#define ADC_CHANNELS (1 << 8)
|
||||
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 8
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
|
||||
|
||||
|
||||
#include <system_config.h>
|
||||
#include <px4_platform_common/board_common.h>
|
||||
|
||||
@ -31,4 +31,4 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_subdirectory(bbblue_adc)
|
||||
add_subdirectory(adc)
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2018-2019 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2020 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,10 +31,6 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
px4_add_module(
|
||||
MODULE drivers__bbblue_adc
|
||||
MAIN bbblue_adc
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
bbblue_adc.cpp
|
||||
px4_add_library(arch_adc
|
||||
adc.cpp
|
||||
)
|
||||
98
boards/beaglebone/blue/adc/adc.cpp
Normal file
98
boards/beaglebone/blue/adc/adc.cpp
Normal file
@ -0,0 +1,98 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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 <px4_platform_common/log.h>
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <stdint.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#define ADC_SYSFS_PATH "/sys/bus/iio/devices/iio:device0"
|
||||
#define ADC_MAX_CHAN 8
|
||||
int _channels_fd[ADC_MAX_CHAN];
|
||||
|
||||
int px4_arch_adc_init(uint32_t base_address)
|
||||
{
|
||||
for (int i = 0; i < ADC_MAX_CHAN; i++) {
|
||||
_channels_fd[i] = -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void px4_arch_adc_uninit(uint32_t base_address)
|
||||
{
|
||||
for (int i = 0; i < ADC_MAX_CHAN; i++) {
|
||||
::close(_channels_fd[i]);
|
||||
_channels_fd[i] = -1;
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t px4_arch_adc_sample(uint32_t base_address, unsigned channel)
|
||||
{
|
||||
if (channel > ADC_MAX_CHAN) {
|
||||
PX4_ERR("channel %d out of range: %d", channel, ADC_MAX_CHAN);
|
||||
return UINT32_MAX; // error
|
||||
}
|
||||
|
||||
// open channel if necessary
|
||||
if (_channels_fd[channel] == -1) {
|
||||
// ADC_SYSFS_PATH
|
||||
char channel_path[strlen(ADC_SYSFS_PATH) + 20] {};
|
||||
|
||||
if (sprintf(channel_path, "%s/in_voltage%d_raw", ADC_SYSFS_PATH, channel) == -1) {
|
||||
PX4_ERR("adc channel: %d\n", channel);
|
||||
return UINT32_MAX; // error
|
||||
}
|
||||
|
||||
_channels_fd[channel] = ::open(channel_path, O_RDONLY);
|
||||
}
|
||||
|
||||
char buffer[10] {};
|
||||
|
||||
if (::pread(_channels_fd[channel], buffer, sizeof(buffer), 0) < 0) {
|
||||
PX4_ERR("read channel %d failed", channel);
|
||||
return UINT32_MAX; // error
|
||||
}
|
||||
|
||||
return atoi(buffer);
|
||||
}
|
||||
|
||||
uint32_t px4_arch_adc_dn_fullcount()
|
||||
{
|
||||
return 1 << 12; // 12 bit ADC
|
||||
}
|
||||
@ -1,251 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2018 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file bbblue_adc.cpp
|
||||
*
|
||||
* BBBlue ADC Driver
|
||||
*
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/tasks.h>
|
||||
#include <px4_platform_common/posix.h>
|
||||
#include <drivers/drv_adc.h>
|
||||
|
||||
#include <VirtDevObj.hpp>
|
||||
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <poll.h>
|
||||
#include <string.h>
|
||||
|
||||
#ifdef __DF_BBBLUE
|
||||
#include <robotcontrol.h>
|
||||
#include <board_config.h>
|
||||
#endif
|
||||
|
||||
#define ADC_BASE_DEV_PATH "/dev/null"
|
||||
|
||||
#define BBBLUE_MAX_ADC_CHANNELS (6)
|
||||
#define BBBLUE_MAX_ADC_USER_CHANNELS (4)
|
||||
#define BBBLUE_ADC_DC_JACK_VOLTAGE_CHANNEL (5)
|
||||
#define BBBLUE_ADC_LIPO_BATTERY_VOLTAGE_CHANNEL (6)
|
||||
|
||||
__BEGIN_DECLS
|
||||
__EXPORT int bbblue_adc_main(int argc, char *argv[]);
|
||||
__END_DECLS
|
||||
|
||||
class BBBlueADC: public DriverFramework::VirtDevObj
|
||||
{
|
||||
public:
|
||||
BBBlueADC();
|
||||
virtual ~BBBlueADC();
|
||||
|
||||
virtual int init();
|
||||
|
||||
virtual ssize_t devRead(void *buf, size_t count) override;
|
||||
virtual int devIOCTL(unsigned long request, unsigned long arg) override;
|
||||
|
||||
protected:
|
||||
virtual void _measure() override;
|
||||
|
||||
private:
|
||||
pthread_mutex_t _samples_lock;
|
||||
px4_adc_msg_t _samples[BBBLUE_MAX_ADC_CHANNELS];
|
||||
};
|
||||
|
||||
BBBlueADC::BBBlueADC()
|
||||
: DriverFramework::VirtDevObj("bbblue_adc", ADC0_DEVICE_PATH, ADC_BASE_DEV_PATH, 1e6 / 100)
|
||||
{
|
||||
pthread_mutex_init(&_samples_lock, NULL);
|
||||
}
|
||||
|
||||
BBBlueADC::~BBBlueADC()
|
||||
{
|
||||
pthread_mutex_destroy(&_samples_lock);
|
||||
|
||||
rc_cleaning();
|
||||
}
|
||||
|
||||
void BBBlueADC::_measure()
|
||||
{
|
||||
#ifdef __DF_BBBLUE
|
||||
px4_adc_msg_t tmp_samples[BBBLUE_MAX_ADC_CHANNELS];
|
||||
|
||||
for (int i = 0; i < BBBLUE_MAX_ADC_USER_CHANNELS; ++i) {
|
||||
tmp_samples[i].am_channel = i;
|
||||
tmp_samples[i].am_data = rc_adc_read_raw(i);
|
||||
}
|
||||
|
||||
tmp_samples[BBBLUE_MAX_ADC_USER_CHANNELS].am_channel = BBBLUE_ADC_LIPO_BATTERY_VOLTAGE_CHANNEL;
|
||||
tmp_samples[BBBLUE_MAX_ADC_USER_CHANNELS].am_data = rc_adc_read_raw(BBBLUE_ADC_LIPO_BATTERY_VOLTAGE_CHANNEL);
|
||||
|
||||
tmp_samples[BBBLUE_ADC_DC_JACK_VOLTAGE_CHANNEL].am_channel = BBBLUE_ADC_DC_JACK_VOLTAGE_CHANNEL;
|
||||
tmp_samples[BBBLUE_ADC_DC_JACK_VOLTAGE_CHANNEL].am_data = rc_adc_read_raw(BBBLUE_ADC_DC_JACK_VOLTAGE_CHANNEL);
|
||||
|
||||
pthread_mutex_lock(&_samples_lock);
|
||||
memcpy(&_samples, &tmp_samples, sizeof(tmp_samples));
|
||||
pthread_mutex_unlock(&_samples_lock);
|
||||
#endif
|
||||
}
|
||||
|
||||
int BBBlueADC::init()
|
||||
{
|
||||
rc_init();
|
||||
|
||||
int ret = DriverFramework::VirtDevObj::init();
|
||||
|
||||
if (ret != PX4_OK) {
|
||||
PX4_ERR("init failed");
|
||||
return ret;
|
||||
}
|
||||
|
||||
_measure(); // start the initial conversion so that the test command right
|
||||
// after the start command can return values
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
int BBBlueADC::devIOCTL(unsigned long request, unsigned long arg)
|
||||
{
|
||||
return -ENOTTY;
|
||||
}
|
||||
|
||||
ssize_t BBBlueADC::devRead(void *buf, size_t count)
|
||||
{
|
||||
const size_t maxsize = sizeof(_samples);
|
||||
int ret;
|
||||
|
||||
if (count > maxsize) {
|
||||
count = maxsize;
|
||||
}
|
||||
|
||||
ret = pthread_mutex_trylock(&_samples_lock);
|
||||
|
||||
if (ret != 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
memcpy(buf, &_samples, count);
|
||||
pthread_mutex_unlock(&_samples_lock);
|
||||
|
||||
return count;
|
||||
}
|
||||
|
||||
static BBBlueADC *instance = nullptr;
|
||||
|
||||
int bbblue_adc_main(int argc, char *argv[])
|
||||
{
|
||||
int ret;
|
||||
|
||||
if (argc < 2) {
|
||||
PX4_WARN("usage: {start|stop|test}");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
if (instance) {
|
||||
PX4_WARN("already started");
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
instance = new BBBlueADC;
|
||||
|
||||
if (!instance) {
|
||||
PX4_WARN("not enough memory");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
if (instance->init() != PX4_OK) {
|
||||
delete instance;
|
||||
instance = nullptr;
|
||||
PX4_WARN("init failed");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
PX4_INFO("BBBlueADC started");
|
||||
return PX4_OK;
|
||||
|
||||
} else if (!strcmp(argv[1], "stop")) {
|
||||
if (!instance) {
|
||||
PX4_WARN("already stopped");
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
delete instance;
|
||||
instance = nullptr;
|
||||
return PX4_OK;
|
||||
|
||||
} else if (!strcmp(argv[1], "test")) {
|
||||
if (!instance) {
|
||||
PX4_ERR("start first");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
px4_adc_msg_t adc_msgs[BBBLUE_MAX_ADC_CHANNELS];
|
||||
|
||||
ret = instance->devRead((char *)&adc_msgs, sizeof(adc_msgs));
|
||||
|
||||
if (ret < 0) {
|
||||
PX4_ERR("ret: %s (%d)\n", strerror(ret), ret);
|
||||
return ret;
|
||||
|
||||
} else if (ret != sizeof(adc_msgs)) {
|
||||
PX4_ERR("incomplete read: %d expected %d", ret, sizeof(adc_msgs));
|
||||
return ret;
|
||||
}
|
||||
|
||||
for (int i = 0; i < BBBLUE_MAX_ADC_USER_CHANNELS; ++i) {
|
||||
PX4_INFO("ADC channel: %d; value: %d", (int)adc_msgs[i].am_channel,
|
||||
adc_msgs[i].am_data);
|
||||
}
|
||||
|
||||
for (int i = BBBLUE_MAX_ADC_USER_CHANNELS; i < BBBLUE_MAX_ADC_CHANNELS; ++i) {
|
||||
PX4_INFO("ADC channel: %d; value: %d, voltage: %6.2f V", (int)adc_msgs[i].am_channel,
|
||||
adc_msgs[i].am_data, adc_msgs[i].am_data * 1.8 / 4095.0 * 11.0);
|
||||
|
||||
}
|
||||
|
||||
return PX4_OK;
|
||||
|
||||
} else {
|
||||
PX4_WARN("action (%s) not supported", argv[1]);
|
||||
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
return PX4_OK;
|
||||
|
||||
}
|
||||
|
||||
|
||||
@ -8,6 +8,7 @@ px4_add_board(
|
||||
TOOLCHAIN arm-linux-gnueabihf
|
||||
TESTING
|
||||
DRIVERS
|
||||
adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/bmp280
|
||||
batt_smbus
|
||||
|
||||
38
boards/beaglebone/blue/include/px4_arch/adc.h
Normal file
38
boards/beaglebone/blue/include/px4_arch/adc.h
Normal file
@ -0,0 +1,38 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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
|
||||
|
||||
#define SYSTEM_ADC_BASE 0 // not used
|
||||
|
||||
#define px4_arch_adc_temp_sensor_mask() (0)
|
||||
@ -39,27 +39,17 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#ifndef BOARD_CONFIG_H
|
||||
#define BOARD_CONFIG_H
|
||||
|
||||
#define BOARD_OVERRIDE_UUID "BBBLUEID00000000" // must be of length 16
|
||||
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_BBBLUE
|
||||
|
||||
#define BOARD_BATTERY1_V_DIV (11.0f)
|
||||
//#define BOARD_BATTERY1_A_PER_V (15.391030303f)
|
||||
|
||||
// Battery ADC channels
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 5
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
|
||||
#define ADC_AIRSPEED_VOLTAGE_CHANNEL ((uint8_t)(-1))
|
||||
|
||||
#define BOARD_HAS_NO_BOOTLOADER
|
||||
|
||||
#define BOARD_MAX_LEDS 4 // Number external of LED's this board has
|
||||
|
||||
/*
|
||||
* I2C busses
|
||||
*/
|
||||
|
||||
// I2C
|
||||
#define PX4_I2C_BUS_EXPANSION 1 // i2c-1: pins P9 17,18
|
||||
#define PX4_I2C_BUS_ONBOARD 2 // i2c-2: pins P9 19,20 - bmp280, mpu9250
|
||||
|
||||
@ -68,6 +58,14 @@
|
||||
#define PX4_I2C_OBDEV_MPU9250 0x68
|
||||
#define PX4_I2C_OBDEV_BMP280 0x76
|
||||
|
||||
|
||||
// ADC channels:
|
||||
#define ADC_CHANNELS (1 << 5)
|
||||
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 5
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
|
||||
|
||||
|
||||
#include <system_config.h>
|
||||
#include <px4_platform_common/board_common.h>
|
||||
|
||||
@ -87,8 +85,6 @@ void rc_cleaning(void);
|
||||
#define rc_i2c_unlock_bus rc_i2c_release_bus
|
||||
#define rc_i2c_get_lock rc_i2c_get_in_use_state
|
||||
|
||||
#define rc_adc_read_raw rc_adc_raw
|
||||
|
||||
#define rc_servo_send_pulse_us rc_send_servo_pulse_us
|
||||
|
||||
#define rc_filter_empty rc_empty_filter
|
||||
@ -99,4 +95,3 @@ void rc_cleaning(void);
|
||||
|
||||
#endif
|
||||
|
||||
#endif // BOARD_CONFIG_H
|
||||
|
||||
@ -31,6 +31,6 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_subdirectory(navio_adc)
|
||||
add_subdirectory(adc)
|
||||
add_subdirectory(navio_rgbled)
|
||||
add_subdirectory(navio_sysfs_rc_in)
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015-2017 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2020 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
|
||||
@ -30,12 +30,7 @@
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE drivers__navio_adc
|
||||
MAIN navio_adc
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
navio_adc.cpp
|
||||
DEPENDS
|
||||
)
|
||||
|
||||
px4_add_library(arch_adc
|
||||
adc.cpp
|
||||
)
|
||||
98
boards/emlid/navio2/adc/adc.cpp
Normal file
98
boards/emlid/navio2/adc/adc.cpp
Normal file
@ -0,0 +1,98 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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 <px4_platform_common/log.h>
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <stdint.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#define ADC_SYSFS_PATH "/sys/kernel/rcio/adc"
|
||||
#define ADC_MAX_CHAN 6
|
||||
int _channels_fd[ADC_MAX_CHAN];
|
||||
|
||||
int px4_arch_adc_init(uint32_t base_address)
|
||||
{
|
||||
for (int i = 0; i < ADC_MAX_CHAN; i++) {
|
||||
_channels_fd[i] = -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void px4_arch_adc_uninit(uint32_t base_address)
|
||||
{
|
||||
for (int i = 0; i < ADC_MAX_CHAN; i++) {
|
||||
::close(_channels_fd[i]);
|
||||
_channels_fd[i] = -1;
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t px4_arch_adc_sample(uint32_t base_address, unsigned channel)
|
||||
{
|
||||
if (channel > ADC_MAX_CHAN) {
|
||||
PX4_ERR("channel %d out of range: %d", channel, ADC_MAX_CHAN);
|
||||
return UINT32_MAX; // error
|
||||
}
|
||||
|
||||
// open channel if necessary
|
||||
if (_channels_fd[channel] == -1) {
|
||||
// ADC_SYSFS_PATH
|
||||
char channel_path[strlen(ADC_SYSFS_PATH) + 5] {};
|
||||
|
||||
if (sprintf(channel_path, "%s/ch%d", ADC_SYSFS_PATH, channel) == -1) {
|
||||
PX4_ERR("adc channel: %d\n", channel);
|
||||
return UINT32_MAX; // error
|
||||
}
|
||||
|
||||
_channels_fd[channel] = ::open(channel_path, O_RDONLY);
|
||||
}
|
||||
|
||||
char buffer[10] {};
|
||||
|
||||
if (::pread(_channels_fd[channel], buffer, sizeof(buffer), 0) < 0) {
|
||||
PX4_ERR("read channel %d failed", channel);
|
||||
return UINT32_MAX; // error
|
||||
}
|
||||
|
||||
return atoi(buffer);
|
||||
}
|
||||
|
||||
uint32_t px4_arch_adc_dn_fullcount()
|
||||
{
|
||||
return 1 << 12; // 12 bit ADC
|
||||
}
|
||||
@ -8,6 +8,7 @@ px4_add_board(
|
||||
TOOLCHAIN arm-linux-gnueabihf
|
||||
TESTING
|
||||
DRIVERS
|
||||
adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/ms5611
|
||||
batt_smbus
|
||||
|
||||
38
boards/emlid/navio2/include/px4_arch/adc.h
Normal file
38
boards/emlid/navio2/include/px4_arch/adc.h
Normal file
@ -0,0 +1,38 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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
|
||||
|
||||
#define SYSTEM_ADC_BASE 0 // not used
|
||||
|
||||
#define px4_arch_adc_temp_sensor_mask() (0)
|
||||
@ -1,335 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file navio_adc.cpp
|
||||
*
|
||||
* Navio2 ADC Driver
|
||||
*
|
||||
* This driver exports the sysfs-based ADC driver on Navio2.
|
||||
*
|
||||
* @author Nicolae Rosia <nicolae.rosia@gmail.com>
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/tasks.h>
|
||||
#include <px4_platform_common/posix.h>
|
||||
#include <drivers/drv_adc.h>
|
||||
|
||||
#include <VirtDevObj.hpp>
|
||||
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <poll.h>
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#define ADC_BASE_DEV_PATH "/dev/adc"
|
||||
#define ADC_SYSFS_PATH "/sys/kernel/rcio/adc/ch0"
|
||||
#define ADC_MAX_CHAN 6
|
||||
|
||||
/*
|
||||
* ADC Channels:
|
||||
* A0 - Board voltage (5V)
|
||||
* A1 - servo rail voltage
|
||||
* A2 - power module voltage (ADC0, POWER port)
|
||||
* A3 - power module current (ADC1, POWER port)
|
||||
* A4 - ADC2 (ADC port)
|
||||
* A5 - ADC3 (ADC port)
|
||||
*/
|
||||
|
||||
#define NAVIO_ADC_BATTERY_VOLTAGE_CHANNEL (2)
|
||||
#define NAVIO_ADC_BATTERY_CURRENT_CHANNEL (3)
|
||||
|
||||
__BEGIN_DECLS
|
||||
__EXPORT int navio_adc_main(int argc, char *argv[]);
|
||||
__END_DECLS
|
||||
|
||||
class NavioADC: public DriverFramework::VirtDevObj
|
||||
{
|
||||
public:
|
||||
NavioADC();
|
||||
virtual ~NavioADC();
|
||||
|
||||
virtual int init() override;
|
||||
|
||||
virtual ssize_t devRead(void *buf, size_t count) override;
|
||||
virtual int devIOCTL(unsigned long request, unsigned long arg) override;
|
||||
|
||||
protected:
|
||||
virtual void _measure() override;
|
||||
|
||||
private:
|
||||
int read_channel(px4_adc_msg_t *adc_msg, int channel);
|
||||
|
||||
pthread_mutex_t _samples_lock;
|
||||
int _fd[ADC_MAX_CHAN];
|
||||
px4_adc_msg_t _samples[ADC_MAX_CHAN];
|
||||
};
|
||||
|
||||
NavioADC::NavioADC()
|
||||
: DriverFramework::VirtDevObj("navio_adc", ADC0_DEVICE_PATH, ADC_BASE_DEV_PATH, 1e6 / 100)
|
||||
{
|
||||
pthread_mutex_init(&_samples_lock, NULL);
|
||||
|
||||
for (int i = 0; i < ADC_MAX_CHAN; i++) {
|
||||
_fd[i] = -1;
|
||||
}
|
||||
}
|
||||
|
||||
NavioADC::~NavioADC()
|
||||
{
|
||||
pthread_mutex_destroy(&_samples_lock);
|
||||
|
||||
for (int i = 0; i < ADC_MAX_CHAN; i++) {
|
||||
if (_fd[i] != -1) {
|
||||
close(_fd[i]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void NavioADC::_measure()
|
||||
{
|
||||
px4_adc_msg_t tmp_samples[ADC_MAX_CHAN];
|
||||
|
||||
for (int i = 0; i < ADC_MAX_CHAN; ++i) {
|
||||
int ret;
|
||||
|
||||
/* Currently we only use these channels */
|
||||
if (i != NAVIO_ADC_BATTERY_VOLTAGE_CHANNEL &&
|
||||
i != NAVIO_ADC_BATTERY_CURRENT_CHANNEL) {
|
||||
tmp_samples[i].am_channel = i;
|
||||
tmp_samples[i].am_data = 0;
|
||||
|
||||
continue;
|
||||
}
|
||||
|
||||
ret = read_channel(&tmp_samples[i], i);
|
||||
|
||||
if (ret < 0) {
|
||||
PX4_ERR("read_channel(%d): %d", i, ret);
|
||||
tmp_samples[i].am_channel = i;
|
||||
tmp_samples[i].am_data = 0;
|
||||
}
|
||||
}
|
||||
|
||||
tmp_samples[NAVIO_ADC_BATTERY_VOLTAGE_CHANNEL].am_channel = ADC_BATTERY_VOLTAGE_CHANNEL;
|
||||
tmp_samples[NAVIO_ADC_BATTERY_CURRENT_CHANNEL].am_channel = ADC_BATTERY_CURRENT_CHANNEL;
|
||||
|
||||
pthread_mutex_lock(&_samples_lock);
|
||||
memcpy(&_samples, &tmp_samples, sizeof(tmp_samples));
|
||||
pthread_mutex_unlock(&_samples_lock);
|
||||
}
|
||||
|
||||
int NavioADC::init()
|
||||
{
|
||||
int ret;
|
||||
|
||||
ret = DriverFramework::VirtDevObj::init();
|
||||
|
||||
if (ret != PX4_OK) {
|
||||
PX4_ERR("init failed");
|
||||
return ret;
|
||||
}
|
||||
|
||||
for (int i = 0; i < ADC_MAX_CHAN; i++) {
|
||||
char channel_path[sizeof(ADC_SYSFS_PATH)];
|
||||
strncpy(channel_path, ADC_SYSFS_PATH, sizeof(channel_path));
|
||||
channel_path[sizeof(ADC_SYSFS_PATH) - 2] += i;
|
||||
|
||||
_fd[i] = ::open(channel_path, O_RDONLY);
|
||||
|
||||
if (_fd[i] == -1) {
|
||||
int err = errno;
|
||||
ret = -1;
|
||||
PX4_ERR("init: open: %s (%d)", strerror(err), err);
|
||||
goto cleanup;
|
||||
}
|
||||
}
|
||||
|
||||
return PX4_OK;
|
||||
|
||||
cleanup:
|
||||
|
||||
for (int i = 0; i < ADC_MAX_CHAN; i++) {
|
||||
if (_fd[i] != -1) {
|
||||
close(_fd[i]);
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int NavioADC::devIOCTL(unsigned long request, unsigned long arg)
|
||||
{
|
||||
return -ENOTTY;
|
||||
}
|
||||
|
||||
ssize_t NavioADC::devRead(void *buf, size_t count)
|
||||
{
|
||||
const size_t maxsize = sizeof(_samples);
|
||||
int ret;
|
||||
|
||||
if (count > maxsize) {
|
||||
count = maxsize;
|
||||
}
|
||||
|
||||
ret = pthread_mutex_trylock(&_samples_lock);
|
||||
|
||||
if (ret != 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
memcpy(buf, &_samples, count);
|
||||
pthread_mutex_unlock(&_samples_lock);
|
||||
|
||||
return count;
|
||||
}
|
||||
|
||||
int NavioADC::read_channel(px4_adc_msg_t *adc_msg, int channel)
|
||||
{
|
||||
char buffer[11]; /* 32bit max INT has maximum 10 chars */
|
||||
int ret;
|
||||
|
||||
if (channel < 0 || channel >= ADC_MAX_CHAN) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
ret = lseek(_fd[channel], 0, SEEK_SET);
|
||||
|
||||
if (ret == -1) {
|
||||
ret = errno;
|
||||
PX4_ERR("read_channel %d: lseek: %s (%d)", channel, strerror(ret), ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
ret = ::read(_fd[channel], buffer, sizeof(buffer) - 1);
|
||||
|
||||
if (ret == -1) {
|
||||
ret = errno;
|
||||
PX4_ERR("read_channel %d: read: %s (%d)", channel, strerror(ret), ret);
|
||||
return ret;
|
||||
|
||||
} else if (ret == 0) {
|
||||
PX4_ERR("read_channel %d: read empty", channel);
|
||||
ret = -EINVAL;
|
||||
return ret;
|
||||
}
|
||||
|
||||
buffer[ret] = 0;
|
||||
|
||||
adc_msg->am_channel = channel;
|
||||
adc_msg->am_data = strtol(buffer, NULL, 10);
|
||||
ret = 0;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static NavioADC *instance = nullptr;
|
||||
|
||||
int navio_adc_main(int argc, char *argv[])
|
||||
{
|
||||
int ret;
|
||||
|
||||
if (argc < 2) {
|
||||
PX4_WARN("usage: <start/stop>");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
if (instance) {
|
||||
PX4_WARN("already started");
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
instance = new NavioADC;
|
||||
|
||||
if (!instance) {
|
||||
PX4_WARN("not enough memory");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
if (instance->init() != PX4_OK) {
|
||||
delete instance;
|
||||
instance = nullptr;
|
||||
PX4_WARN("init failed");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
return PX4_OK;
|
||||
|
||||
} else if (!strcmp(argv[1], "stop")) {
|
||||
if (!instance) {
|
||||
PX4_WARN("already stopped");
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
delete instance;
|
||||
instance = nullptr;
|
||||
return PX4_OK;
|
||||
|
||||
} else if (!strcmp(argv[1], "test")) {
|
||||
if (!instance) {
|
||||
PX4_ERR("start first");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
px4_adc_msg_t adc_msgs[ADC_MAX_CHAN];
|
||||
|
||||
ret = instance->devRead((char *)&adc_msgs, sizeof(adc_msgs));
|
||||
|
||||
if (ret < 0) {
|
||||
PX4_ERR("ret: %s (%d)\n", strerror(ret), ret);
|
||||
return ret;
|
||||
|
||||
} else if (ret != sizeof(adc_msgs)) {
|
||||
PX4_ERR("incomplete read: %d expected %d", ret, sizeof(adc_msgs));
|
||||
return ret;
|
||||
}
|
||||
|
||||
for (int i = 0; i < ADC_MAX_CHAN; ++i) {
|
||||
PX4_INFO("chan: %d; value: %d", (int)adc_msgs[i].am_channel,
|
||||
adc_msgs[i].am_data);
|
||||
}
|
||||
|
||||
return PX4_OK;
|
||||
|
||||
} else {
|
||||
PX4_WARN("action (%s) not supported", argv[1]);
|
||||
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
return PX4_OK;
|
||||
|
||||
}
|
||||
@ -50,13 +50,13 @@
|
||||
|
||||
#define BOARD_MAX_LEDS 1 // Number of external LED's this board has
|
||||
|
||||
/*
|
||||
* I2C busses
|
||||
*/
|
||||
|
||||
// I2C
|
||||
#define PX4_I2C_BUS_EXPANSION 1
|
||||
|
||||
#define PX4_NUMBER_I2C_BUSES 1
|
||||
|
||||
|
||||
// SPI
|
||||
#define PX4_SPI_BUS_SENSORS 0
|
||||
#define PX4_SPIDEV_UBLOX PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 0) // spidev0.0 - ublox m8n
|
||||
@ -64,9 +64,20 @@
|
||||
#define PX4_SPIDEV_LSM9DS1_M PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 2) // spidev0.2 - lsm9ds1 mag
|
||||
#define PX4_SPIDEV_LSM9DS1_AG PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 3) // spidev0.3 - lsm9ds1 accel/gyro
|
||||
|
||||
// Battery ADC channels
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 2
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL 3
|
||||
|
||||
// ADC channels:
|
||||
// A0 - board voltage (shows 5V)
|
||||
// A1 - servo rail voltage
|
||||
// A2 - power module voltage (ADC0, POWER port)
|
||||
// A3 - power module current (ADC1, POWER port)
|
||||
// A4 - ADC2 (ADC port)
|
||||
// A5 - ADC3 (ADC port)
|
||||
#define ADC_CHANNELS (1 << 0) | (1 << 1) | (1 << 2) | (1 << 3) | (1 << 4) | (1 << 5)
|
||||
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 2
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL 3
|
||||
#define ADC_5V_RAIL_SENSE 0
|
||||
|
||||
|
||||
#include <system_config.h>
|
||||
#include <px4_platform_common/board_common.h>
|
||||
|
||||
@ -57,12 +57,11 @@
|
||||
#define CYCLE_TICKS_DELAY MSEC2TICK(100)
|
||||
|
||||
|
||||
uint32_t px4_arch_adc_dn_fullcount(void)
|
||||
uint32_t px4_arch_adc_dn_fullcount()
|
||||
{
|
||||
return 1 << 12; // 12 bit ADC
|
||||
}
|
||||
|
||||
|
||||
enum AEROFC_ADC_BUS {
|
||||
AEROFC_ADC_BUS_ALL = 0,
|
||||
AEROFC_ADC_BUS_I2C_INTERNAL,
|
||||
|
||||
@ -180,7 +180,10 @@ function(px4_add_common_flags)
|
||||
${PX4_SOURCE_DIR}/src/lib/DriverFramework/framework/include
|
||||
${PX4_SOURCE_DIR}/src/lib/matrix
|
||||
${PX4_SOURCE_DIR}/src/modules
|
||||
)
|
||||
)
|
||||
if(EXISTS ${PX4_BOARD_DIR}/include)
|
||||
include_directories(${PX4_BOARD_DIR}/include)
|
||||
endif()
|
||||
|
||||
add_definitions(
|
||||
-DCONFIG_ARCH_BOARD_${PX4_BOARD_NAME}
|
||||
|
||||
@ -181,7 +181,7 @@ uint32_t px4_arch_adc_temp_sensor_mask()
|
||||
return 1 << (ADC_SC1_ADCH_TEMP >> ADC_SC1_ADCH_SHIFT);
|
||||
}
|
||||
|
||||
uint32_t px4_arch_adc_dn_fullcount(void)
|
||||
uint32_t px4_arch_adc_dn_fullcount()
|
||||
{
|
||||
return 1 << 12; // 12 bit ADC
|
||||
}
|
||||
|
||||
@ -229,7 +229,7 @@ uint32_t px4_arch_adc_temp_sensor_mask()
|
||||
return 1 << 16;
|
||||
}
|
||||
|
||||
uint32_t px4_arch_adc_dn_fullcount(void)
|
||||
uint32_t px4_arch_adc_dn_fullcount()
|
||||
{
|
||||
return 1 << 12; // 12 bit ADC
|
||||
}
|
||||
|
||||
@ -309,7 +309,7 @@ uint32_t px4_arch_adc_temp_sensor_mask()
|
||||
return 1 << 16;
|
||||
}
|
||||
|
||||
uint32_t px4_arch_adc_dn_fullcount(void)
|
||||
uint32_t px4_arch_adc_dn_fullcount()
|
||||
{
|
||||
return 1 << 16; // 16 bit ADC
|
||||
}
|
||||
|
||||
@ -49,7 +49,6 @@ if("${CONFIG_SHMEM}" STREQUAL "1")
|
||||
endif()
|
||||
|
||||
add_library(px4_layer
|
||||
adc.cpp
|
||||
px4_posix_impl.cpp
|
||||
px4_posix_tasks.cpp
|
||||
px4_sem.cpp
|
||||
|
||||
@ -46,9 +46,6 @@ param set BAT_CNT_V_VOLT 0.0004394531
|
||||
# Battery voltage scale factor, from BBBlue schematics: (4.7K + 47K) / 4.7K = 11
|
||||
param set BAT_V_DIV 11.0
|
||||
|
||||
#param set BAT_CNT_V_CURR 0.001
|
||||
#param set BAT_A_PER_V 15.391030303
|
||||
|
||||
dataman start
|
||||
|
||||
bmp280 -I start
|
||||
@ -59,8 +56,9 @@ df_mpu9250_wrapper start
|
||||
gps start -d /dev/ttyS2 -s -p ubx
|
||||
|
||||
#rgbled start -b 1
|
||||
bbblue_adc start
|
||||
bbblue_adc test
|
||||
|
||||
adc start
|
||||
battery_status start
|
||||
|
||||
rc_update start
|
||||
sensors start
|
||||
@ -72,8 +70,6 @@ land_detector start multicopter
|
||||
mc_pos_control start
|
||||
mc_att_control start
|
||||
mc_rate_control start
|
||||
#fw_att_control start
|
||||
#fw_pos_control_l1 start
|
||||
|
||||
mavlink start -n SoftAp -x -u 14556 -r 1000000
|
||||
# -n name of wifi interface: SoftAp, wlan or your custom interface,
|
||||
@ -81,10 +77,6 @@ mavlink start -n SoftAp -x -u 14556 -r 1000000
|
||||
|
||||
sleep 1
|
||||
|
||||
mavlink stream -u 14556 -s HIGHRES_IMU -r 20
|
||||
mavlink stream -u 14556 -s ATTITUDE -r 20
|
||||
mavlink stream -u 14556 -s MANUAL_CONTROL -r 10
|
||||
|
||||
linux_sbus start -d /dev/ttyS4 -c 16
|
||||
# DSM2 port is mapped to /dev/ttyS4 (default for linux_sbus)
|
||||
|
||||
@ -93,4 +85,5 @@ linux_pwm_out start -p bbblue_rc -m ROMFS/px4fmu_common/mixers/quad_x.main.mix
|
||||
#linux_pwm_out start -p bbblue_rc -m ROMFS/px4fmu_common/mixers/AETRFG.main.mix
|
||||
|
||||
logger start -t -b 200
|
||||
|
||||
mavlink boot_complete
|
||||
|
||||
@ -46,9 +46,6 @@ param set BAT_CNT_V_VOLT 0.0004394531
|
||||
# Battery voltage scale factor, from BBBlue schematics: (4.7K + 47K) / 4.7K = 11
|
||||
param set BAT_V_DIV 11.0
|
||||
|
||||
#param set BAT_CNT_V_CURR 0.001
|
||||
#param set BAT_A_PER_V 15.391030303
|
||||
|
||||
dataman start
|
||||
|
||||
bmp280 -I start
|
||||
@ -59,19 +56,17 @@ df_mpu9250_wrapper start
|
||||
gps start -d /dev/ttyS2 -s -p ubx
|
||||
|
||||
#rgbled start -b 1
|
||||
bbblue_adc start
|
||||
bbblue_adc test
|
||||
|
||||
adc start
|
||||
battery_status start
|
||||
|
||||
rc_update start
|
||||
sensors start
|
||||
commander start
|
||||
navigator start
|
||||
ekf2 start
|
||||
#land_detector start multicopter
|
||||
land_detector start fixedwing
|
||||
|
||||
#mc_pos_control start
|
||||
#mc_att_control start
|
||||
#mc_rate_control start
|
||||
fw_att_control start
|
||||
fw_pos_control_l1 start
|
||||
|
||||
@ -81,10 +76,6 @@ mavlink start -n SoftAp -x -u 14556 -r 1000000
|
||||
|
||||
sleep 1
|
||||
|
||||
mavlink stream -u 14556 -s HIGHRES_IMU -r 20
|
||||
mavlink stream -u 14556 -s ATTITUDE -r 20
|
||||
mavlink stream -u 14556 -s MANUAL_CONTROL -r 10
|
||||
|
||||
linux_sbus start -d /dev/ttyS4 -c 16
|
||||
# DSM2 port is mapped to /dev/ttyS4 (default for linux_sbus)
|
||||
|
||||
@ -93,4 +84,5 @@ linux_sbus start -d /dev/ttyS4 -c 16
|
||||
linux_pwm_out start -p bbblue_rc -m ROMFS/px4fmu_common/mixers/AETRFG.main.mix
|
||||
|
||||
logger start -t -b 200
|
||||
|
||||
mavlink boot_complete
|
||||
|
||||
@ -19,7 +19,10 @@ df_mpu9250_wrapper start_without_mag -R 10
|
||||
hmc5883 start
|
||||
ms5611 start
|
||||
rgbled start -b 1
|
||||
ocpoc_adc start
|
||||
|
||||
adc start
|
||||
battery_status start
|
||||
|
||||
gps start -d /dev/ttyS3 -s
|
||||
rc_update start
|
||||
sensors start
|
||||
|
||||
@ -4,7 +4,9 @@
|
||||
. px4-alias.sh
|
||||
|
||||
# navio config for a quad
|
||||
|
||||
uorb start
|
||||
|
||||
if [ -f eeprom/parameters ]
|
||||
then
|
||||
param load
|
||||
@ -13,15 +15,18 @@ param set SYS_AUTOSTART 4001
|
||||
param set MAV_BROADCAST 1
|
||||
param set MAV_TYPE 2
|
||||
param set BAT_CNT_V_VOLT 0.001
|
||||
param set BAT_V_DIV 10.9176300578
|
||||
param set BAT_CNT_V_CURR 0.001
|
||||
param set BAT_A_PER_V 15.391030303
|
||||
|
||||
dataman start
|
||||
|
||||
df_lsm9ds1_wrapper start -R 4
|
||||
#df_mpu9250_wrapper start -R 10
|
||||
ms5611 start
|
||||
navio_rgbled start
|
||||
navio_adc start
|
||||
|
||||
adc start
|
||||
battery_status start
|
||||
|
||||
gps start -d /dev/spidev0.0 -i spi -p ubx
|
||||
rc_update start
|
||||
sensors start
|
||||
@ -32,18 +37,17 @@ land_detector start multicopter
|
||||
mc_pos_control start
|
||||
mc_att_control start
|
||||
mc_rate_control start
|
||||
|
||||
mavlink start -x -u 14556 -r 1000000
|
||||
mavlink stream -u 14556 -s HIGHRES_IMU -r 50
|
||||
mavlink stream -u 14556 -s ATTITUDE -r 50
|
||||
|
||||
if [ -f /dev/ttyUSB0 ]
|
||||
then
|
||||
mavlink start -x -d /dev/ttyUSB0
|
||||
mavlink stream -d /dev/ttyUSB0 -s HIGHRES_IMU -r 50
|
||||
mavlink stream -d /dev/ttyUSB0 -s ATTITUDE -r 50
|
||||
fi
|
||||
|
||||
navio_sysfs_rc_in start
|
||||
linux_pwm_out start
|
||||
|
||||
logger start -t -b 200
|
||||
|
||||
mavlink boot_complete
|
||||
|
||||
@ -6,22 +6,27 @@
|
||||
# navio config for FW
|
||||
|
||||
uorb start
|
||||
param load
|
||||
|
||||
if [ -f eeprom/parameters ]
|
||||
then
|
||||
param load
|
||||
fi
|
||||
param set MAV_BROADCAST 1
|
||||
param set SYS_AUTOSTART 2100
|
||||
param set MAV_TYPE 1
|
||||
|
||||
param set BAT_CNT_V_VOLT 0.001
|
||||
param set BAT_V_DIV 10.9176300578
|
||||
param set BAT_CNT_V_CURR 0.001
|
||||
param set BAT_A_PER_V 15.391030303
|
||||
|
||||
dataman start
|
||||
|
||||
df_lsm9ds1_wrapper start -R 4
|
||||
#df_mpu9250_wrapper start -R 10
|
||||
ms5611 start
|
||||
navio_rgbled start
|
||||
navio_adc start
|
||||
|
||||
adc start
|
||||
battery_status start
|
||||
|
||||
gps start -d /dev/spidev0.0 -i spi -p ubx
|
||||
ms4525_airspeed start
|
||||
rc_update start
|
||||
@ -29,17 +34,20 @@ sensors start
|
||||
commander start
|
||||
navigator start
|
||||
ekf2 start
|
||||
land_detector start fixedwing
|
||||
fw_att_control start
|
||||
fw_pos_control_l1 start
|
||||
|
||||
mavlink start -x -u 14556 -r 1000000
|
||||
sleep 1
|
||||
mavlink stream -u 14556 -s HIGHRES_IMU -r 20
|
||||
mavlink stream -u 14556 -s ATTITUDE -r 20
|
||||
mavlink stream -u 14556 -s MANUAL_CONTROL -r 10
|
||||
|
||||
if [ -f /dev/ttyUSB0 ]
|
||||
then
|
||||
mavlink start -x -d /dev/ttyUSB0
|
||||
fi
|
||||
|
||||
navio_sysfs_rc_in start
|
||||
linux_pwm_out start -m ROMFS/px4fmu_common/mixers/AETRFG.main.mix
|
||||
|
||||
logger start -t -b 200
|
||||
|
||||
mavlink boot_complete
|
||||
|
||||
@ -8,11 +8,17 @@
|
||||
# ./Tools/jmavsim_run.sh -q -i <IP> -p 14577 -r 250
|
||||
|
||||
uorb start
|
||||
param load
|
||||
|
||||
if [ -f eeprom/parameters ]
|
||||
then
|
||||
param load
|
||||
fi
|
||||
param set SYS_AUTOSTART 1001
|
||||
param set MAV_BROADCAST 1
|
||||
param set MAV_TYPE 2
|
||||
|
||||
dataman start
|
||||
|
||||
rc_update start
|
||||
sensors start -hil
|
||||
commander start -hil
|
||||
@ -22,10 +28,13 @@ land_detector start multicopter
|
||||
mc_pos_control start
|
||||
mc_att_control start
|
||||
mc_rate_control start
|
||||
|
||||
mavlink start -x -u 14577 -r 1000000
|
||||
navio_sysfs_rc_in start
|
||||
pwm_out_sim start
|
||||
mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_x.main.mix
|
||||
|
||||
logger start -t -b 200
|
||||
|
||||
mavlink boot_complete
|
||||
|
||||
|
||||
@ -1,38 +0,0 @@
|
||||
#!/bin/sh
|
||||
# PX4 commands need the 'px4-' prefix in bash.
|
||||
# (px4-alias.sh is expected to be in the PATH)
|
||||
. px4-alias.sh
|
||||
|
||||
# config for a quad without any shield:
|
||||
# - u-blox GPS connected via UART
|
||||
# - PWM output using PCA9685 via I2C
|
||||
# - RC input via shared memory from ppmdecode (https://github.com/crossa/raspberry-pi-ppm-rc-in),
|
||||
# GPIO input
|
||||
uorb start
|
||||
param load
|
||||
param set SYS_AUTOSTART 4001
|
||||
param set MAV_BROADCAST 1
|
||||
sleep 1
|
||||
param set MAV_TYPE 2
|
||||
df_mpu9250_wrapper start -R 10
|
||||
ms5611 start
|
||||
gps start -d /dev/ttyACM0 -i uart -p ubx
|
||||
rc_update start
|
||||
sensors start
|
||||
commander start
|
||||
ekf2 start
|
||||
land_detector start multicopter
|
||||
mc_pos_control start
|
||||
mc_att_control start
|
||||
mc_rate_control start
|
||||
mavlink start -x -u 14556 -r 1000000
|
||||
sleep 1
|
||||
mavlink stream -u 14556 -s HIGHRES_IMU -r 50
|
||||
mavlink stream -u 14556 -s ATTITUDE -r 50
|
||||
#mavlink start -x -d /dev/ttyUSB0
|
||||
#mavlink stream -d /dev/ttyUSB0 -s HIGHRES_IMU -r 50
|
||||
#mavlink stream -d /dev/ttyUSB0 -s ATTITUDE -r 50
|
||||
rpi_rc_in start
|
||||
linux_pwm_out start -p pca9685
|
||||
logger start -t
|
||||
mavlink boot_complete
|
||||
@ -3,8 +3,10 @@
|
||||
# (px4-alias.sh is expected to be in the PATH)
|
||||
. px4-alias.sh
|
||||
|
||||
# navio config for a quad
|
||||
# navio config for simple testing
|
||||
|
||||
uorb start
|
||||
|
||||
if [ -f eeprom/parameters ]
|
||||
then
|
||||
param load
|
||||
@ -13,15 +15,18 @@ param set SYS_AUTOSTART 4001
|
||||
param set MAV_BROADCAST 1
|
||||
param set MAV_TYPE 2
|
||||
param set BAT_CNT_V_VOLT 0.001
|
||||
param set BAT_V_DIV 10.9176300578
|
||||
param set BAT_CNT_V_CURR 0.001
|
||||
param set BAT_A_PER_V 15.391030303
|
||||
|
||||
dataman start
|
||||
|
||||
df_lsm9ds1_wrapper start -R 4
|
||||
#df_mpu9250_wrapper start -R 10
|
||||
ms5611 start
|
||||
navio_rgbled start
|
||||
navio_adc start
|
||||
|
||||
adc start
|
||||
battery_status start
|
||||
|
||||
gps start -d /dev/spidev0.0 -i spi -p ubx
|
||||
rc_update start
|
||||
sensors start
|
||||
@ -31,20 +36,19 @@ ekf2 start
|
||||
land_detector start multicopter
|
||||
mc_pos_control start
|
||||
mc_att_control start
|
||||
|
||||
mavlink start -x -u 14556 -r 1000000
|
||||
mavlink stream -u 14556 -s HIGHRES_IMU -r 50
|
||||
mavlink stream -u 14556 -s ATTITUDE -r 50
|
||||
|
||||
if [ -f /dev/ttyUSB0 ]
|
||||
then
|
||||
mavlink start -x -d /dev/ttyUSB0
|
||||
mavlink stream -d /dev/ttyUSB0 -s HIGHRES_IMU -r 50
|
||||
mavlink stream -d /dev/ttyUSB0 -s ATTITUDE -r 50
|
||||
fi
|
||||
|
||||
navio_sysfs_rc_in start
|
||||
linux_pwm_out start
|
||||
|
||||
logger start -t -b 200
|
||||
|
||||
mavlink boot_complete
|
||||
|
||||
sleep 5
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012-2019 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2012-2020 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
|
||||
@ -68,7 +68,7 @@ public:
|
||||
|
||||
int init() override;
|
||||
|
||||
ssize_t read(file *filp, char *buffer, size_t len) override;
|
||||
ssize_t read(cdev::file_t *filp, char *buffer, size_t len) override;
|
||||
|
||||
private:
|
||||
void Run() override;
|
||||
@ -170,7 +170,7 @@ ADC::init()
|
||||
}
|
||||
|
||||
ssize_t
|
||||
ADC::read(file *filp, char *buffer, size_t len)
|
||||
ADC::read(cdev::file_t *filp, char *buffer, size_t len)
|
||||
{
|
||||
const size_t maxsize = sizeof(px4_adc_msg_t) * _channel_count;
|
||||
|
||||
@ -179,9 +179,9 @@ ADC::read(file *filp, char *buffer, size_t len)
|
||||
}
|
||||
|
||||
/* block interrupts while copying samples to avoid racing with an update */
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
lock();
|
||||
memcpy(buffer, _samples, len);
|
||||
px4_leave_critical_section(flags);
|
||||
unlock();
|
||||
|
||||
return len;
|
||||
}
|
||||
@ -189,6 +189,7 @@ ADC::read(file *filp, char *buffer, size_t len)
|
||||
void
|
||||
ADC::Run()
|
||||
{
|
||||
lock();
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
/* scan the channel set and sample each */
|
||||
@ -198,6 +199,7 @@ ADC::Run()
|
||||
|
||||
update_adc_report(now);
|
||||
update_system_power(now);
|
||||
unlock();
|
||||
}
|
||||
|
||||
void
|
||||
@ -215,7 +217,6 @@ ADC::update_adc_report(hrt_abstime now)
|
||||
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 / px4_arch_adc_dn_fullcount();
|
||||
;
|
||||
}
|
||||
|
||||
_to_adc_report.publish(adc);
|
||||
@ -332,7 +333,7 @@ int
|
||||
test(void)
|
||||
{
|
||||
|
||||
int fd = open(ADC0_DEVICE_PATH, O_RDONLY);
|
||||
int fd = px4_open(ADC0_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
PX4_ERR("can't open ADC device %d", errno);
|
||||
@ -341,7 +342,7 @@ test(void)
|
||||
|
||||
for (unsigned i = 0; i < 20; i++) {
|
||||
px4_adc_msg_t data[ADC_TOTAL_CHANNELS];
|
||||
ssize_t count = read(fd, data, sizeof(data));
|
||||
ssize_t count = px4_read(fd, data, sizeof(data));
|
||||
|
||||
if (count < 0) {
|
||||
PX4_ERR("read error");
|
||||
@ -358,6 +359,8 @@ test(void)
|
||||
px4_usleep(500000);
|
||||
}
|
||||
|
||||
px4_close(fd);
|
||||
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015-2019 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2015-2020 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
|
||||
@ -37,11 +37,10 @@ px4_add_module(
|
||||
SRCS
|
||||
battery_status.cpp
|
||||
analog_battery.cpp
|
||||
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
|
||||
DEPENDS
|
||||
arch_adc
|
||||
battery
|
||||
conversion
|
||||
drivers__device
|
||||
|
||||
@ -63,40 +63,14 @@
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
|
||||
#include <DevMgr.hpp>
|
||||
|
||||
#include "analog_battery.h"
|
||||
|
||||
using namespace DriverFramework;
|
||||
using namespace time_literals;
|
||||
|
||||
/**
|
||||
* Analog layout:
|
||||
* FMU:
|
||||
* IN2 - battery voltage
|
||||
* IN3 - battery current
|
||||
* IN4 - 5V sense
|
||||
* IN10 - spare (we could actually trim these from the set)
|
||||
* IN11 - spare on FMUv2 & v3, RC RSSI on FMUv4
|
||||
* IN12 - spare (we could actually trim these from the set)
|
||||
* IN13 - aux1 on FMUv2, unavaible on v3 & v4
|
||||
* IN14 - aux2 on FMUv2, unavaible on v3 & v4
|
||||
* IN15 - pressure sensor on FMUv2, unavaible on v3 & v4
|
||||
*
|
||||
* IO:
|
||||
* IN4 - servo supply rail
|
||||
* IN5 - analog RSSI on FMUv2 & v3
|
||||
*
|
||||
* The channel definitions (e.g., ADC_BATTERY_VOLTAGE_CHANNEL, ADC_BATTERY_CURRENT_CHANNEL, and ADC_AIRSPEED_VOLTAGE_CHANNEL) are defined in board_config.h
|
||||
*/
|
||||
|
||||
/**
|
||||
* Battery status app start / stop handling function
|
||||
*
|
||||
* @ingroup apps
|
||||
*/
|
||||
extern "C" __EXPORT int battery_status_main(int argc, char *argv[]);
|
||||
|
||||
#ifndef BOARD_NUMBER_BRICKS
|
||||
#error "battery_status module requires power bricks"
|
||||
#endif
|
||||
@ -123,11 +97,8 @@ public:
|
||||
void Run() override;
|
||||
bool init();
|
||||
|
||||
/** @see ModuleBase::print_status() */
|
||||
int print_status() override;
|
||||
|
||||
private:
|
||||
DevHandle _h_adc; /**< ADC driver handle */
|
||||
int _adc_fd{-1}; /**< ADC file handle */
|
||||
|
||||
uORB::Subscription _actuator_ctrl_0_sub{ORB_ID(actuator_controls_0)}; /**< attitude controls sub */
|
||||
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; /**< notification of parameter updates */
|
||||
@ -151,11 +122,6 @@ private:
|
||||
|
||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||
|
||||
/**
|
||||
* Do adc-related initialisation.
|
||||
*/
|
||||
int adc_init();
|
||||
|
||||
/**
|
||||
* Check for changes in parameters.
|
||||
*/
|
||||
@ -187,19 +153,6 @@ BatteryStatus::~BatteryStatus()
|
||||
ScheduleClear();
|
||||
}
|
||||
|
||||
int
|
||||
BatteryStatus::adc_init()
|
||||
{
|
||||
DevMgr::getHandle(ADC0_DEVICE_PATH, _h_adc);
|
||||
|
||||
if (!_h_adc.isValid()) {
|
||||
PX4_ERR("no ADC found: %s (%d)", ADC0_DEVICE_PATH, _h_adc.getError());
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
void
|
||||
BatteryStatus::parameter_update_poll(bool forced)
|
||||
{
|
||||
@ -221,7 +174,7 @@ BatteryStatus::adc_poll()
|
||||
px4_adc_msg_t buf_adc[PX4_MAX_ADC_CHANNELS];
|
||||
|
||||
/* read all channels available */
|
||||
int ret = _h_adc.read(&buf_adc, sizeof(buf_adc));
|
||||
int ret = px4_read(_adc_fd, &buf_adc, sizeof(buf_adc));
|
||||
|
||||
/* For legacy support we publish the battery_status for the Battery that is
|
||||
* associated with the Brick that is the selected source for VDD_5V_IN
|
||||
@ -307,12 +260,17 @@ BatteryStatus::Run()
|
||||
return;
|
||||
}
|
||||
|
||||
if (!_h_adc.isValid()) {
|
||||
adc_init();
|
||||
}
|
||||
|
||||
perf_begin(_loop_perf);
|
||||
|
||||
if (_adc_fd < 0) {
|
||||
_adc_fd = px4_open(ADC0_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (_adc_fd < 0) {
|
||||
PX4_ERR("unable to open ADC: %s", ADC0_DEVICE_PATH);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
/* check parameters for updates */
|
||||
parameter_update_poll();
|
||||
|
||||
@ -354,11 +312,6 @@ BatteryStatus::init()
|
||||
return true;
|
||||
}
|
||||
|
||||
int BatteryStatus::print_status()
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
int BatteryStatus::custom_command(int argc, char *argv[])
|
||||
{
|
||||
return print_usage("unknown command");
|
||||
@ -390,7 +343,7 @@ It runs in its own thread and polls on the currently selected gyro topic.
|
||||
return 0;
|
||||
}
|
||||
|
||||
int battery_status_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int battery_status_main(int argc, char *argv[])
|
||||
{
|
||||
return BatteryStatus::main(argc, argv);
|
||||
}
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user