mavlink: add initial mavlink OPEN_DRONE_ID_SYSTEM stream

This commit is contained in:
Daniel Agar 2022-10-20 14:14:05 -04:00
parent 696eeb9a49
commit 4d318ebd30
4 changed files with 119 additions and 6 deletions

View File

@ -1515,7 +1515,8 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("LOCAL_POSITION_NED", 1.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.0f);
configure_stream_local("OBSTACLE_DISTANCE", 1.0f);
configure_stream_local("OPEN_DRONE_ID_LOCATION", 0.1f);
configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f);
configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 2.0f);
configure_stream_local("PING", 0.1f);
configure_stream_local("POSITION_TARGET_GLOBAL_INT", 1.0f);
@ -1578,6 +1579,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("HYGROMETER_SENSOR", 1.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f);
configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f);
configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f);
configure_stream_local("OPTICAL_FLOW_RAD", 10.0f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
configure_stream_local("PING", 1.0f);
@ -1730,6 +1732,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("MANUAL_CONTROL", 5.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f);
configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f);
configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f);
configure_stream_local("OPTICAL_FLOW_RAD", 10.0f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
configure_stream_local("PING", 1.0f);
@ -1811,6 +1814,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.5f);
configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f);
configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f);
configure_stream_local("OPTICAL_FLOW_RAD", 1.0f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
configure_stream_local("PING", 0.1f);

View File

@ -97,6 +97,7 @@
#include "streams/OBSTACLE_DISTANCE.hpp"
#include "streams/OPEN_DRONE_ID_BASIC_ID.hpp"
#include "streams/OPEN_DRONE_ID_LOCATION.hpp"
#include "streams/OPEN_DRONE_ID_SYSTEM.hpp"
#include "streams/OPTICAL_FLOW_RAD.hpp"
#include "streams/ORBIT_EXECUTION_STATUS.hpp"
#include "streams/PING.hpp"
@ -436,9 +437,12 @@ static const StreamListItem streams_list[] = {
#if defined(OPEN_DRONE_ID_BASIC_ID_HPP)
create_stream_list_item<MavlinkStreamOpenDroneIdBasicId>(),
#endif // OPEN_DRONE_ID_BASIC_ID_HPP
#if defined(OPEN_DRONE_ID_LOCATION)
#if defined(OPEN_DRONE_ID_LOCATION_HPP)
create_stream_list_item<MavlinkStreamOpenDroneIdLocation>(),
#endif // OPEN_DRONE_ID_LOCATION
#endif // OPEN_DRONE_ID_LOCATION_HPP
#if defined(OPEN_DRONE_ID_SYSTEM_HPP)
create_stream_list_item<MavlinkStreamOpenDroneIdSystem>(),
#endif // OPEN_DRONE_ID_SYSTEM_HPP
#if defined(ESC_INFO_HPP)
create_stream_list_item<MavlinkStreamESCInfo>(),
#endif // ESC_INFO_HPP

View File

@ -31,8 +31,8 @@
*
****************************************************************************/
#ifndef OPEN_DRONE_ID_LOCATION
#define OPEN_DRONE_ID_LOCATION
#ifndef OPEN_DRONE_ID_LOCATION_HPP
#define OPEN_DRONE_ID_LOCATION_HPP
#include <uORB/topics/home_position.h>
#include <uORB/topics/sensor_gps.h>
@ -270,4 +270,4 @@ private:
}
};
#endif // OPEN_DRONE_ID_LOCATION
#endif // OPEN_DRONE_ID_LOCATION_HPP

View File

@ -0,0 +1,105 @@
/****************************************************************************
*
* Copyright (c) 2022 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.
*
****************************************************************************/
#ifndef OPEN_DRONE_ID_SYSTEM_HPP
#define OPEN_DRONE_ID_SYSTEM_HPP
#include <uORB/topics/home_position.h>
#include <uORB/topics/sensor_gps.h>
class MavlinkStreamOpenDroneIdSystem : public MavlinkStream
{
public:
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamOpenDroneIdSystem(mavlink); }
static constexpr const char *get_name_static() { return "OPEN_DRONE_ID_SYSTEM"; }
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM; }
const char *get_name() const override { return get_name_static(); }
uint16_t get_id() override { return get_id_static(); }
unsigned get_size() override
{
if (_vehicle_gps_position_sub.advertised() && _home_position_sub.advertised()) {
return MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
return 0;
}
private:
explicit MavlinkStreamOpenDroneIdSystem(Mavlink *mavlink) : MavlinkStream(mavlink) {}
uORB::Subscription _home_position_sub{ORB_ID(home_position)};
uORB::Subscription _vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)};
bool send() override
{
sensor_gps_s vehicle_gps_position;
home_position_s home_position;
if (_vehicle_gps_position_sub.update(&vehicle_gps_position) && _home_position_sub.copy(&home_position)) {
if (vehicle_gps_position.fix_type >= 3
&& home_position.valid_alt && home_position.valid_hpos) {
mavlink_open_drone_id_system_t msg{};
msg.target_component = 0; // 0 for broadcast
msg.target_system = 0; // 0 for broadcast
// msg.id_or_mac // Only used for drone ID data received from other UAs.
msg.operator_location_type = MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF;
msg.classification_type = MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED;
msg.operator_latitude = home_position.lat * 1e7;
msg.operator_longitude = home_position.lon * 1e7;
msg.area_count = 1;
msg.area_radius = 0;
msg.area_ceiling = -1000;
msg.area_floor = -1000;
msg.category_eu = MAV_ODID_CATEGORY_EU_UNDECLARED;
msg.class_eu = MAV_ODID_CLASS_EU_UNDECLARED;
msg.operator_altitude_geo = home_position.alt;
// timestamp: 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.
static uint64_t utc_offset_s = 1'546'300'800; // UTC seconds since 00:00:00 01/01/2019
msg.timestamp = vehicle_gps_position.time_utc_usec / 1e6 - utc_offset_s;
mavlink_msg_open_drone_id_system_send_struct(_mavlink->get_channel(), &msg);
return true;
}
}
return false;
}
};
#endif // OPEN_DRONE_ID_SYSTEM_HPP