Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open Drone ID Live GNSS and Arm status prototype #21647

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions msg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -151,6 +151,11 @@ set(msg_files
ObstacleDistance.msg
OffboardControlMode.msg
OnboardComputerStatus.msg
OpenDroneIdArmStatus.msg
OpenDroneIdBasicId.msg
OpenDroneIdOperatorId.msg
OpenDroneIdSelfId.msg
OpenDroneIdSystem.msg
OrbitStatus.msg
OrbTest.msg
OrbTestLarge.msg
Expand Down
3 changes: 3 additions & 0 deletions msg/OpenDroneIdArmStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
uint64 timestamp
uint8 status
dirksavage88 marked this conversation as resolved.
Show resolved Hide resolved
char[50] error
7 changes: 7 additions & 0 deletions msg/OpenDroneIdBasicId.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
uint64 timestamp
uint8 target_system
uint8 target_component
uint8[20] id_or_mac
uint8 id_type
uint8 ua_type
uint8[20] uas_id
6 changes: 6 additions & 0 deletions msg/OpenDroneIdOperatorId.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
uint64 timestamp
uint8 target_system
uint8 target_component
uint8[20] id_or_mac
uint8 operator_id_type
char[20] operator_id
6 changes: 6 additions & 0 deletions msg/OpenDroneIdSelfId.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
uint64 timestamp
uint8 target_system
uint8 target_component
uint8[20] id_or_mac
uint8 description_type
char[23] description
15 changes: 15 additions & 0 deletions msg/OpenDroneIdSystem.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
uint64 timestamp
uint8 target_system
uint8 target_component
uint8[20] id_or_mac
uint8 operator_location_type
uint8 classification_type
int32 operator_latitude
int32 operator_longitude
uint16 area_count
uint16 area_radius
float32 area_ceiling
float32 area_floor
uint8 category_eu
uint8 class_eu
float32 operator_altitude_geo
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2023 PX4 Development Team. All rights reserved.
* Copyright (c) 2024 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
Expand Down Expand Up @@ -33,6 +33,7 @@

#include "openDroneIDCheck.hpp"

#define ODID_ARM_FAIL 1

void OpenDroneIDChecks::checkAndReport(const Context &context, Report &reporter)
{
Expand All @@ -41,46 +42,55 @@ void OpenDroneIDChecks::checkAndReport(const Context &context, Report &reporter)
return;
}

// ODID module arm status topic
open_drone_id_arm_status_s odid_module_arm_status;

NavModes affected_modes{NavModes::None};

if (_param_com_arm_odid.get() == 2) {
// disallow arming without the Open Drone ID system
affected_modes = NavModes::All;
}

if (!context.status().open_drone_id_system_present) {
/* EVENT
* @description
* Open Drone ID system failed to report. Make sure it is setup and installed properly.
*
* <profile name="dev">
* This check can be configured via <param>COM_ARM_ODID</param> parameter.
* </profile>
*/
reporter.armingCheckFailure(affected_modes, health_component_t::open_drone_id,
events::ID("check_open_drone_id_missing"),
events::Log::Error, "Open Drone ID system missing");
if (_open_drone_id_arm_status_sub.copy(&odid_module_arm_status)) {

// Check ODID arm status
if (odid_module_arm_status.status == ODID_ARM_FAIL) {
/* EVENT
* @description
* Open Drone ID system reported being unhealthy.
*
* <profile name="dev">
* This check can be ignored or set to warning via <param>COM_ARM_ODID</param> parameter.
* </profile>
*/
reporter.armingCheckFailure(affected_modes, health_component_t::open_drone_id,
events::ID("check_open_drone_id_unhealthy"),
events::Log::Error, "Open Drone ID arm status error");

if (reporter.mavlink_log_pub()) {
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Open Drone ID arm status error");
}

if (reporter.mavlink_log_pub()) {
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Open Drone ID system missing");
}

} else if (!context.status().open_drone_id_system_healthy) {
} else if (!context.status().open_drone_id_system_present) {
/* EVENT
* @description
* Open Drone ID system reported being unhealthy.
*
* <profile name="dev">
* This check can be configured via <param>COM_ARM_ODID</param> parameter.
* </profile>
*/
* @description
* Open Drone ID system failed to report. Make sure it is setup and installed properly.
*
* <profile name="dev">
* This check can be configured via <param>COM_ARM_ODID</param> parameter.
* </profile>
*/
reporter.armingCheckFailure(affected_modes, health_component_t::open_drone_id,
events::ID("check_open_drone_id_unhealthy"),
events::Log::Error, "Open Drone ID system not ready");
events::ID("check_open_drone_id_missing"),
events::Log::Error, "Open Drone ID system missing");

if (reporter.mavlink_log_pub()) {
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Open Drone ID system not ready");
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Open Drone ID system missing");
}

}

}
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,8 @@
#pragma once

#include "../Common.hpp"
#include <uORB/Subscription.hpp>
#include <uORB/topics/open_drone_id_arm_status.h>

class OpenDroneIDChecks : public HealthAndArmingCheckBase
{
Expand All @@ -47,4 +49,5 @@ class OpenDroneIDChecks : public HealthAndArmingCheckBase
DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase,
(ParamInt<px4::params::COM_ARM_ODID>) _param_com_arm_odid
)
uORB::Subscription _open_drone_id_arm_status_sub{ORB_ID(open_drone_id_arm_status)};
};
16 changes: 8 additions & 8 deletions src/modules/mavlink/mavlink_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1421,14 +1421,14 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
configure_stream_local("GPS_RAW_INT", 5.0f);
configure_stream_local("GPS_STATUS", 1.0f);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("HOME_POSITION", 1.5f);
configure_stream_local("HYGROMETER_SENSOR", 0.1f);
configure_stream_local("LOCAL_POSITION_NED", 1.0f);
configure_stream_local("MOUNT_ORIENTATION", 10.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.0f);
configure_stream_local("OBSTACLE_DISTANCE", 1.0f);
configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f);
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);
Expand Down Expand Up @@ -1490,11 +1490,11 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
configure_stream_local("GPS_RAW_INT", unlimited_rate);
configure_stream_local("GPS_STATUS", 1.0f);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("HOME_POSITION", 1.5f);
configure_stream_local("HYGROMETER_SENSOR", 1.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f);
configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f);
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);
Expand Down Expand Up @@ -1648,13 +1648,13 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("GPS_RAW_INT", unlimited_rate);
configure_stream_local("GPS_STATUS", 1.0f);
configure_stream_local("HIGHRES_IMU", 50.0f);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("HOME_POSITION", 1.5f);
configure_stream_local("HYGROMETER_SENSOR", 1.0f);
configure_stream_local("MAG_CAL_REPORT", 1.0f);
configure_stream_local("MANUAL_CONTROL", 5.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f);
configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f);
Copy link
Contributor

