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

Wip/opendroneid #21075

Merged
merged 13 commits into from
Aug 9, 2022
Merged

Wip/opendroneid #21075

merged 13 commits into from
Aug 9, 2022

Conversation

BluemarkInnovations
Copy link
Contributor

@BluemarkInnovations BluemarkInnovations commented Jun 29, 2022

WIP Initial Remote ID (open drone ID) implementation and tested with a Remote ID MAVLink transponder (DroneBeacon MAVlLnk transponder, https://dronescout.co/dronebeacon-mavlink-remote-id-transponder/). This command in the ArduPlane folder is used for testing: sim_vehicle.py --wipe-eeprom --console --map -A --serial1=uart:/dev/ttyUSB1:9600 (and a DroneBeacon MAVLink transponder connected to ttyUSB1)

This implementation supports these MAVLink messages:

  • Basic ID
  • Location
  • Self ID
  • System

Issues/To Do

  • current code sets dummy values for most fields in AP_OpenDroneID::init()
  • location messages uses location data from ArduPilot (function: void GCS_MAVLINK::send_open_drone_id_location()) It needs review and improvement. The received location values seem to be weird although the location data types are similar to open drone ID.
    - System messages are not received by the transponder at all. Cause unsure, perhaps MAVLink library needs to be regenerated? Even on low level the transponder does not detect this system message packet type. Other open drone ID MAVLink messages are detected. If I look to the byte stream, system messages are transmitted by sim_vehicle. Clearly something goes wrong with parsing MAVLink messages at the transponder. This is outside ArduPilot. I will do more investigation why with the (internal) test MAVLink TX application, all message types are decoded successful by the transponder, whereas with sim_vehicle it doesn't. The issue was an outdated MAVLink library version at the transponder side. Now all messages are successful decoded including the system message.
    - sim vehicle simulator is too slow to test properly. If multiple MAVLink messages are sent at the same time, some are skipped. Perhaps this is due to the 20 Hz update rate. See previous point, there seem to be issues with MAVLink parsing at the transponder. As such, some MAVLink packets are not recognized.

Timeline

  • get this code reviewed and included into the master branch. Can you @magicrub @hendjoshsr71 let me know the next steps?
  • add support for the Auth messages, Support for MessagePack messages is not planned as current message set already cover full functionality.
  • add additional open drone ID messages like ACK and Command message. These are missing for a full implementation. Discuss this first with open drone ID project. @friissoren @gabrielcox before implementation. (First this initial code needs to be included in the main branch.)
  • NEW: update the information at https://mavlink.io/en/services/opendroneid.html once above is completed.

@hendjoshsr71
Copy link
Member

hendjoshsr71 commented Jul 1, 2022

Rebased this on master to have the proper mavlink submodule commit.

I also removed the merge commits as we keep a linear commit history as we rebase PRs on top of master.
https://ardupilot.org/dev/docs/git-rebase.html

I think we will move all the processing input/output of messages from the GCS library into the OpenDroneID library.
This will mean we wont need so many set & get methods. Just the ones that are "important" enough for that to access say serial numbers and such.

The reason I think this will be better is because
a.) likely less code
b.) likely less flash space used (we are limited to 2MB and are very protective of space) and given that nearly every UAS will need this library we shouldn't make it bigger than needed

Sorry, I should have warned you that is where I was thinking about going with this..... just too busy to get it done in the initial branch.

However, before you make changes, lets get this passing autotests and see what the size cost really is.

@hendjoshsr71
Copy link
Member

hendjoshsr71 commented Jul 1, 2022

Fixed some of the autotest errors and whitespace changes
Fixed the commits so that they are by library and squashed them down.

https://ardupilot.org/dev/docs/submitting-patches-back-to-master.html

Hopefully, test_size completes now. And then we can consider getting this smaller.

Copy link
Contributor

@magicrub magicrub left a comment

Choose a reason for hiding this comment

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

I'm not done reviewing this, but some cleanups that are needed are:

  • timers be in _ms
  • one-line accessors can just go into the header.
  • You have lots of bounds checking on the sets, which is nice. Please use our in-house functions to turn your dozen lines into 1 line. If they're actually 1 line, move it to the header. See other libraries as examples.
  • Wee need a special spot in memory to store the strings into non-volatile memory. That's something we can do in a follow-up PR, and likely by a maintainer since it's touchy playing in those parts of the code
  • Change all you lat/lng to int32_t and use the built-in Location class.
  • when fiddling with strings use strncmpy() instead of memcpy().

libraries/AP_OpenDroneID/AP_OpenDroneID.h Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/GCS_MAVLink/GCS_Common.cpp Outdated Show resolved Hide resolved
@Hwurzburg
Copy link
Collaborator

