Compare commits

...

11 Commits

18 changed files with 552 additions and 16 deletions

View File

@ -91,6 +91,8 @@ then
fi
unset BOARD_RC_SENSORS
analog_measurement start
#
# Start UART/Serial device drivers.
# Note: rc.serial is auto-generated from Tools/serial/generate_config.py

View File

@ -56,6 +56,7 @@ px4_add_board(
#tone_alarm
uavcannode
MODULES
analog_measurement
#ekf2
#load_mon
sensors
@ -81,7 +82,7 @@ px4_add_board(
#sd_bench
#shutdown
top
#topic_listener
topic_listener
#tune_control
ver
work_queue

View File

@ -41,6 +41,7 @@ set(msg_files
adc_report.msg
airspeed.msg
airspeed_validated.msg
analog_measurement.msg
battery_status.msg
camera_capture.msg
camera_trigger.msg

View File

@ -0,0 +1,10 @@
uint64 timestamp # time since system start (microseconds)
int32 id # Source node ID
uint8[4] unit_type # Units: mV, mA, Kelvin*10
uint16[4] values # mV, mA, Kelvin*10
uint8 UNITS_NONE = 0
uint8 UNITS_MV = 1
uint8 UNITS_MA = 2
uint8 UNITS_CK = 3

View File

@ -126,14 +126,15 @@ px4_add_module(
actuators/hardpoint.cpp
# Sensors
sensors/sensor_bridge.cpp
sensors/differential_pressure.cpp
sensors/analog_measurement.cpp
sensors/airspeed.cpp
sensors/baro.cpp
sensors/battery.cpp
sensors/airspeed.cpp
sensors/differential_pressure.cpp
sensors/flow.cpp
sensors/gnss.cpp
sensors/mag.cpp
sensors/sensor_bridge.cpp
DEPENDS
px4_uavcan_dsdlc

View File

@ -0,0 +1,7 @@
uint3 UNITS_NONE = 0
uint3 UNITS_MV = 1
uint3 UNITS_MA = 2
uint3 UNITS_CK = 3
uint3[4] unit_type
int16[4] values

View File

@ -0,0 +1,80 @@
/****************************************************************************
*
* 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 <drivers/drv_hrt.h>
#include "analog_measurement.hpp"
const char *const UavcanAnalogMeasurementBridge::NAME = "analog_measurement";
UavcanAnalogMeasurementBridge::UavcanAnalogMeasurementBridge(uavcan::INode &node) :
UavcanCDevSensorBridgeBase("uavcan_airspeed", "/dev/uavcan/analog_measurement", "/dev/analog_measurement",
ORB_ID(analog_measurement)),
_sub_analog_data(node)
{ }
int UavcanAnalogMeasurementBridge::init()
{
int res = device::CDev::init();
if (res < 0) {
return res;
}
res = _sub_analog_data.start(AnalogCbBinder(this, &UavcanAnalogMeasurementBridge::analog_measurement_sub_cb));
if (res < 0) {
DEVICE_LOG("failed to start uavcan sub: %d", res);
return res;
}
return 0;
}
void
UavcanAnalogMeasurementBridge::analog_measurement_sub_cb(const
uavcan::ReceivedDataStructure<com::volansi::equipment::adc::AnalogMeasurement> &msg)
{
analog_measurement_s report{};
int node_id = msg.getSrcNodeID().get();
report.id = node_id;
int numIndices = msg.values.size();
for (int i = 0; i < numIndices; i++) {
report.values[i] = msg.values[i];
report.unit_type[i] = msg.unit_type[i];
}
publish(node_id, &report);
}

View File

@ -0,0 +1,67 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
/**
* @author RJ Gritter <rjgritter657@gmail.com>
*/
#pragma once
#include "sensor_bridge.hpp"
#include <uORB/topics/analog_measurement.h>
#include <com/volansi/equipment/adc/AnalogMeasurement.hpp>
class UavcanAnalogMeasurementBridge : public UavcanCDevSensorBridgeBase
{
public:
static const char *const NAME;
UavcanAnalogMeasurementBridge(uavcan::INode &node);
const char *get_name() const override { return NAME; }
int init() override;
private:
void analog_measurement_sub_cb(const uavcan::ReceivedDataStructure<com::volansi::equipment::adc::AnalogMeasurement>
&msg);
typedef uavcan::MethodBinder < UavcanAnalogMeasurementBridge *,
void (UavcanAnalogMeasurementBridge::*)
(const uavcan::ReceivedDataStructure<com::volansi::equipment::adc::AnalogMeasurement> &) >
AnalogCbBinder;
uavcan::Subscriber<com::volansi::equipment::adc::AnalogMeasurement, AnalogCbBinder> _sub_analog_data;
};

View File

@ -38,6 +38,7 @@
#include "sensor_bridge.hpp"
#include <cassert>
#include "analog_measurement.hpp"
#include "differential_pressure.hpp"
#include "baro.hpp"
#include "battery.hpp"
@ -58,6 +59,7 @@ void IUavcanSensorBridge::make_all(uavcan::INode &node, List<IUavcanSensorBridge
list.add(new UavcanBatteryBridge(node));
list.add(new UavcanAirspeedBridge(node));
list.add(new UavcanDifferentialPressureBridge(node));
list.add(new UavcanAnalogMeasurementBridge(node));
}
/*

View File

@ -81,6 +81,7 @@ UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &sys
_air_data_static_temperature_publisher(_node),
_raw_air_data_publisher(_node),
_range_sensor_measurement(_node),
_analog_measurement_publisher(_node),
_cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle time")),
_interval_perf(perf_alloc(PC_INTERVAL, MODULE_NAME": cycle interval")),
_reset_timer(_node)
@ -330,9 +331,28 @@ void UavcanNode::Run()
PX4_ERR("node spin error %i", spin_res);
}
send_analog_measurements();
send_battery_info();
send_raw_air_data();
send_static_pressure();
send_magnetic_field_strength2();
send_gnss_fix2();
perf_end(_cycle_perf);
pthread_mutex_unlock(&_node_mutex);
if (_task_should_exit.load()) {
ScheduleClear();
_instance = nullptr;
}
}
void UavcanNode::send_battery_info()
{
// battery_status -> uavcan::equipment::power::BatteryInfo
if (_battery_status_sub.updated()) {
battery_status_s battery;
battery_status_s battery{};
if (_battery_status_sub.copy(&battery)) {
uavcan::equipment::power::BatteryInfo battery_info{};
@ -359,10 +379,13 @@ void UavcanNode::Run()
_power_battery_info_publisher.broadcast(battery_info);
}
}
}
void UavcanNode::send_raw_air_data()
{
// differential_pressure -> uavcan::equipment::air_data::RawAirData
if (_diff_pressure_sub.updated()) {
differential_pressure_s diff_press;
differential_pressure_s diff_press{};
if (_diff_pressure_sub.copy(&diff_press)) {
@ -378,10 +401,13 @@ void UavcanNode::Run()
_raw_air_data_publisher.broadcast(raw_air_data);
}
}
}
void UavcanNode::send_range_sensor_measurement()
{
// distance_sensor[] -> uavcan::equipment::range_sensor::Measurement
for (int i = 0; i < ORB_MULTI_MAX_INSTANCES; i++) {
distance_sensor_s dist;
distance_sensor_s dist{};
if (_distance_sensor_sub[i].update(&dist)) {
uavcan::equipment::range_sensor::Measurement range_sensor{};
@ -427,10 +453,13 @@ void UavcanNode::Run()
_range_sensor_measurement.broadcast(range_sensor);
}
}
}
void UavcanNode::send_static_pressure()
{
// sensor_baro -> uavcan::equipment::air_data::StaticTemperature
if (_sensor_baro_sub.updated()) {
sensor_baro_s baro;
sensor_baro_s baro{};
if (_sensor_baro_sub.copy(&baro)) {
uavcan::equipment::air_data::StaticPressure static_pressure{};
@ -445,10 +474,13 @@ void UavcanNode::Run()
}
}
}
}
void UavcanNode::send_magnetic_field_strength2()
{
// sensor_mag -> uavcan::equipment::ahrs::MagneticFieldStrength2
if (_sensor_mag_sub.updated()) {
sensor_mag_s mag;
sensor_mag_s mag{};
if (_sensor_mag_sub.copy(&mag)) {
uavcan::equipment::ahrs::MagneticFieldStrength2 magnetic_field{};
@ -459,10 +491,13 @@ void UavcanNode::Run()
_ahrs_magnetic_field_strength2_publisher.broadcast(magnetic_field);
}
}
}
void UavcanNode::send_gnss_fix2()
{
// vehicle_gps_position -> uavcan::equipment::gnss::Fix2
if (_vehicle_gps_position_sub.updated()) {
vehicle_gps_position_s gps;
vehicle_gps_position_s gps{};
if (_vehicle_gps_position_sub.copy(&gps)) {
uavcan::equipment::gnss::Fix2 fix2{};
@ -494,14 +529,27 @@ void UavcanNode::Run()
_gnss_fix2_publisher.broadcast(fix2);
}
}
}
perf_end(_cycle_perf);
void UavcanNode::send_analog_measurements()
{
// vehicle_gps_position -> uavcan::equipment::gnss::Fix2
if (_analog_report_sub.updated()) {
analog_measurement_s measurement{};
pthread_mutex_unlock(&_node_mutex);
if (_analog_report_sub.copy(&measurement)) {
if (_task_should_exit.load()) {
ScheduleClear();
_instance = nullptr;
com::volansi::equipment::adc::AnalogMeasurement report{};
for (size_t i = 0; i < sizeof(measurement.values) / sizeof(measurement.values[0]); i++) {
if (measurement.unit_type[i]) {
report.unit_type[i] = measurement.unit_type[i];
report.values[i] = measurement.values[i];
}
}
_analog_measurement_publisher.broadcast(report);
}
}
}

View File

@ -64,6 +64,7 @@
#include <uavcan/equipment/gnss/Fix2.hpp>
#include <uavcan/equipment/power/BatteryInfo.hpp>
#include <uavcan/equipment/range_sensor/Measurement.hpp>
#include <com/volansi/equipment/adc/AnalogMeasurement.hpp>
#include <lib/parameters/param.h>
@ -71,10 +72,11 @@
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionCallback.hpp>
#include <uORB/topics/analog_measurement.h>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/distance_sensor.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/sensor_baro.h>
#include <uORB/topics/sensor_mag.h>
#include <uORB/topics/vehicle_gps_position.h>
@ -146,6 +148,14 @@ private:
void fill_node_info();
int init(uavcan::NodeID node_id, UAVCAN_DRIVER::BusEvent &bus_events);
void send_battery_info();
void send_raw_air_data();
void send_static_pressure();
void send_magnetic_field_strength2();
void send_gnss_fix2();
void send_range_sensor_measurement();
void send_analog_measurements();
px4::atomic_bool _task_should_exit{false}; ///< flag to indicate to tear down the CAN driver
bool _initialized{false}; ///< number of actuators currently available
@ -176,6 +186,8 @@ private:
uavcan::Publisher<uavcan::equipment::air_data::StaticTemperature> _air_data_static_temperature_publisher;
uavcan::Publisher<uavcan::equipment::air_data::RawAirData> _raw_air_data_publisher;
uavcan::Publisher<uavcan::equipment::range_sensor::Measurement> _range_sensor_measurement;
uavcan::Publisher<com::volansi::equipment::adc::AnalogMeasurement> _analog_measurement_publisher;
hrt_abstime _last_static_temperature_publish{0};
@ -192,6 +204,8 @@ private:
uORB::SubscriptionCallbackWorkItem _sensor_baro_sub{this, ORB_ID(sensor_baro)};
uORB::SubscriptionCallbackWorkItem _sensor_mag_sub{this, ORB_ID(sensor_mag)};
uORB::SubscriptionCallbackWorkItem _vehicle_gps_position_sub{this, ORB_ID(vehicle_gps_position)};
uORB::SubscriptionCallbackWorkItem _analog_report_sub{this, ORB_ID(analog_measurement)};
perf_counter_t _cycle_perf;
perf_counter_t _interval_perf;

View File

@ -0,0 +1,7 @@
uint3 UNITS_NONE = 0
uint3 UNITS_MV = 1
uint3 UNITS_MA = 2
uint3 UNITS_CK = 3
uint3[4] unit_type
int16[4] values

View File

@ -50,3 +50,17 @@ PARAM_DEFINE_INT32(CANNODE_NODE_ID, 120);
* @group UAVCAN
*/
PARAM_DEFINE_INT32(CANNODE_BITRATE, 1000000);
/**
* Units associated with ADC measurement.
* 0 - unused
* 1 - mV
* 2 - mA
* 3 - cK
* @group UAVCAN
*/
PARAM_DEFINE_INT32(ADC1_UNIT_TYPE, 1);
PARAM_DEFINE_INT32(ADC2_UNIT_TYPE, 2);
PARAM_DEFINE_INT32(ADC3_UNIT_TYPE, 0);
PARAM_DEFINE_INT32(ADC4_UNIT_TYPE, 0);

View File

@ -0,0 +1,11 @@
px4_add_module(
MODULE modules__analog_measurement
MAIN analog_measurement
COMPILE_FLAGS
SRCS
analog_measurement.cpp
analog_measurement.hpp
DEPENDS
px4_work_queue
)

View File

@ -0,0 +1,153 @@
/****************************************************************************
*
* Copyright (c) 2013-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.
*
****************************************************************************/
#include "analog_measurement.hpp"
AnalogMeasurement::AnalogMeasurement() :
ModuleParams(nullptr),
WorkItem(MODULE_NAME, px4::wq_configurations::lp_default)
{
}
bool
AnalogMeasurement::init()
{
if (!_adc_report_sub.registerCallback()) {
PX4_ERR("adc_report callback registration failed!");
return false;
}
return true;
}
void
AnalogMeasurement::Run()
{
if (should_exit()) {
_adc_report_sub.unregisterCallback();
exit_and_cleanup();
return;
}
adc_report_s report{};
if (_adc_report_sub.update(&report)) {
analog_measurement_s measurement{};
int adc1_unit = _adc1_unit.get();
int adc2_unit = _adc2_unit.get();
int adc3_unit = _adc3_unit.get();
int adc4_unit = _adc4_unit.get();
// TODO: determine size. Only read first 4 ADCs for now.
const float adc_raw_scale = report.v_ref / (float)report.resolution;
if (adc1_unit) {
measurement.values[0] = report.raw_data[0] * adc_raw_scale * _adc1_scale.get();
measurement.unit_type[0] = adc1_unit;
}
if (adc2_unit) {
measurement.values[1] = report.raw_data[1] * adc_raw_scale * _adc2_scale.get();
measurement.unit_type[1] = adc2_unit;
}
if (adc3_unit) {
measurement.values[2] = report.raw_data[2] * adc_raw_scale * _adc3_scale.get();
measurement.unit_type[2] = adc3_unit;
}
if (adc4_unit) {
measurement.values[3] = report.raw_data[3] * adc_raw_scale * _adc4_scale.get();
measurement.unit_type[3] = adc4_unit;
}
_analog_measurement_pub.publish(measurement);
}
}
int AnalogMeasurement::task_spawn(int argc, char *argv[])
{
AnalogMeasurement *instance = new AnalogMeasurement();
if (instance) {
_object.store(instance);
_task_id = task_id_is_work_queue;
if (instance->init()) {
return PX4_OK;
}
} else {
PX4_ERR("alloc failed");
}
delete instance;
_object.store(nullptr);
_task_id = -1;
return PX4_ERROR;
}
int AnalogMeasurement::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");
}
int AnalogMeasurement::print_usage(const char *reason)
{
if (reason) {
PX4_WARN("%s\n", reason);
}
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
This module reads the adc_report and converts the raw adc values into voltage,
current, or temperature depending on the parameter ADC[N]_UNIT and applies the
scale factor ADC[N]_SCALE.
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("analog_measurement", "driver");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
return 0;
}
int analog_measurement_main(int argc, char *argv[])
{
return AnalogMeasurement::main(argc, argv);
}

View File

@ -0,0 +1,92 @@
/****************************************************************************
*
* Copyright (c) 2013-2019 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <matrix/matrix/math.hpp>
#include <perf/perf_counter.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/px4_work_queue/WorkItem.hpp>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionCallback.hpp>
#include <uORB/topics/adc_report.h>
#include <uORB/topics/analog_measurement.h>
extern "C" __EXPORT int analog_measurement_main(int argc, char *argv[]);
class AnalogMeasurement : public ModuleBase<AnalogMeasurement>, public ModuleParams,
public px4::WorkItem
{
public:
AnalogMeasurement();
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
/** @see ModuleBase */
static int custom_command(int argc, char *argv[]);
/** @see ModuleBase */
static int print_usage(const char *reason = nullptr);
bool init();
private:
void Run() override;
uORB::SubscriptionCallbackWorkItem _adc_report_sub{this, ORB_ID(adc_report)};
uORB::Publication<analog_measurement_s> _analog_measurement_pub{ORB_ID(analog_measurement)};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::ADC1_SCALE>) _adc1_scale,
(ParamFloat<px4::params::ADC2_SCALE>) _adc2_scale,
(ParamFloat<px4::params::ADC3_SCALE>) _adc3_scale,
(ParamFloat<px4::params::ADC4_SCALE>) _adc4_scale,
(ParamInt<px4::params::ADC1_UNIT>) _adc1_unit,
(ParamInt<px4::params::ADC2_UNIT>) _adc2_unit,
(ParamInt<px4::params::ADC3_UNIT>) _adc3_unit,
(ParamInt<px4::params::ADC4_UNIT>) _adc4_unit
)
};

View File

@ -0,0 +1,25 @@
/**
* Scale factor for ADC to convert raw to units
*/
PARAM_DEFINE_FLOAT(ADC1_SCALE, 1.0);
PARAM_DEFINE_FLOAT(ADC2_SCALE, 1.0);
PARAM_DEFINE_FLOAT(ADC3_SCALE, 1.0);
PARAM_DEFINE_FLOAT(ADC4_SCALE, 1.0);
/**
* Unit type:
* 0: none
* 1: mV
* 2: mA
* 3: cK
*
* @min 0
* @max 3
* @group Analog Measurement
*/
PARAM_DEFINE_INT32(ADC1_UNIT, 0);
PARAM_DEFINE_INT32(ADC2_UNIT, 0);
PARAM_DEFINE_INT32(ADC3_UNIT, 0);
PARAM_DEFINE_INT32(ADC4_UNIT, 0);

View File

@ -49,6 +49,7 @@ void LoggedTopics::add_default_topics()
add_topic("actuator_controls_1", 100);
add_topic("airspeed", 1000);
add_topic("airspeed_validated", 1000);
add_topic("analog_measurement", 100);
add_topic("camera_capture");
add_topic("camera_trigger");
add_topic("camera_trigger_secondary");