mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-15 00:27:35 +08:00
delete unused ADCSIM
- set BOARD_NUMBER_BRICKS to 0 for boards without analog power bricks
This commit is contained in:
@@ -39,12 +39,8 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 10
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
|
||||
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
|
||||
#define ADCSIM0_DEVICE_PATH "/dev/adc0"
|
||||
|
||||
#define SIM_FORMATED_UUID "000000010000000200000003"
|
||||
|
||||
#define PX4_CPU_UUID_BYTE_LENGTH 12
|
||||
#define PX4_CPU_UUID_WORD32_LENGTH 3
|
||||
#define PX4_CPU_MFGUID_BYTE_LENGTH PX4_CPU_UUID_BYTE_LENGTH
|
||||
|
||||
@@ -74,7 +74,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
commander start
|
||||
sensors start
|
||||
ekf_att_pos_estimator start
|
||||
|
||||
@@ -19,7 +19,6 @@ mixer load /dev/pwm_output0 ROMFS/px4fmu_test/mixers/uuv_quad_x.mix
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
|
||||
sleep 1
|
||||
|
||||
@@ -51,7 +51,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -53,7 +53,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -53,7 +53,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -52,7 +52,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -54,7 +54,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -51,7 +51,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -51,7 +51,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -73,7 +73,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim start
|
||||
|
||||
@@ -54,7 +54,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim start
|
||||
|
||||
@@ -48,7 +48,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -66,7 +66,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim start start
|
||||
|
||||
@@ -49,7 +49,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim start
|
||||
|
||||
@@ -83,7 +83,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim start
|
||||
|
||||
@@ -54,7 +54,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -49,7 +49,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -51,7 +51,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -19,7 +19,6 @@ mixer load /dev/pwm_output0 ROMFS/px4fmu_test/mixers/uuv_quad_x.mix
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
|
||||
sleep 1
|
||||
|
||||
|
||||
@@ -51,7 +51,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -53,7 +53,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -53,7 +53,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -59,7 +59,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -69,7 +69,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -50,7 +50,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sleep 1
|
||||
|
||||
@@ -56,7 +56,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim start
|
||||
|
||||
@@ -50,7 +50,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim start
|
||||
|
||||
@@ -51,7 +51,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -60,7 +60,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim start
|
||||
|
||||
@@ -48,7 +48,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
|
||||
@@ -32,7 +32,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim start
|
||||
|
||||
@@ -10,7 +10,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim start
|
||||
|
||||
@@ -10,7 +10,6 @@ tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim start
|
||||
|
||||
@@ -43,11 +43,12 @@
|
||||
#define BOARD_OVERRIDE_MFGUID BOARD_OVERRIDE_UUID
|
||||
|
||||
#define BOARD_NAME "BEBOP"
|
||||
#define BOARD_BATTERY1_V_DIV (10.177939394f)
|
||||
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
|
||||
|
||||
#define BOARD_HAS_NO_RESET
|
||||
#define BOARD_HAS_NO_BOOTLOADER
|
||||
|
||||
#define BOARD_NUMBER_BRICKS 0
|
||||
|
||||
/*
|
||||
* I2C busses
|
||||
*/
|
||||
|
||||
@@ -170,7 +170,9 @@
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#if BOARD_NUMBER_BRICKS == 1
|
||||
#if BOARD_NUMBER_BRICKS == 0
|
||||
/* allow SITL to disable all bricks */
|
||||
#elif BOARD_NUMBER_BRICKS == 1
|
||||
# define BOARD_BATT_V_LIST {ADC_BATTERY_VOLTAGE_CHANNEL}
|
||||
# define BOARD_BATT_I_LIST {ADC_BATTERY_CURRENT_CHANNEL}
|
||||
# define BOARD_BRICK_VALID_LIST {BOARD_ADC_BRICK_VALID}
|
||||
|
||||
@@ -43,11 +43,12 @@
|
||||
#define BOARD_OVERRIDE_MFGUID BOARD_OVERRIDE_UUID
|
||||
|
||||
#define BOARD_NAME "EAGLE"
|
||||
#define BOARD_BATTERY1_V_DIV (10.177939394f)
|
||||
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
|
||||
|
||||
#define BOARD_HAS_NO_RESET
|
||||
#define BOARD_HAS_NO_BOOTLOADER
|
||||
|
||||
#define BOARD_NUMBER_BRICKS 0
|
||||
|
||||
#define CONFIG_ARCH_BOARD_SITL 1
|
||||
|
||||
/*
|
||||
|
||||
@@ -43,8 +43,13 @@
|
||||
#define BOARD_OVERRIDE_MFGUID BOARD_OVERRIDE_UUID
|
||||
|
||||
#define BOARD_NAME "RPI"
|
||||
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 2
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL 3
|
||||
|
||||
#define BOARD_BATTERY1_V_DIV (10.177939394f)
|
||||
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
|
||||
|
||||
#define BOARD_HAS_NO_RESET
|
||||
#define BOARD_HAS_NO_BOOTLOADER
|
||||
|
||||
|
||||
@@ -54,5 +54,7 @@
|
||||
#define PX4_I2C_BUS_ONBOARD 2
|
||||
#define PX4_NUMBER_I2C_BUSES 1
|
||||
|
||||
#define BOARD_NUMBER_BRICKS 0
|
||||
|
||||
#include <system_config.h>
|
||||
#include "../common/board_common.h"
|
||||
|
||||
@@ -173,14 +173,18 @@ private:
|
||||
orb_advert_t _sensor_pub{nullptr}; /**< combined sensor data topic */
|
||||
orb_advert_t _airdata_pub{nullptr}; /**< combined sensor data topic */
|
||||
orb_advert_t _magnetometer_pub{nullptr}; /**< combined sensor data topic */
|
||||
|
||||
#if BOARD_NUMBER_BRICKS > 0
|
||||
orb_advert_t _battery_pub[BOARD_NUMBER_BRICKS] {}; /**< battery status */
|
||||
|
||||
Battery _battery[BOARD_NUMBER_BRICKS]; /**< Helper lib to publish battery_status topic. */
|
||||
#endif /* BOARD_NUMBER_BRICKS > 0 */
|
||||
|
||||
#if BOARD_NUMBER_BRICKS > 1
|
||||
int _battery_pub_intance0ndx {0}; /**< track the index of instance 0 */
|
||||
#endif
|
||||
#endif /* BOARD_NUMBER_BRICKS > 1 */
|
||||
|
||||
orb_advert_t _airspeed_pub{nullptr}; /**< airspeed */
|
||||
orb_advert_t _diff_pres_pub{nullptr}; /**< differential_pressure */
|
||||
orb_advert_t _sensor_preflight{nullptr}; /**< sensor preflight topic */
|
||||
|
||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||
@@ -189,9 +193,9 @@ private:
|
||||
|
||||
#ifdef ADC_AIRSPEED_VOLTAGE_CHANNEL
|
||||
differential_pressure_s _diff_pres {};
|
||||
#endif /* ADC_AIRSPEED_VOLTAGE_CHANNEL */
|
||||
|
||||
Battery _battery[BOARD_NUMBER_BRICKS]; /**< Helper lib to publish battery_status topic. */
|
||||
orb_advert_t _diff_pres_pub{nullptr}; /**< differential_pressure */
|
||||
#endif /* ADC_AIRSPEED_VOLTAGE_CHANNEL */
|
||||
|
||||
Parameters _parameters{}; /**< local copies of interesting parameters */
|
||||
ParameterHandles _parameter_handles{}; /**< handles for interesting parameters */
|
||||
@@ -249,9 +253,13 @@ Sensors::Sensors(bool hil_enabled) :
|
||||
_airspeed_validator.set_timeout(300000);
|
||||
_airspeed_validator.set_equal_value_threshold(100);
|
||||
|
||||
#if BOARD_NUMBER_BRICKS > 0
|
||||
|
||||
for (int b = 0; b < BOARD_NUMBER_BRICKS; b++) {
|
||||
_battery[b].setParent(this);
|
||||
}
|
||||
|
||||
#endif /* BOARD_NUMBER_BRICKS > 0 */
|
||||
}
|
||||
|
||||
int
|
||||
@@ -425,6 +433,7 @@ Sensors::adc_poll()
|
||||
/* read all channels available */
|
||||
int ret = _h_adc.read(&buf_adc, sizeof(buf_adc));
|
||||
|
||||
#if BOARD_NUMBER_BRICKS > 0
|
||||
//todo:abosorb into new class Power
|
||||
|
||||
/* For legacy support we publish the battery_status for the Battery that is
|
||||
@@ -433,19 +442,16 @@ Sensors::adc_poll()
|
||||
* Like in the FMUv4
|
||||
*/
|
||||
|
||||
/* The ADC channela that are associated with each brick, in power controller
|
||||
/* The ADC channels that are associated with each brick, in power controller
|
||||
* priority order highest to lowest, as defined by the board config.
|
||||
*/
|
||||
|
||||
int bat_voltage_v_chan[BOARD_NUMBER_BRICKS] = BOARD_BATT_V_LIST;
|
||||
int bat_voltage_i_chan[BOARD_NUMBER_BRICKS] = BOARD_BATT_I_LIST;
|
||||
|
||||
/* The valid signals (HW dependent) are associated with each brick */
|
||||
|
||||
bool valid_chan[BOARD_NUMBER_BRICKS] = BOARD_BRICK_VALID_LIST;
|
||||
|
||||
/* Per Brick readings with default unread channels at 0 */
|
||||
|
||||
float bat_current_a[BOARD_NUMBER_BRICKS] = {0.0f};
|
||||
float bat_voltage_v[BOARD_NUMBER_BRICKS] = {0.0f};
|
||||
|
||||
@@ -456,6 +462,8 @@ Sensors::adc_poll()
|
||||
|
||||
int selected_source = -1;
|
||||
|
||||
#endif /* BOARD_NUMBER_BRICKS > 0 */
|
||||
|
||||
if (ret >= (int)sizeof(buf_adc[0])) {
|
||||
|
||||
/* Read add channels we got */
|
||||
@@ -489,6 +497,9 @@ Sensors::adc_poll()
|
||||
} else
|
||||
#endif /* ADC_AIRSPEED_VOLTAGE_CHANNEL */
|
||||
{
|
||||
|
||||
#if BOARD_NUMBER_BRICKS > 0
|
||||
|
||||
for (int b = 0; b < BOARD_NUMBER_BRICKS; b++) {
|
||||
|
||||
/* Once we have subscriptions, Do this once for the lowest (highest priority
|
||||
@@ -512,7 +523,7 @@ Sensors::adc_poll()
|
||||
_battery_pub_intance0ndx = selected_source;
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif /* BOARD_NUMBER_BRICKS > 1 */
|
||||
}
|
||||
|
||||
// todo:per brick scaling
|
||||
@@ -526,9 +537,13 @@ Sensors::adc_poll()
|
||||
- _parameters.battery_current_offset) * _parameters.battery_a_per_v;
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* BOARD_NUMBER_BRICKS > 0 */
|
||||
}
|
||||
}
|
||||
|
||||
#if BOARD_NUMBER_BRICKS > 0
|
||||
|
||||
if (_parameters.battery_source == 0) {
|
||||
|
||||
for (int b = 0; b < BOARD_NUMBER_BRICKS; b++) {
|
||||
@@ -557,8 +572,9 @@ Sensors::adc_poll()
|
||||
}
|
||||
}
|
||||
|
||||
_last_adc = t;
|
||||
#endif /* BOARD_NUMBER_BRICKS > 0 */
|
||||
|
||||
_last_adc = t;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,42 +0,0 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015 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_module(
|
||||
MODULE platforms__posix__drivers__adcsim
|
||||
MAIN adcsim
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
adcsim.cpp
|
||||
DEPENDS
|
||||
git_driverframework
|
||||
df_driver_framework
|
||||
)
|
||||
@@ -1,255 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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 adcsim.cpp
|
||||
*
|
||||
* Driver for the ADCSIM.
|
||||
*
|
||||
* This is a designed for simulating sampling things like voltages
|
||||
* and so forth.
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_time.h>
|
||||
#include <board_config.h>
|
||||
#include <drivers/device/device.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_adc.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
#include <perf/perf_counter.h>
|
||||
|
||||
#include <uORB/topics/system_power.h>
|
||||
|
||||
#include "SyncObj.hpp"
|
||||
#include "VirtDevObj.hpp"
|
||||
|
||||
using namespace DriverFramework;
|
||||
|
||||
#define ADC_BASE_DEV_PATH "/dev/adc"
|
||||
|
||||
class ADCSIM : public VirtDevObj
|
||||
{
|
||||
public:
|
||||
ADCSIM(uint32_t channels);
|
||||
virtual ~ADCSIM();
|
||||
|
||||
virtual ssize_t devRead(void *buffer, size_t len);
|
||||
|
||||
private:
|
||||
perf_counter_t _sample_perf;
|
||||
|
||||
unsigned _channel_count;
|
||||
px4_adc_msg_t *_samples; /**< sample buffer */
|
||||
|
||||
/** worker function */
|
||||
virtual void _measure();
|
||||
|
||||
/**
|
||||
* 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);
|
||||
|
||||
SyncObj m_lock;
|
||||
};
|
||||
|
||||
ADCSIM::ADCSIM(uint32_t channels) :
|
||||
VirtDevObj("adcsim", "/dev/adcsim", ADC_BASE_DEV_PATH, 10000),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "adc_samples")),
|
||||
_channel_count(0),
|
||||
_samples(nullptr)
|
||||
{
|
||||
/* always enable the temperature sensor */
|
||||
channels |= 1 << 16;
|
||||
|
||||
/* allocate the sample array */
|
||||
for (unsigned i = 0; i < 32; i++) {
|
||||
if (channels & (1 << i)) {
|
||||
_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 < 32; i++) {
|
||||
if (channels & (1 << i)) {
|
||||
_samples[index].am_channel = i;
|
||||
_samples[index].am_data = 0;
|
||||
index++;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
ADCSIM::~ADCSIM()
|
||||
{
|
||||
if (_samples != nullptr) {
|
||||
delete _samples;
|
||||
}
|
||||
}
|
||||
|
||||
ssize_t
|
||||
ADCSIM::devRead(void *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 */
|
||||
m_lock.lock();
|
||||
memcpy(buffer, _samples, len);
|
||||
m_lock.unlock();
|
||||
|
||||
return len;
|
||||
}
|
||||
|
||||
void
|
||||
ADCSIM::_measure()
|
||||
{
|
||||
m_lock.lock();
|
||||
|
||||
/* scan the channel set and sample each */
|
||||
for (unsigned i = 0; i < _channel_count; i++) {
|
||||
_samples[i].am_data = _sample(_samples[i].am_channel);
|
||||
}
|
||||
|
||||
m_lock.unlock();
|
||||
}
|
||||
|
||||
uint16_t
|
||||
ADCSIM::_sample(unsigned channel)
|
||||
{
|
||||
perf_begin(_sample_perf);
|
||||
|
||||
uint16_t result = 1;
|
||||
|
||||
perf_end(_sample_perf);
|
||||
return result;
|
||||
}
|
||||
|
||||
/*
|
||||
* Driver 'main' command.
|
||||
*/
|
||||
extern "C" __EXPORT int adcsim_main(int argc, char *argv[]);
|
||||
|
||||
namespace
|
||||
{
|
||||
ADCSIM *g_adc;
|
||||
|
||||
int
|
||||
test()
|
||||
{
|
||||
DevHandle h;
|
||||
DevMgr::getHandle(ADCSIM0_DEVICE_PATH, h);
|
||||
|
||||
if (!h.isValid()) {
|
||||
PX4_ERR("can't open ADCSIM device (%d)", h.getError());
|
||||
return 1;
|
||||
}
|
||||
|
||||
for (unsigned i = 0; i < 50; i++) {
|
||||
px4_adc_msg_t data[PX4_MAX_ADC_CHANNELS];
|
||||
ssize_t count = h.read(data, sizeof(data));
|
||||
|
||||
if (count < 0) {
|
||||
PX4_ERR("read error (%d)", h.getError());
|
||||
return 1;
|
||||
}
|
||||
|
||||
unsigned channels = count / sizeof(data[0]);
|
||||
|
||||
for (unsigned j = 0; j < channels; j++) {
|
||||
PX4_INFO("%d: %lu ", data[j].am_channel, (unsigned long)data[j].am_data);
|
||||
}
|
||||
|
||||
usleep(500000);
|
||||
}
|
||||
|
||||
DevMgr::releaseHandle(h);
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
adcsim_main(int argc, char *argv[])
|
||||
{
|
||||
int ret = 0;
|
||||
|
||||
if (g_adc == nullptr) {
|
||||
/* FIXME - this hardcodes the default channel set for SITL - should be configurable */
|
||||
g_adc = new ADCSIM((1 << 10) | (1 << 11) | (1 << 12) | (1 << 13));
|
||||
|
||||
if (g_adc == nullptr) {
|
||||
PX4_ERR("couldn't allocate the ADCSIM driver");
|
||||
return 1;
|
||||
}
|
||||
|
||||
ret = g_adc->init();
|
||||
|
||||
if (ret != 0) {
|
||||
PX4_ERR("ADCSIM init failed (%d)", ret);
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
if (argc > 1 && g_adc) {
|
||||
if (!strcmp(argv[1], "test")) {
|
||||
ret = test();
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
Reference in New Issue
Block a user