@BluemarkInnovations I would be happy to test fly in US when the time comes and help in creating a wiki page for OpenDroneID compatible devices

@BluemarkInnovations
Copy link
Contributor Author

@BluemarkInnovations I would be happy to test fly in US when the time comes and help in creating a wiki page for OpenDroneID compatible devices
Yes for sure, thanks for the offer. For sure, I would be interested to get some feedback on the transponder and potential things to improve. BTW OpenDrone ID also has it's own page for transmitter devices: https://github.com/opendroneid/receiver-android/blob/master/transmitter-devices.md

@BluemarkInnovations
Copy link
Contributor Author

In general, I made a new revision of the code based on the feedback I received. It is much cleaner and less lines of code. Due to my limited git knowledge, I messed up with the MAVLink module and as a result I can't compile it anymore. I don't know how to solve or revert to a state that ArduPilot can be compiled again. I have asked @hendjoshsr71 to get this resolved. Once that is fixed I can do a final test with the MAVLink transponder.

Copy link
Member

@hendjoshsr71 hendjoshsr71 left a comment

Choose a reason for hiding this comment

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

I did most of these changes already except the send_location() const

I didn't really review a lot as I ran out of time for the evening.

The send_location() needs some work from me to pull in the correct info. and get it to be a const function. All sets should be external to it and done in the update function (ideally).

Eventually, most of the sets/gets will likely be removed since everything is only being accessed by the OpenDroneID library alone.

libraries/GCS_MAVLink/GCS_Common.cpp Outdated Show resolved Hide resolved
libraries/GCS_MAVLink/GCS_Common.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.h Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.h Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.h Outdated Show resolved Hide resolved
Copy link

@friissoren friissoren left a comment

Choose a reason for hiding this comment

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

It is really great to see the integration of Open Drone ID into Ardupilot. This is something I have been waiting for, for a very long time but didn't have the skill nor resources to do myself. I very much appreciate your effort here.

I added some comments. I think there are a few places that probably needs a bit of refinement but please take a look.

* (and a DroneBeacon MAVLink transponder connected to ttyUSB1)
*
* The Remote ID implementation expects a transponder that caches the received MAVLink messages from ArduPilot
* and transmits them at the required intervals. So static messages are only send once to the transponder.

Choose a reason for hiding this comment

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

The last paragraph doesn't seem to fit line 157 - 159?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Agreed, in the initial revision it was sent once. Based on feedback from Tom, it has changed to every 10 seconds in revision 1. This solution is better as a transponder may reboot or loose temporarily power. So I forgot to update the description. At this moment I won't update any code until Josh has finished reviewing the code.

libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.h Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.h Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
}

void set_operator_id_type(MAV_ODID_OPERATOR_ID_TYPE type) {
//for now _operator_id_type can only be MAV_ODID_OPERATOR_ID_TYPE_CAA

Choose a reason for hiding this comment

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

Alignment.

libraries/AP_OpenDroneID/AP_OpenDroneID.h Outdated Show resolved Hide resolved
@hendjoshsr71
Copy link
Member

hendjoshsr71 commented Jul 20, 2022

Still need lots of work on send_location .. But it is much closer to having correct inputs coming into it.

Added a basic functions for an arming check that can't be overriden.
GPS functions for WGS84 altitude and to collect the GPS time accuracy (only for ublox at the moment. That needs fixing.)

Still need to fix the update() to get the takeoff location and store it

@hendjoshsr71 hendjoshsr71 marked this pull request as draft July 28, 2022 07:49
Copy link
Member

@hendjoshsr71 hendjoshsr71 left a comment

Choose a reason for hiding this comment

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

I've marked this as a draft since it is really a working draft right. With many implementation details to be completed still.

Anyone interested feel free to comment or add pieces.

libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.h Outdated Show resolved Hide resolved
libraries/AP_GPS/AP_GPS.h Outdated Show resolved Hide resolved
@BluemarkInnovations
Copy link
Contributor Author

It is okay for me to mark it as draft, but I prefer to have a first basic, minimum, implementation in ArduPilot, which can be improved over time. Today I checked the current PR version; it (still) works with my hardware.

So the things missing in this PR are settings in the ground station (GCS) implemented where a user can set the Serial ID, Operator ID, Self ID and some other settings.like UAV type. And/or store these vars as strings non-volatile memory.

On my end I aim to get 2nd generation hardware available in September. And there is the MAVLink PR for additional functionality. So, my only concern is that while on my end, I will make progress both on MAVLink messages and hardware, the draft status could cause support for Remote ID to be pending for some time.

@magicrub
Copy link
Contributor

This is failing a lot of the CI tests because of the PreArm test you've added:
AP: PreArm: OpenDroneID: UA_TYPE Must Not Be NONE
So, either disable this by default (for now and/or this PR) or some other scheme that if the hardware is not present, and not expected to be present, then the prearm check passes.

@friissoren
Copy link

@hendjoshsr71: I saw you have initiated a membership of the Ardupilot maintainers to the ASTM organization. Once you have access, apart from the remote ID standard, also pick up a copy of the recently published Means of Compliance document, which has some additional requirements needed to be fully compliant with the FAA rule.

libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Show resolved Hide resolved
send_basic_id_message();
break;
case NEXT_MSG_SYSTEM:
send_system_message();

Choose a reason for hiding this comment

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

You now have the system message grouped under the static data. If the GCS is of a type that supports dynamic updates of the operator location (this is mandatory for integrated drone ID implementations in the US and EU), the operator location will need to be updated once per second in the US or every three seconds for EU . I.e. it is no longer static data.

Copy link
Member

Choose a reason for hiding this comment

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

Looks like we pass by the requirement as the _mavlink_dynamic_period_ms / 4 with this number of messages will get us 1 second? Though how closely we meet that requirement would need to be determined.

And it will be fragile if we add additional messages here.

libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Outdated Show resolved Hide resolved
}
break;
}
// accept other messages from the GCS