@hamishwillee hamishwillee Jun 29, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why are we streaming OPEN_DRONE_ID_ARM_STATUS? Its inbound from the remoteID hardware. Should be used to indicate healthy/unhealthy for the remoteID.

I.e. an update to #21652

I'm probably missing something ...

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The Bluemark module requires the stream to work correctly. Without it, the module health checks are not satisfied and arming is prevented. Perhaps Bluemark can clarify on why this is.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

how much of this behaviour is defined in the spec vs left to the manufacturer to figure out?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@tridge may know more about the how the spec has been implemented. The vendor may have just an abstraction layer on top of ODID core library for their specific hardware. Or they may use proprietary software and just satisfy the mavlink ODID definitions and don’t use ardu (or ODID core library)

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yeah even in Ardupilot, the ARM_STATUS message isn't getting sent out, so I am puzzled as to why Bluemark module needs it 🤔

https://github.com/ArduPilot/ardupilot/blob/5fa8b887a2df8a85822f84f41eec64bef5066895/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp#L266-L326

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The Bluemark module requires the stream to work correctly. Without it, the module health checks are not satisfied and arming is prevented. Perhaps Bluemark can clarify on why this is.

Well in the standard Remote ID regulation, you need to make sure the Remote ID information is correct and there are no failures. So if the Remote ID module detect an issue, it should report it back to the GCS.

