Browse Source

uavcan: support uavcan hygrometer

master
honglang 3 years ago committed by Daniel Agar
parent
commit
983867f9af
  1. 2
      src/drivers/uavcan/CMakeLists.txt
  2. 2
      src/drivers/uavcan/libuavcan
  3. 73
      src/drivers/uavcan/sensors/hygrometer.cpp
  4. 61
      src/drivers/uavcan/sensors/hygrometer.hpp
  5. 23
      src/drivers/uavcan/sensors/sensor_bridge.cpp
  6. 12
      src/drivers/uavcan/uavcan_params.c
  7. 1
      src/drivers/uavcannode/CMakeLists.txt

2
src/drivers/uavcan/CMakeLists.txt

@ -102,6 +102,7 @@ set(DSDLC_INPUTS @@ -102,6 +102,7 @@ set(DSDLC_INPUTS
"${LIBUAVCAN_DIR}/dsdl/ardupilot"
"${LIBUAVCAN_DIR}/dsdl/com"
"${LIBUAVCAN_DIR}/dsdl/cuav"
"${LIBUAVCAN_DIR}/dsdl/dronecan"
"${LIBUAVCAN_DIR}/dsdl/uavcan"
)
set(DSDLC_OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/include/dsdlc_generated")
@ -163,6 +164,7 @@ px4_add_module( @@ -163,6 +164,7 @@ px4_add_module(
sensors/gyro.cpp
sensors/cbat.cpp
sensors/ice_status.cpp
sensors/hygrometer.cpp
MODULE_CONFIG
module.yaml

2
src/drivers/uavcan/libuavcan

@ -1 +1 @@ @@ -1 +1 @@
Subproject commit 76b2c4c33858fcde18c50d29184273a495bdbbd1
Subproject commit 9c09983f737de0dd224d26025f8f439d6d860b27

73
src/drivers/uavcan/sensors/hygrometer.cpp

@ -0,0 +1,73 @@ @@ -0,0 +1,73 @@
/****************************************************************************
*
* Copyright (c) 2021 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 "hygrometer.hpp"
#include <drivers/drv_hrt.h>
#include <lib/geo/geo.h>
const char *const UavcanHygrometerBridge::NAME = "hygrometer_sensor";
UavcanHygrometerBridge::UavcanHygrometerBridge(uavcan::INode &node) :
UavcanSensorBridgeBase("uavcan_hygrometer_sensor", ORB_ID(sensor_hygrometer)),
_sub_hygro(node)
{
}
int UavcanHygrometerBridge::init()
{
int res = _sub_hygro.start(HygroCbBinder(this, &UavcanHygrometerBridge::hygro_sub_cb));
if (res < 0) {
DEVICE_LOG("failed to start uavcan sub: %d", res);
return res;
}
return 0;
}
void UavcanHygrometerBridge::hygro_sub_cb(const uavcan::ReceivedDataStructure<dronecan::sensors::hygrometer::Hygrometer>
&msg)
{
const hrt_abstime timestamp_sample = hrt_absolute_time();
sensor_hygrometer_s report{};
report.timestamp_sample = timestamp_sample;
report.device_id = 0; // TODO
report.temperature = msg.temperature + CONSTANTS_ABSOLUTE_NULL_CELSIUS;
report.humidity = msg.humidity;
report.timestamp = hrt_absolute_time();
publish(msg.getSrcNodeID().get(), &report);
}

61
src/drivers/uavcan/sensors/hygrometer.hpp

@ -0,0 +1,61 @@ @@ -0,0 +1,61 @@
/****************************************************************************
*
* Copyright (c) 2021 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 <uORB/topics/sensor_hygrometer.h>
#include "sensor_bridge.hpp"
#include <dronecan/sensors/hygrometer/Hygrometer.hpp>
class UavcanHygrometerBridge : public UavcanSensorBridgeBase
{
public:
static const char *const NAME;
UavcanHygrometerBridge(uavcan::INode &node);
const char *get_name() const override { return NAME; }
int init() override;
private:
void hygro_sub_cb(const uavcan::ReceivedDataStructure<dronecan::sensors::hygrometer::Hygrometer> &msg);
typedef uavcan::MethodBinder < UavcanHygrometerBridge *,
void (UavcanHygrometerBridge::*)
(const uavcan::ReceivedDataStructure<dronecan::sensors::hygrometer::Hygrometer> &) >
HygroCbBinder;
uavcan::Subscriber<dronecan::sensors::hygrometer::Hygrometer, HygroCbBinder> _sub_hygro;
};

23
src/drivers/uavcan/sensors/sensor_bridge.cpp

@ -38,18 +38,19 @@ @@ -38,18 +38,19 @@
#include "sensor_bridge.hpp"
#include <cassert>
#include "differential_pressure.hpp"
#include "accel.hpp"
#include "airspeed.hpp"
#include "baro.hpp"
#include "battery.hpp"
#include "airspeed.hpp"
#include "gnss.hpp"
#include "cbat.hpp"
#include "differential_pressure.hpp"
#include "flow.hpp"
#include "mag.hpp"
#include "rangefinder.hpp"
#include "accel.hpp"
#include "gnss.hpp"
#include "gyro.hpp"
#include "cbat.hpp"
#include "hygrometer.hpp"
#include "ice_status.hpp"
#include "mag.hpp"
#include "rangefinder.hpp"
/*
* IUavcanSensorBridge
@ -107,6 +108,14 @@ void IUavcanSensorBridge::make_all(uavcan::INode &node, List<IUavcanSensorBridge @@ -107,6 +108,14 @@ void IUavcanSensorBridge::make_all(uavcan::INode &node, List<IUavcanSensorBridge
list.add(new UavcanGnssBridge(node));
}
// hygrometer
int32_t uavcan_sub_hygro = 1;
param_get(param_find("UAVCAN_SUB_HYGRO"), &uavcan_sub_hygro);
if (uavcan_sub_hygro != 0) {
list.add(new UavcanHygrometerBridge(node));
}
// ice (internal combustion engine)
int32_t uavcan_sub_ice = 1;
param_get(param_find("UAVCAN_SUB_ICE"), &uavcan_sub_ice);

12
src/drivers/uavcan/uavcan_params.c

@ -275,6 +275,18 @@ PARAM_DEFINE_INT32(UAVCAN_SUB_FLOW, 0); @@ -275,6 +275,18 @@ PARAM_DEFINE_INT32(UAVCAN_SUB_FLOW, 0);
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_GPS, 1);
/**
* subscription hygrometer
*
* Enable UAVCAN hygrometer subscriptions.
* dronecan::sensors::hygrometer::Hygrometer
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_HYGRO, 0);
/**
* subscription ICE
*

1
src/drivers/uavcannode/CMakeLists.txt

@ -102,6 +102,7 @@ set(DSDLC_INPUTS @@ -102,6 +102,7 @@ set(DSDLC_INPUTS
"${LIBUAVCAN_DIR}/dsdl/ardupilot"
"${LIBUAVCAN_DIR}/dsdl/com"
"${LIBUAVCAN_DIR}/dsdl/cuav"
"${LIBUAVCAN_DIR}/dsdl/dronecan"
"${LIBUAVCAN_DIR}/dsdl/uavcan"
)
set(DSDLC_OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/include/dsdlc_generated")

Loading…
Cancel
Save