uavcan: add RelPosHeading->sensor_gnss_relative

This commit is contained in:
alexklimaj 2023-11-01 15:15:17 -06:00 committed by Daniel Agar
parent db60bbc46b
commit 3ff1f213a4
7 changed files with 176 additions and 2 deletions

View File

@ -15,8 +15,8 @@ float32[3] position_accuracy # Accuracy of relative position (m)
float32 heading # Heading of the relative position vector (radians)
float32 heading_accuracy # Accuracy of heading of the relative position vector (radians)
float32 position_length
float32 accuracy_length
float32 position_length # Length of the position vector (m)
float32 accuracy_length # Accuracy of the position length (m)
bool gnss_fix_ok # GNSS valid fix (i.e within DOP & accuracy masks)
bool differential_solution # differential corrections were applied

View File

@ -167,6 +167,7 @@ px4_add_module(
sensors/battery.cpp
sensors/airspeed.cpp
sensors/flow.cpp
sensors/gnss_relative.cpp
sensors/gnss.cpp
sensors/mag.cpp
sensors/rangefinder.cpp

View File

@ -57,6 +57,10 @@ if DRIVERS_UAVCAN
bool "Subscribe to GPS: uavcan::equipment::gnss::Auxiliary | uavcan::equipment::gnss::Fix | uavcan::equipment::gnss::Fix2"
default y
config UAVCAN_SENSOR_GNSS_RELATIVE
bool "Subscribe to GPS Relative: ardupilot::equipment::gnss::RelPosHeading"
default y
config UAVCAN_SENSOR_HYGROMETER
bool "Subscribe to Hygrometer: dronecan::sensors::hygrometer::Hygrometer"
default y

View File

@ -0,0 +1,78 @@
/****************************************************************************
*
* 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 "gnss_relative.hpp"
#include <drivers/drv_hrt.h>
#include <lib/mathlib/math/Limits.hpp>
const char *const UavcanGnssRelativeBridge::NAME = "gnss_relative";
UavcanGnssRelativeBridge::UavcanGnssRelativeBridge(uavcan::INode &node) :
UavcanSensorBridgeBase("uavcan_gnss_relative", ORB_ID(sensor_gnss_relative)),
_sub_rel_pos_heading(node)
{
}
int
UavcanGnssRelativeBridge::init()
{
int res = _sub_rel_pos_heading.start(RelPosHeadingCbBinder(this, &UavcanGnssRelativeBridge::rel_pos_heading_sub_cb));
if (res < 0) {
DEVICE_LOG("failed to start uavcan sub: %d", res);
return res;
}
return 0;
}
void UavcanGnssRelativeBridge::rel_pos_heading_sub_cb(const
uavcan::ReceivedDataStructure<ardupilot::gnss::RelPosHeading> &msg)
{
sensor_gnss_relative_s sensor_gnss_relative{};
sensor_gnss_relative.timestamp_sample = uavcan::UtcTime(msg.timestamp).toUSec();
sensor_gnss_relative.heading_valid = msg.reported_heading_acc_available;
sensor_gnss_relative.heading = math::radians(msg.reported_heading_deg);
sensor_gnss_relative.heading_accuracy = math::radians(msg.reported_heading_acc_deg);
sensor_gnss_relative.position_length = msg.relative_distance_m;
sensor_gnss_relative.position[2] = msg.relative_down_pos_m;
sensor_gnss_relative.device_id = get_device_id();
sensor_gnss_relative.timestamp = hrt_absolute_time();
publish(msg.getSrcNodeID().get(), &sensor_gnss_relative);
}

View File

@ -0,0 +1,65 @@
/****************************************************************************
*
* 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 <stdint.h>
#include <uORB/topics/sensor_gnss_relative.h>
#include <ardupilot/gnss/RelPosHeading.hpp>
class UavcanGnssRelativeBridge : public UavcanSensorBridgeBase
{
public:
static const char *const NAME;
UavcanGnssRelativeBridge(uavcan::INode &node);
const char *get_name() const override { return NAME; }
int init() override;
private:
void rel_pos_heading_sub_cb(const uavcan::ReceivedDataStructure<ardupilot::gnss::RelPosHeading> &msg);
typedef uavcan::MethodBinder < UavcanGnssRelativeBridge *,
void (UavcanGnssRelativeBridge::*)(const uavcan::ReceivedDataStructure<ardupilot::gnss::RelPosHeading> &) >
RelPosHeadingCbBinder;
uavcan::Subscriber<ardupilot::gnss::RelPosHeading, RelPosHeadingCbBinder> _sub_rel_pos_heading;
};

View File

@ -60,6 +60,9 @@
#if defined(CONFIG_UAVCAN_SENSOR_GNSS)
#include "gnss.hpp"
#endif
#if defined(CONFIG_UAVCAN_SENSOR_GNSS_RELATIVE)
#include "gnss_relative.hpp"
#endif
#if defined(CONFIG_UAVCAN_SENSOR_HYGROMETER)
#include "hygrometer.hpp"
#endif
@ -145,6 +148,17 @@ void IUavcanSensorBridge::make_all(uavcan::INode &node, List<IUavcanSensorBridge
list.add(new UavcanGnssBridge(node));
}
#endif
// GPS relative
#if defined(CONFIG_UAVCAN_SENSOR_GNSS_RELATIVE)
int32_t uavcan_sub_gps_rel = 1;
param_get(param_find("UAVCAN_SUB_GPS_R"), &uavcan_sub_gps_rel);
if (uavcan_sub_gps_rel != 0) {
list.add(new UavcanGnssRelativeBridge(node));
}
#endif
// hygrometer

View File

@ -306,6 +306,18 @@ PARAM_DEFINE_INT32(UAVCAN_SUB_FLOW, 0);
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_GPS, 1);
/**
* subscription GPS Relative
*
* Enable UAVCAN GPS Relative subscription.
* ardupilot::gnss::RelPosHeading
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_GPS_R, 1);
/**
* subscription hygrometer
*