Note there are open PRs that needs to be merged into master of ArduRemoteID: PR#101 and PR#102 that will improve these checks or its status message.

Copy link
Contributor

@hamishwillee hamishwillee Jul 5, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@BluemarkInnovations I was going to sarcastically say where did you get that "requirement", but you're absolutely right - its in the MAVLink spec:

Similarly, the autopilot and GCS components must listen to the ARM_STATUS from the RID transmitter component(s) and not allow the UA to be airborne before the RID transmitter component(s) is ready. During flight, if the arm status indicates a failure, similar action must be taken as for a lack of HEARTBEAT messages.

The vehicle shouldn't start if it doesn't have this so what the GCS does is irrelevant. Though this is needed for monitoring the precise cause of arming failure, unless the flight stack were to emit an event (and none is standardized).

@dirksavage88 What is interesting here is that the status would also have to be updated in LOCATION (that is what appears to happen if the HEARTBEAT disappears).

I'll see if I can tidy the spec: mavlink/mavlink-devguide#511

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

FWIW I don't think this should be streamed by default. If there is no GPS then firing this off is a waste of bandwidth. perhaps it could be requested by GCS or enabled by a parameter.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Late to the party as I only started looking into Remote ID yesterday, but I had the same initial reaction as @hamishwillee back in June.

In my mind it's more logical if you just set up mavlink forwarding so that the GCS can subscribe directly to the topic from the Remote ID hardware without going through the "useless" steps of repackaging the incoming message and publishing it as uORB only to subscribe to the uORB message to republish a mavlink message with basically the same content as the initial message.

Maybe I am too naive and miss something essential here?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, that would make sense, just forwarding it. However, for a module that talks DroneCAN or some other protocol, this might be required again.

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);
Expand Down Expand Up @@ -1740,10 +1740,10 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
configure_stream_local("GPS2_RAW", unlimited_rate);
configure_stream_local("GPS_RAW_INT", unlimited_rate);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("HOME_POSITION", 1.5f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.5f);
configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f);
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);
Expand Down
12 changes: 10 additions & 2 deletions src/modules/mavlink/mavlink_messages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,9 +94,8 @@
#include "streams/MOUNT_ORIENTATION.hpp"
#include "streams/NAV_CONTROLLER_OUTPUT.hpp"
#include "streams/OBSTACLE_DISTANCE.hpp"
#include "streams/OPEN_DRONE_ID_BASIC_ID.hpp"
#include "streams/OPEN_DRONE_ID_ARM_STATUS.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"
Expand Down Expand Up @@ -445,12 +444,21 @@ static const StreamListItem streams_list[] = {
#if defined(OBSTACLE_DISTANCE_HPP)
create_stream_list_item<MavlinkStreamObstacleDistance>(),
#endif // OBSTACLE_DISTANCE_HPP
#if defined(OPEN_DRONE_ID_ARM_STATUS_HPP)
create_stream_list_item<MavlinkStreamOpenDroneIdArmStatus>(),
#endif // OPEN_DRONE_ID_ARM_STATUS_HPP
#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_HPP)
create_stream_list_item<MavlinkStreamOpenDroneIdLocation>(),
#endif // OPEN_DRONE_ID_LOCATION_HPP
#if defined(OPEN_DRONE_ID_OPERATOR_ID_HPP)
create_stream_list_item<MavlinkStreamOpenDroneIdOperatorId>(),
#endif // OPEN_DRONE_ID_OPERATOR_ID_HPP
#if defined(OPEN_DRONE_ID_SELF_ID_HPP)
create_stream_list_item<MavlinkStreamOpenDroneIdSelfId>(),
#endif // OPEN_DRONE_ID_SELF_ID_HPP
#if defined(OPEN_DRONE_ID_SYSTEM_HPP)
create_stream_list_item<MavlinkStreamOpenDroneIdSystem>(),
#endif // OPEN_DRONE_ID_SYSTEM_HPP
Expand Down
Loading
Loading