Choose a reason for hiding this comment

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

In theory, a drone ID transmitter can also be a receiver.

I agree that most systems probably will not be doing that but should it already now be taken into account? I guess the current code approach would confuse the messages from the receiver with the messages from the GCS.

This could also be handled in later PRs.

Copy link
Member

Choose a reason for hiding this comment

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

Will be later PRs.

libraries/AP_OpenDroneID/AP_OpenDroneID.h Show resolved Hide resolved
ODID_COPY(category_eu);
ODID_COPY(class_eu);
ODID_COPY(operator_altitude_geo);
ODID_COPY(timestamp);

Choose a reason for hiding this comment

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

I think you now assume that the system message come from the GCS. That is fine. The below is mainly FYI.

The GCS needs to fill this timestamp field and the time needs to be valid, since it is used by receivers to validate also the timing of the location data.
The FAA did not approve that the shortened timestamp field in the Location message is enough to meet their rule requirement. This full 32-bit timestamp field was therefore added to the System message and the Means of Compliance document updated to mandate that the System message is mandatory, must be sent once per second and this timestamp field must be filled.
In praxis, this means the GCS needs to send the System MAVLink message to the flight controller once per second.

Copy link
Contributor

Choose a reason for hiding this comment

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

the transmitter module can correct the timestamp based on the last msg from the flight controller plus its own internal clock. That should be ok I think?

Choose a reason for hiding this comment

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

the transmitter module can correct the timestamp based on the last msg from the flight controller plus its own internal clock. That should be ok I think?

In theory possible, but then you pose a requirement on the transmitter implementation. Where should this be documented and how to ensure that all transmitter implementations will do this, since it is more like an exception that the transmitter suddenly needs to start modifying the data that is being transmitted.

So far, the assumption has been that the GCS+flight controller generate all the valid message data and the transmitter is just a "dumb" device that blurbs that out into the aether (?).

Probably you are in a better situation to decide what would make sense from a system architecture/eco-system perspective:

  1. The GCS updates the System timestamp regularly and publishes new MAVLink messages regularly (for the dynamic Operator Location case, it would anyway need to do this)
  2. The flight controller increases the frequency of the System messages that it publishes and ensures the timestamp is up-to-date
  3. The transmitter overwrites the System timestamp field to make sure it is up-to-date before transmitting it on the air

@tridge tridge force-pushed the wip/opendroneid branch 2 times, most recently from 0891edb to dcaaa4f Compare August 8, 2022 11:33
Copy link
Member

@hendjoshsr71 hendjoshsr71 left a comment

Choose a reason for hiding this comment

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

We should fix the time_accuracy bit I marked.

I will approve after that fix.

I do still disagree with get_undulation method as evidenced by the gps changes. All but three (of all our GPS drivers) would then need to do WGS84_Ellipsoid - AMSL_EGR99 and then reverse that change for use.

It would be more natural to store and use WGS84. It will be hard to tell which altitude frames are available and where the undulation is referenced between. (Which geoid and ellipsoid)

We can fly with just WGS84 (as do now for many drivers.) But cannot fly alone with AMSL.

There will need to be arming check in terrain that doesn't allow arming if you are actually flying with respect to WGS84.

libraries/AP_OpenDroneID/AP_OpenDroneID.cpp Show resolved Hide resolved
Copy link
Contributor

@WickedShell WickedShell left a comment

