From be3d09c700cff506d10109dcadf7d2d126884ab0 Mon Sep 17 00:00:00 2001 From: Daniele Pettenuzzo Date: Thu, 15 Aug 2019 18:22:29 +0200 Subject: [PATCH] uavcan: add optical flow support (Here Flow) * move uavcan dsdlc generation to module * 20200.Measurement.uavcan sync with upstream project (https://github.com/OpenMotorDrive/flow/blob/master/dsdl/com/hex/equipment/flow/20200.Measurement.uavcan) Signed-off-by: DanielePettenuzzo --- src/drivers/uavcan/CMakeLists.txt | 23 ++++- .../equipment/flow/20200.Measurement.uavcan | 4 + src/drivers/uavcan/sensors/flow.cpp | 83 +++++++++++++++++++ src/drivers/uavcan/sensors/flow.hpp | 67 +++++++++++++++ src/drivers/uavcan/sensors/sensor_bridge.cpp | 2 + 5 files changed, 178 insertions(+), 1 deletion(-) create mode 100644 src/drivers/uavcan/dsdl/com/hex/equipment/flow/20200.Measurement.uavcan create mode 100644 src/drivers/uavcan/sensors/flow.cpp create mode 100644 src/drivers/uavcan/sensors/flow.hpp diff --git a/src/drivers/uavcan/CMakeLists.txt b/src/drivers/uavcan/CMakeLists.txt index bc504b8455..065e172991 100644 --- a/src/drivers/uavcan/CMakeLists.txt +++ b/src/drivers/uavcan/CMakeLists.txt @@ -71,12 +71,31 @@ add_compile_options(-Wno-cast-align) # TODO: fix and enable add_subdirectory(libuavcan EXCLUDE_FROM_ALL) add_dependencies(uavcan prebuild_targets) + +# generated DSDL +set(DSDLC_INPUTS "${CMAKE_CURRENT_SOURCE_DIR}/dsdl/com" "${CMAKE_CURRENT_SOURCE_DIR}/libuavcan/dsdl/uavcan") +set(DSDLC_OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/include/dsdlc_generated") + +set(DSDLC_INPUT_FILES) +foreach(DSDLC_INPUT ${DSDLC_INPUTS}) + file(GLOB_RECURSE DSDLC_NEW_INPUT_FILES ${CMAKE_CURRENT_SOURCE_DIR} "${DSDLC_INPUT}/*.uavcan") + list(APPEND DSDLC_INPUT_FILES ${DSDLC_NEW_INPUT_FILES}) +endforeach(DSDLC_INPUT) +add_custom_command(OUTPUT px4_uavcan_dsdlc_run.stamp + COMMAND ${PYTHON} ${CMAKE_CURRENT_SOURCE_DIR}/libuavcan/libuavcan/dsdl_compiler/libuavcan_dsdlc ${DSDLC_INPUTS} -O${DSDLC_OUTPUT} + COMMAND ${CMAKE_COMMAND} -E touch px4_uavcan_dsdlc_run.stamp + DEPENDS ${DSDLC_INPUT_FILES} + COMMENT "PX4 UAVCAN dsdl compiler" + ) +add_custom_target(px4_uavcan_dsdlc DEPENDS px4_uavcan_dsdlc_run.stamp) + px4_add_module( MODULE modules__uavcan MAIN uavcan STACK_MAIN 3200 STACK_MAX 1500 INCLUDES + ${DSDLC_OUTPUT} ${PX4_SOURCE_DIR}/mavlink/include/mavlink libuavcan/libuavcan/include libuavcan/libuavcan/include/dsdlc_generated @@ -97,15 +116,17 @@ px4_add_module( sensors/gnss.cpp sensors/mag.cpp sensors/baro.cpp + sensors/flow.cpp DEPENDS + px4_uavcan_dsdlc + mixer version git_uavcan # within libuavcan - libuavcan_dsdlc uavcan uavcan_${UAVCAN_PLATFORM}_driver ) diff --git a/src/drivers/uavcan/dsdl/com/hex/equipment/flow/20200.Measurement.uavcan b/src/drivers/uavcan/dsdl/com/hex/equipment/flow/20200.Measurement.uavcan new file mode 100644 index 0000000000..093a9a1c2b --- /dev/null +++ b/src/drivers/uavcan/dsdl/com/hex/equipment/flow/20200.Measurement.uavcan @@ -0,0 +1,4 @@ +float32 integration_interval +float32[2] rate_gyro_integral +float32[2] flow_integral +uint8 quality diff --git a/src/drivers/uavcan/sensors/flow.cpp b/src/drivers/uavcan/sensors/flow.cpp new file mode 100644 index 0000000000..d2e6c25364 --- /dev/null +++ b/src/drivers/uavcan/sensors/flow.cpp @@ -0,0 +1,83 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "flow.hpp" + +#include + +const char *const UavcanFlowBridge::NAME = "flow"; + +UavcanFlowBridge::UavcanFlowBridge(uavcan::INode &node) : + UavcanCDevSensorBridgeBase("uavcan_flow", "/dev/uavcan/flow", "/dev/flow", ORB_ID(optical_flow)), + _sub_flow(node) +{ +} + +int +UavcanFlowBridge::init() +{ + int res = device::CDev::init(); + + if (res < 0) { + return res; + } + + res = _sub_flow.start(FlowCbBinder(this, &UavcanFlowBridge::flow_sub_cb)); + + if (res < 0) { + DEVICE_LOG("failed to start uavcan sub: %d", res); + return res; + } + + return 0; +} + +void +UavcanFlowBridge::flow_sub_cb(const uavcan::ReceivedDataStructure &msg) +{ + optical_flow_s flow{}; + + flow.timestamp = hrt_absolute_time(); + flow.pixel_flow_x_integral = msg.flow_integral[0]; + flow.pixel_flow_y_integral = msg.flow_integral[1]; + + flow.gyro_x_rate_integral = msg.rate_gyro_integral[0]; + flow.gyro_y_rate_integral = msg.rate_gyro_integral[1]; + + flow.quality = msg.quality; + flow.max_flow_rate = 5.0f; // Datasheet: 7.4 rad/s + flow.min_ground_distance = 0.1f; // Datasheet: 80mm + flow.max_ground_distance = 30.0f; // Datasheet: infinity + + publish(msg.getSrcNodeID().get(), &flow); +} diff --git a/src/drivers/uavcan/sensors/flow.hpp b/src/drivers/uavcan/sensors/flow.hpp new file mode 100644 index 0000000000..40a398a48e --- /dev/null +++ b/src/drivers/uavcan/sensors/flow.hpp @@ -0,0 +1,67 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#include "sensor_bridge.hpp" + +#include +#include + +#include + +#include + +class UavcanFlowBridge : public UavcanCDevSensorBridgeBase +{ +public: + static const char *const NAME; + + UavcanFlowBridge(uavcan::INode &node); + + const char *get_name() const override { return NAME; } + + int init() override; + +private: + + void flow_sub_cb(const uavcan::ReceivedDataStructure &msg); + + typedef uavcan::MethodBinder < UavcanFlowBridge *, + void (UavcanFlowBridge::*) + (const uavcan::ReceivedDataStructure &) > + FlowCbBinder; + + uavcan::Subscriber _sub_flow; + +}; diff --git a/src/drivers/uavcan/sensors/sensor_bridge.cpp b/src/drivers/uavcan/sensors/sensor_bridge.cpp index fec12209d6..39cb57df2b 100644 --- a/src/drivers/uavcan/sensors/sensor_bridge.cpp +++ b/src/drivers/uavcan/sensors/sensor_bridge.cpp @@ -41,6 +41,7 @@ #include "gnss.hpp" #include "mag.hpp" #include "baro.hpp" +#include "flow.hpp" /* * IUavcanSensorBridge @@ -50,6 +51,7 @@ void IUavcanSensorBridge::make_all(uavcan::INode &node, List