Choose a reason for hiding this comment

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

Not a full review at this stage, just some initial comments.

I'm with @hendjoshsr71 that I would rather not have users directly manipulating undulation here as it's rapidly a tricky concept and easy to screw up. I'd rather just store the both altitudes directly, or provide a mapping function that maps an altitude between frames with a very clear name. (Maybe even like the Location altitude frames even though we'd only support 2 at the moment).

@@ -1855,6 +1865,16 @@ void AP_GPS::calc_blended_state(void)
timing[GPS_BLENDED_INSTANCE].last_fix_time_ms = 0;
timing[GPS_BLENDED_INSTANCE].last_message_time_ms = 0;

if (state[0].have_undulation) {
state[GPS_BLENDED_INSTANCE].have_undulation = true;
state[GPS_BLENDED_INSTANCE].undulation = state[0].undulation;
Copy link
Contributor

Choose a reason for hiding this comment

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

The vertical position is possibly blended here, but the undulation isn't? Given the differences in stored table accuracies that will result in random step changes.

Copy link
Contributor

Choose a reason for hiding this comment

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

only used in one plane, in AP_OpenDroneID and both receivers should be giving the same undulation. It is a very slowly changing number with distance. We really only support blending between two receivers of the same type due to the way we use the accuracy numbers


// we need to notify user if we lost the transmitter
if (now_ms - last_arm_status_ms > 5000) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ODID: lost transmitter");
Copy link
Contributor

Choose a reason for hiding this comment

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

Once you've lost link doesn't this result in flooding the links with a status text?

Copy link
Contributor

Choose a reason for hiding this comment

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

once every 5s only, and apparently required by the FAA to notify users

Copy link
Contributor

Choose a reason for hiding this comment

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

Where's the rate limiting come from though? I only see 2 places that set it, once over CAN, and once over MAVLink. In both cases the last_arm_status_ms is only updated if a specific message is received, but the send text here is in an always called path from update(), so why wouldn't it flood the link after 5 seconds?

MAV_ODID_HOR_ACC AP_OpenDroneID::create_enum_horizontal_accuracy(float accuracy) const
{
// Out of bounds return UKNOWN flag
if (accuracy < 0.0 || accuracy >= 18520.0) {
Copy link
Contributor

Choose a reason for hiding this comment

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

Why bother checking the maximum here? It just means we have to keep that updated with table. We need to sanity check the low side obviously, but the final return statement will cover the high side for us nicely.

// make sure value is within limits of remote ID standard
uint16_t AP_OpenDroneID::create_speed_horizontal(uint16_t speed) const
{
if (speed > ODID_MAX_SPEED_H) { // constraint function can't be used, because out of range value is invalid
Copy link
Contributor

Choose a reason for hiding this comment

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

This seems like a very odd construction, ODID_MAX_SPEED_H is a float, that we compare against a uint16_t argument that is truncating our floating point representation. I suspect that the speed argument is supposed to be a float, and the return also is based on the defines, and the fact that anything else truncates to meter resolution.

Why not scale in here and have this just return the correctly output scalled cm/s uint16_t?

This looks like a common problem on these helpers.

@tridge
Copy link
Contributor

tridge commented Aug 9, 2022

@WickedShell doing separate accessors for the two heights gets out of hand quickly as we use Location struct, which ties in with AP_Mission and a thousand other places.
Only one piece of code needs to know the difference. Using get_undulation() gives us a narrow change that works for that one case.
It also makes no sense at all when using altitude from AHRS or EKF. Say you need an AHRS altitude (which is what we fly on) but need it relative to WGS84. If we do it as a "get wgs84 alt" from GPS then we'd need to go ask the GPS (which GPS???) what the WGS84 alt is, then ask it what the AMSL alt is, then subtract, then add to AHRS alt. A great mess with races galore.
Having get_undulation gives us the difference between the two types of heights, without spreading the mess across the whole code base
Feel free to rework this some other way in future but I don't want to hold up getting opendroneid support for this


alloc_failed:
dronecan_init_failed |= driver_mask;
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "OpenDroneID DroneCAN alloc failed");
Copy link
Contributor

Choose a reason for hiding this comment

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

We should probably call alloc_error here.This message could easily be lost in a rush of startup messages otherwise.

Copy link
Member

@hendjoshsr71 hendjoshsr71 left a comment

Choose a reason for hiding this comment

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

Fine as is and fix ups for the other issues found (not yet resolved) can be done as cleanups.

@tridge tridge dismissed WickedShell’s stale review August 9, 2022 04:37

happy to do followup PRs, but for now we need to get base support in

@tridge tridge merged commit a34ff49 into ArduPilot:master Aug 9, 2022
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

10 participants