Code Monkey home page Code Monkey logo

arduremoteid's Introduction

ArduPilot RemoteID Transmitter

This is an implementation of a MAVLink and DroneCAN OpenDroneID transmitter. It aims to provide a transmitter solution for the FAA standard RemoteID requrement, meeting the transmitter component of the ASTM F3586-22 Means of Compliance. It also aims to be compliant with the RemoteID regulation in the EU.

It is the responsibility of the user/manufacturer to configure the ArduRemoteID firmware in a way that it is compliant with the local RemoteID regulation. For instance, in the USA it is mandatory that UAV manufacturers submit a DoC (Declaration of Conformance) to the FAA where they state that their product is compliant with the RemoteID regulation.

Hardware Supported

The firmware currently supports the ESP32-S3 and ESP32-C3 chips. There are 7 boards supported so far with more to come:

Hardware from https://wurzbachelectronics.com/ is expected to be added soon.

For the ESP32-S3 dev board the pins assumed in this firmware are:

  • UART TX on pin 18
  • UART RX on pin 17
  • CAN TX on pin 47
  • CAN RX on pin 38

For the ESP32-C3 dev board the pins assumed in this firmware are:

  • UART TX on pin 3
  • UART RX on pin 2
  • CAN TX on pin 5
  • CAN RX on pin 4

For CAN a suitable 1MBit bxCAN transceiver needs to be connected to the CAN TX/RX pins.

You can also do MAVLink on the USB UART port (the one marked "UART" on the silkscreen). That allows for easy simulation testing by plugging in a micro USB cable.

See board_config.h and Makefile for information on porting to new boards.

Transmission Modes

This firmware supports the following transmission modes:

  • WiFi Broadcast
  • WiFi NAN (Neighbour Awareness Networking)
  • Bluetooth 4 Legacy Advertising
  • Bluetooth 5 Long Range + Extended Advertising

Protocols

This firmware supports communication with an ArduPilot flight controller either using MAVLink or DroneCAN.

For MAVLink the following service is used: https://mavlink.io/en/services/opendroneid.html

For DroneCAN the following messages are used: https://github.com/dronecan/DSDL/tree/master/dronecan/remoteid

The DroneCAN messages are an exact mirror of the MAVLink messages to make a dual-transport implementation easy.

Releases

Pre-built releases are in the releases list folder on github.

https://github.com/ArduPilot/ArduRemoteID/releases

Flashing

For initial firmload load, to flash to an ESP32-S3 board use the espressif FlashTool from

https://www.espressif.com/en/support/download/other-tools

If this is the first time flashing the board, you may need to hold the "boot" button down while attaching the USB cable to the USB connector marked "USB"

and then use the pre-built binary in the releases folder to flash using the following options, after selecting the COMM port that the board is attached:

Board setup dialog

Flashing with FlashTool

subsequent re-flashing of newer releases should not require holding the "boot" button during power-up of the board as the USB cable is attached.

If the board already runs ArduRemoteID, the preferred firmware upgrade method is to upload a new firmware file via the webinterface.

Parameters

The firmware comes with a set of parameters which are accessible from DroneCAN or MAVLink. The parameters allow for a lot of flexibility in controlling the behaviour of the board.

DroneCAN allows control of any parameter. Using MAVLink only non-string parameters are accessible.

DroneCan Parameters

Key parameters are:

  • LOCK_LEVEL: this controls the lockdown of the board. If this is set to a non-zero value then all parameters updates via DroneCAN will be prevented. To change parameters (including the LOCK_LEVEL) once this is set you need to use a DroneCAN SecureCommand. There is an example script in scripts/secure_command.py which can change any parameter if you know a private key corresponding to one of the public keys.

  • UAS_TYPE, UAS_ID_TYPE and UAS_ID: these override the IDs in the RemoteID BasicID packet when they have all been set. These should be set by the vendor before shipping the vehicle.

  • WEBSERVER_ENABLE: this enables the building WiFi access point and webserver for status monitoring and secure firmware update.

  • PUBLIC_KEY1 to PUBLIC_KEY5: these are the public keys that will be used to verify firmware updates and secure update of parameters

Web Server

The firmware comes with a builtin web server if the parameters WEBSERVER_ENABLE is set. The WiFi access point will use a SSID from WIFI_SSID and password from WIFI_PASSWORD which you can set with DroneCAN parameter tools such as the DroneCAN GUI tool or MissionPlanner CAN tool.

The default SSID is RID_xxxxxxxx where xxxxxxxx is the factory WiFi MAC address of the board. The default password is ArduRemoteID.

The web server has a secure firmware update mechanism which will only allow a properly signed firmware with a signature corresponding to one of the 5 public keys in the parameters. If no public keys are set then any firmware can be loaded.

The web server defaults to URL http://192.168.4.1 once you connect to the WiFi access point.

Firmware Signing

To generate public/private key pairs please use:

  scripts/generate_keys.py

the keys are compatible with the ArduPilot secure boot system. By default the 3 ArduPilot release public keys are included.

Once you have generated a public key you can add it to the RemoteID node using a DroneCAN parameter editor. Make sure you keep the private key in a secure location.

To upload a firmware via the web server you need to use an "OTA" (Over The Air) firmware, which is generated as OTA files in the build. You then need to sign it with a private key corresponding to one of the public keys on the RemoteID node.

To sign an OTA firmware you should use a command such as this one:

 scripts/sign_fw.py ArduRemoteID_ESP32S3_DEV_OTA.bin MyName_private_key.dat 1

The '1' on the end is the BOARD_ID. See board_config.h for the board IDs for your board.

Once signed you can upload the firmware via the web server.

Set LOCK_LEVEL to -1 to skip any checks for the OTA upgrade like board ID check, signed firmware with a valid key. For LOCK_LEVEL 0 or higher, only firmware files are accepted that match the board ID and are signed with a valid key. (OTA firmware files in the ArduRemoteID github page are always signed with a valid key.)

LOCK_LEVEL Parameter

The LOCK_LEVEL parameter is the way a vendor can lock down the RemoteID board so that it is tamper resistant. if any valid public keys have been set then setting LOCK_LEVEL=1 will prevent any parameter changes using the DroneCAN or MAVLink interfaces. All parameter changes will need to be made via the SecureCommand signed interface.

Setting LOCK_LEVEL=2 will also cause the ESP32 eFuses to be set to prevent firmware updates except via the signed web interface. This is a permanent change and cannot be undone even if the LOCK_LEVEL is changed back to 0 or 1 via SecureCommand.

Setting LOCK_LEVEL=-1 will skip any checks for upgrading the firmware via the web server like board ID check, signed firmware with a valid key.

The default LOCK_LEVEL=0 allows to change parameters and only allows firmware upgrades via the web server that have been signed with a valid key. Also the board ID of the firmware file needs to match the board ID of the device.

Secure Parameter Update

Once LOCK_LEVEL is 1 or 2 you cannot use normal parameter commands to set parameters. Instead you need to use the DroneCAN SecureCommand interface or the MAVLink SECURE_COMMAND interface.

For DroneCAN see the script in scripts/secure_command.py, for example this command would change the UAS_TYPE to 3:

scripts/secure_command.py mavcan::14550 --private-key my_private_key.dat --target-node=125 UAS_TYPE=3

For MAVLink you can use the SecureCommand module in MAVProxy. For example:

module load SecureCommand
securecommand set private_keyfile my_private_key.dat
securecommand getsessionkey
securecommand setconfig UAS_TYPE=3

You can also use secure commands to set LOCK_LEVEL back to zero, but note that if you have set LOCK_LEVEL=2 then the setting of the eFuse bits is not undone. You will be able to change parameters but you will not be able to flash firmware via the USB port. You can still flash a signed firmware using the web interface.

Secure Command over support.ardupilot.org

If using secure_command.py remotely via a link forwarded over support.ardupilot.org then you would run the following:

scripts/secure_command.py mavcan:udpout:support.ardupilot.org:AAAAA --signing-passphrase=XXXXXXX --target-node=NNN --private-key=my_private_key.dat UAS_TYPE=3

where

  • AAAAA is your support.ardupilot.org remote support ID (the support engineer ID, not the customers ID)
  • NNN is the target CAN node ID on the remote flight controller
  • add --bus-num=2 if the node is on the 2nd CAN bus

As the link may be slow you may also need a higher value for the --timeout option.

Secure Command using DroneCAN GUI Tool

For a CAN attached ArduRemoteID module you can use DroneCAN GUI tool to update parameters securely.

Get the latest DroneCAN GUI tool here:

https://firmware.ardupilot.org/Tools/CAN_GUI/

You will need version 1.2.23 or later.

After connecting, select the RemoteID panel:

RemoteID Panel1

then use like this:

RemoteID Panel2

The command is of the form "PARAMETERNAME=VALUE".

When you are using DroneCAN GUI tool over a support.ardupilot.org signed link you will need to enter the URI like this:

GUI Signed

where 999999 is replaced with your support engineer ID.

ArduPilot Support

Support for OpenDroneID is in ArduPilot master and is also in the 4.2.3 stable releases and 4.3.x releases. You need to enable it on a board by setting "define AP_OPENDRONEID_ENABLED 1" in the hwdef.dat for your board or by using --enable-opendroneid when doing waf configure.

Credit

Many thanks to the great work by:

This firmware builds on their work.

License

This firmware is licensed under the GNU GPLv2 or later

arduremoteid's People

Contributors

bluemarkinnovations avatar bradh avatar davidbuzz avatar dcl-beep avatar dusan19 avatar friissoren avatar hwurzburg avatar lgarciaos avatar muramura avatar sborenstein-ift avatar tridge avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

arduremoteid's Issues

ArduRemoteID Module - UA Serial Number, Serial Number Type and Vehicle Type Burn In

In order to comply with MOC 7.5.2, the serial number needs to be baked into the module. It is recommended that this be done for all three fields required for BASIC_ID. This includes:

  • UAS ID: 20 characters
  • UA Type: MAV_ODID_UA_TYPE (byte)
  • ID Type: MAV_ODID_TYPE

One recommendation is to burn this in on the mfg floor at firmware burn-in time. Other options include a one-time write capability after firmware is loaded. Other options may exist, however there seems to be general agreement that:

  1. This information should be baked into the module, not the autopilot
  2. The contents of the 20 character ID number should start with the 4 character ICAO requirement, but otherwise be vendor specific.

Operator Location doesn't fail on CAN

This may be a bug on the ArduPilot OpenDroneID library. When the operator location feed is turned off, the RID module does not detect this. Likely due to the AP module not failing and continuing to send stale data.

Operation Description / Emergency Status variation

On Android and the OpenDroneID app I can see the Emergency Status text and type correctly but on iOS and DroneScanner I get a series of numbers in Operation Description. Doesn't look like Hex but certainly something converted.

Is this a program side issue (seems like it) and has anyone else seen this?

Missing default private key

I changed the lock_level from 0 to 1 to test it but now I can't changed it back because I'm missing the default private keys. I changed it without changing the default public keys. They should be in the github repository or am I missing something because I can't find them.
Thanks

Cannot view parameters

Problem description:
I am not able to change the parameters as they are not displayed.
I have tried to do this in Mission Planner and although I can see the CAN node, the parameters are not displayed.
I have found that this problem comes from commit DroneCAN: use TWAI acceptance filters
It seems like the acceptance mask and code implemented are somewhat discriminating RID CAN messages.

Expected behavior:
When click on RID Module CAN parameters button in MissionPlanner, the parameters are displayed.

Current behavior
When click on RID Module CAN parameters button in MissionPlanner, only an empty window is displayed.

RID Module:
Custom module ESP32-C3-MINI-1U based

Flight Controller:
CubeOrange

Steps to reproduce:

  1. Build (for a ESP32-C3 device) and upload the ArduRemoteID firmware v1.14
  2. Connect the RID module to a CubeOrange (loaded with ardupilot ODID firmware, above v4.5.0) via CAN
  3. Enable CAN interface on CubeOrange as suggested
  4. Reboot flight controller and connect to mission planner
  5. Display CAN parameters on Setup->Optional Hardware->DroneCan/UAVCAN

Workaround:
In file "RemoteIDModule/CANDriver.cpp" comment out the following lines inside init function:
f_config.acceptance_code = acceptance_code;
f_config.acceptance_mask = acceptance_mask;
f_config.single_filter = true;

Some questions about ArduRemoteID on FMUV3

According to the tutorial on youtube, I tried to compile and burn the firmware with ODID support on FMUV3.
My device is FMUV3, ardupilot version is 4.3.1, MP version is 1.3.80.
But after entering 'flashbootloader' using MAVProxy terminal, the device became bricked. After unbricking, I recompiled and burned again, this time I skipped the 'flashbootloader' step. But in the UAVCAN interface on MP, I didn't get the same result as on the video, see
image
Also, the MP didn't find ODID_TXRX device and the messages column shows as
image

Do I need to use a newer device? Like the pixhawk6c?

releases folder should contain binaries for all boards

The folder releases should contain the binaries for all available boards. Now only a generic binary is available. (It is unclear for which platform it is intended.)

This means that all users have to build the code in order to flash their own board. Or they need to go the Action menu and download the binary for a particular build. Both are a bit unconvenient.

ID error when not set to params

In uint8_t Transport::arm_status_check():

if (!g.have_basic_id_info()) { // if there is no basic ID data stored in the parameters give warning. If basic ID data are streamed to RID device, // it will store them in the parameters ret += "ID "; }

but what if options param is set such that OPTIONS_DONT_SAVE_BASIC_ID_TO_PARAMETERS is enabled? Then basic ID would not be stored and there will always be an arm status check error.

Providing UA ID, type etc. from broadcast module to GCS

I understood general open architectural issues should be logged as issues in this project so I will add this one here.

If the UA ID/serial number, UA ID Type and UA Type are stored permanently in the broadcast module, there needs to be a way to get that information from the broadcast module to the GCS, so it can be shown to the operator on a UI of some kind.

I know the below is a purely theoretical discussion until someone includes a RID transmitter component to the UAS that is also capable of receiving BT/Wi-Fi RID messages, but I would rather think through this now, than have this causing problems later on.

RID receiver components should follow the instructions here: https://mavlink.io/en/services/opendroneid.html#other_ua
I.e. when publishing the received drone ID data as internal MAVLink messages, they must set the compid field to their own MAV_COMP_ID_ODID_TXRX_n ID, to make it possible to distinguish this data from the drone ID data of the UA itself.
But how do we then distinguish between a Basic ID message with compid = MAV_COMP_ID_ODID_TXRX_n that carries data from the transmitter module (i.e. for the UAS itself) and one that carries data from an entirely different UAS flying nearby?

PS: Having the UA type (quad-rotor, VTOL, blimp etc.) stored in the broadcast module doesn't sound quite reasonable? Maybe that should belong somewhere else? Should it be possible for the operator to input this via a UI on the GCS? A separate topic though.

WSL2 Support for flashing ESP32-S3

For those working on Windows using WSL 2:
In order to connect a USB device to WSL, follow the instructions from Microsoft. For me, the ESP32 shows up at /dev/ttyACM0 . You can find the location of your device by checking /dev/tty* or with lsusb . Instead of running make upload inside of the RemoteIDModule dir, you can construct your own command to flash the ESP32

~/.arduino15/packages/esp32/hardware/esp32/2.0.3/tools/esptool.py --port /dev/ttyACM0 write_flash 0x0 ArduRemoteID-ESP32S3_DEV.bin

Be sure to change the command to match the settings on your system.

Transmitter health flag for FAA MOC

Document F3586-22 (attached) requires checking if Transmitter radio hardware and software are functioning properly.
That's in chapters: 7.2.3.2 and 7.3.2.2 that are further referenced in tests in chapter 8 (8.8.2 and 8.9.6).

I see in the code that there are no checks that transmitter is working properly.
There is a flag pfst_check_ok but it doesnt have any effect as its just set to true.
The radio has to be tested pre flight, but also in flight, as the mentioned chapters of F3586-22 require.

Is there a way of checking whether the transmitter is working properly? Is there a plan of implementing this feature?

F3586-22 Standard Practice for Remote ID Means of Compliance (1).pdf

todo - Document how to build and test this, how to configure it, how to wire it to an autopilot, and

Right now, it builds with "Arduino", and needs very recent 'esp32' board-manager added in eg:

Arduino IDE -> File Menu -> Preferences -> "Additional Board Manager URLs:" https://github.com/espressif/arduino-esp32/releases/download/2.0.3-RC1/package_esp32_dev_index.json
Arduino IDE -> Tools Menu -> Board -> Boards Manager -> [search for 'esp32'] ->Select Version [drop-down]-> 2.0.3-RC1 -> Install
Arduino IDE -> Tools Menu -> Board -> "ESP32 Arduino" ->"ESP32S3 Dev Module" [choose it]
In your file manager navigate to ~/Arduino/libraries/ folder
In this folder you need symlinks to a few folders... one called 'id_open' and a folder called 'utm' that come from https://github.com/sxjack/uav_electronic_ids. as well as some others - there's a shell script to make these symlinks into ~/Arduino/libraries, but how they get here doesn't matter too much.

You can then open one of the minimal 'remote-id' example/s from id_open eg:
Arduino IDE -> File Menu -> Examples ->[scroll] Examples from Custom Libraries -> id_open -> random_flight
OR
You can then open the 'RemoteIDModule.ino 'from this repo:
Arduino IDE -> File Menu -> Open ... [navigate to it and open it ...

how to connect?
Plugin your ep32-s3 with usb cable using the port labeled "USB" on the pcb - this is for FLASHING/debug/console/etc
Optional:
Plugin your ep32-s3 with ANOTHER usb cable using the port labeled "UART" on the pcb - this is where mavlink is coming/going, and you can connect to this with mavproxy, etc.
Optional:
Plugin your ep32-s3 into a flight-controller UART using RX/TX/GND on pins 17,18,GND on the pcb - this listens for mavlink from an autopilot, and expects to find REMOTE_ID* packets in the mavlink stream, and it broadcast/s this information from the drone as bluetooth/wifi on 2.4ghz in a manner that can be received by Android mobile phone App [https://play.google.com/store/apps/details?id=org.opendroneid.android_osm] and hopefully other open-drone-id compliant receivers.

Arduino IDE -> Tools Menu -> Port:... -> /dev/ttyACM0
Press 'Upload' '"arrow" in IDE green bar.
If board does not flash, hold-down BOOT pushbutton on pcb while pressing RESET pushbutton briefly [to force it into bootloader mode] and retry.
done, ESP32-S3 is now running and emitting test/demo remote-id bluetooth messages.

TJA1050

Hi,

When I try to use dronecan, with TJA1050 converter Im unable to load parameters. DronId is showing on list of CAN nodes.

What can be the issue.

THX Peter

Planned Authentication support?

Is there any plans to support the transmission of Authentication messages with data coming from either Mavlink or DroneCAN?

Troubleshooting Guidance

I am attempting to get this working on an ESP32-C3 dev board and I am running into a dead end. I could use some troubleshooting advice.

I believe I have successfully flashed the ESP32-C3 board, but I can't see any indication that it is working. I have a constant red LED indicating power as the only sign of life. No wifi networks visible on my phone, no bluetooth devices visible on my phone, no indication that mavlink is being sent from my flight controller, and my drone scanner apps can't see anything.

What tests can I run to verify my ESP32-C3 ArduRemoteID flash was successful?

Ideas for what might be wrong:

  1. I missed some part of the setup procedure in Mission Planner (I am very new to DIY drones and Mission Planner)
  2. Insufficient power from my USB port to power all devices
  3. Using wrong pins on the ESP32-C3 for TX/RX . The readme has pin 2 as RX and pin 3 as TX which is backwards from the board labels. I tried both just in case.
  4. Bad flash. I tried two different flashing utilities, neither of which worked. I finally got it to flash using esptool.py from Windows Command Line.
  5. Bad wiring between the flight controller and the ESP32-C3. I am new to soldering.

Update 1 -

  • I attempted to rule out a bad flash by using the esptool's verify_flash command. The check passed.
  • I attempted to rule out insufficient power by supplying a dedicated USB power feed direction to the ESP32-C3 board.

Update 2 -

  • I tried a different binary (non-OTA) and suddenly progress. The RGB LED lit up red and my scanner app can now see the drone. Awesome! Not sure what was wrong with the other binary.

Update 3 -

  • I have Mavlink working, but I'm constantly getting an error message "location message missing". The operator location and aircraft info are all there, but the location information is not. I have a GPS fix and Mission Planner has no problem plotting the position. Not sure why location for the aircraft isn't getting through.

My Setup

Breadboard:

  • F405-WMN:
    • ArduPlane V4.3.1
    • Powered via USB to Flight Controller (No Battery)
    • Active Mavlink Connection to Mission Planner via USB
  • GPS/Compass (Calibrated and Working):
    • Power from Flight Controller 5v
  • ESP32-C3 Dev Kit:
    • Flashed ArduRemoteID release: v1.11, file: ArduRemoteID_ESP32C3_DEV_OTA.bin
    • Power from Flight Controller 5v
    • Connected to UART1 TX/RX on flight controller

Desktop PC (Windows 10):

  • Mission Planner v1.3.77.1 (build 1.3.8349.13456)
    • Telem1 set to use Mavlink2
    • GCS GPS from Android Phone via bluetooth (Connected and Working)
  • USB Bluetooth Dongle (to receive GPS from Android Phone)

Android Phone:

  • GPS2Bluetooth
  • Drone Scanner (Application to test the transponder)
  • OpenDroneID (Application to test the transponder)

Can't compile on Ubuntu 22.04

After following the instructions in BUILDING.md, I seethe following compilation error:

In file included from /media/shalomc/home/workspace/opensource/arduremoteid/RemoteIDModule/mavlink_msgs.h:18,
                 from /media/shalomc/home/workspace/opensource/arduremoteid/RemoteIDModule/transport.h:6,
                 from /media/shalomc/home/workspace/opensource/arduremoteid/RemoteIDModule/mavlink.h:5,
                 from /media/shalomc/home/workspace/opensource/arduremoteid/RemoteIDModule/RemoteIDModule.ino:15:
/media/shalomc/home/Arduino/libraries/mavlink2/mavlink2.h:1:10: fatal error: generated/all/version.h: No such file or directory
 #include "generated/all/version.h"
          ^~~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated.

Host: Ubuntu 22.04
Python: 3.10.6

Make output:


➜  RemoteIDModule git:(master) make setup 
Installing ESP32 support
../bin/arduino-cli core update-index --config-file arduino-cli.yaml
Downloading index: package_index.tar.bz2 downloaded                                                                                                   
Downloading index: package_esp32_index.json downloaded                                                                                                
../bin/arduino-cli core install esp32:[email protected]
Platform esp32:[email protected] already installed
../bin/arduino-cli lib install "Adafruit NeoPixel"
Already installed Adafruit [email protected]
➜  RemoteIDModule git:(master) make
Generating mavlink2 headers
Validating modules/mavlink/message_definitions/v1.0/all.xml
Parsing modules/mavlink/message_definitions/v1.0/all.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/ardupilotmega.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/ardupilotmega.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/ASLUAV.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/ASLUAV.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/common.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/common.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/development.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/development.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/icarous.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/icarous.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/minimal.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/minimal.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/python_array_test.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/python_array_test.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/standard.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/standard.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/test.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/test.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/ualberta.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/ualberta.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/uAvionix.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/uAvionix.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/loweheiser.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/loweheiser.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/storm32.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/storm32.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/AVSSUAS.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/AVSSUAS.xml
Validating /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/cubepilot.xml
Parsing /media/shalomc/home/workspace/opensource/arduremoteid/modules/mavlink/message_definitions/v1.0/cubepilot.xml
Merged enum MAV_CMD
Merged enum MAV_CMD
Merged enum MAV_CMD
Merged enum MAV_CMD
Merged enum MAV_CMD
Enum STORAGE_TYPE in STORAGE_INFORMATION.type does not exist
Generating DroneCAN headers for libcanard
expanding uavcan.Timestamp
expanding uavcan.CoarseOrientation
expanding uavcan.tunnel.Call
expanding uavcan.tunnel.Broadcast
expanding uavcan.tunnel.Protocol
expanding uavcan.equipment.range_sensor.Measurement
expanding uavcan.equipment.safety.ArmingStatus
expanding uavcan.equipment.hardpoint.Status
expanding uavcan.equipment.hardpoint.Command
expanding uavcan.equipment.gnss.Fix
expanding uavcan.equipment.gnss.Fix2
expanding uavcan.equipment.gnss.ECEFPositionVelocity
expanding uavcan.equipment.gnss.RTCMStream
expanding uavcan.equipment.gnss.Auxiliary
expanding uavcan.equipment.power.PrimaryPowerSupplyStatus
expanding uavcan.equipment.power.CircuitStatus
expanding uavcan.equipment.power.BatteryInfo
expanding uavcan.equipment.ahrs.MagneticFieldStrength
expanding uavcan.equipment.ahrs.RawIMU
expanding uavcan.equipment.ahrs.Solution
expanding uavcan.equipment.ahrs.MagneticFieldStrength2
expanding uavcan.equipment.actuator.ArrayCommand
expanding uavcan.equipment.actuator.Status
expanding uavcan.equipment.actuator.Command
expanding uavcan.equipment.air_data.AngleOfAttack
expanding uavcan.equipment.air_data.RawAirData
expanding uavcan.equipment.air_data.StaticPressure
expanding uavcan.equipment.air_data.Sideslip
expanding uavcan.equipment.air_data.StaticTemperature
expanding uavcan.equipment.air_data.IndicatedAirspeed
expanding uavcan.equipment.air_data.TrueAirspeed
expanding uavcan.equipment.device.Temperature
expanding uavcan.equipment.ice.FuelTankStatus
expanding uavcan.equipment.ice.reciprocating.Status
expanding uavcan.equipment.ice.reciprocating.CylinderStatus
expanding uavcan.equipment.indication.RGB565
expanding uavcan.equipment.indication.BeepCommand
expanding uavcan.equipment.indication.SingleLightCommand
expanding uavcan.equipment.indication.LightsCommand
expanding uavcan.equipment.esc.RPMCommand
expanding uavcan.equipment.esc.Status
expanding uavcan.equipment.camera_gimbal.GEOPOICommand
expanding uavcan.equipment.esc.RawCommand
expanding uavcan.equipment.camera_gimbal.Status
expanding uavcan.equipment.camera_gimbal.Mode
expanding uavcan.equipment.camera_gimbal.AngularCommand
expanding uavcan.navigation.GlobalNavigationSolution
expanding uavcan.protocol.DataTypeKind
expanding uavcan.protocol.HardwareVersion
expanding uavcan.protocol.CANIfaceStats
expanding uavcan.protocol.RestartNode
expanding uavcan.protocol.GetDataTypeInfo
expanding uavcan.protocol.AccessCommandShell
expanding uavcan.protocol.GlobalTimeSync
expanding uavcan.protocol.SoftwareVersion
expanding uavcan.protocol.GetNodeInfo
expanding uavcan.protocol.NodeStatus
expanding uavcan.protocol.GetTransportStats
expanding uavcan.protocol.Panic
expanding uavcan.protocol.enumeration.Indication
expanding uavcan.protocol.enumeration.Begin
expanding uavcan.protocol.param.Value
expanding uavcan.protocol.param.NumericValue
expanding uavcan.protocol.param.ExecuteOpcode
expanding uavcan.protocol.param.Empty
expanding uavcan.protocol.param.GetSet
expanding uavcan.protocol.dynamic_node_id.Allocation
expanding uavcan.protocol.dynamic_node_id.server.Entry
expanding uavcan.protocol.dynamic_node_id.server.RequestVote
expanding uavcan.protocol.dynamic_node_id.server.Discovery
expanding uavcan.protocol.dynamic_node_id.server.AppendEntries
expanding uavcan.protocol.file.Path
expanding uavcan.protocol.file.GetDirectoryEntryInfo
expanding uavcan.protocol.file.Error
expanding uavcan.protocol.file.Delete
expanding uavcan.protocol.file.EntryType
expanding uavcan.protocol.file.Read
expanding uavcan.protocol.file.BeginFirmwareUpdate
expanding uavcan.protocol.file.GetInfo
expanding uavcan.protocol.file.Write
expanding uavcan.protocol.debug.LogLevel
expanding uavcan.protocol.debug.LogMessage
expanding uavcan.protocol.debug.KeyValue
expanding dronecan.sensors.hygrometer.Hygrometer
expanding dronecan.remoteid.SecureCommand
expanding dronecan.remoteid.BasicID
expanding dronecan.remoteid.System
expanding dronecan.remoteid.OperatorID
expanding dronecan.remoteid.Location
expanding dronecan.remoteid.SelfID
expanding dronecan.remoteid.ArmStatus
expanding com.hex.equipment.flow.Measurement
Embedding file public_keys/ArduPilot_public_key1.dat:public_keys/ArduPilot_public_key1.dat
Embedding file public_keys/ArduPilot_public_key2.dat:public_keys/ArduPilot_public_key2.dat
Embedding file public_keys/ArduPilot_public_key3.dat:public_keys/ArduPilot_public_key3.dat
Embedding file public_keys/BlueMark_public_key1.dat:public_keys/BlueMark_public_key1.dat
Embedding file web/images/bg.jpg:web/images/bg.jpg
Embedding file web/images/bluemark.png:web/images/bluemark.png
Embedding file web/images/button.jpg:web/images/button.jpg
Embedding file web/images/logo.jpg:web/images/logo.jpg
Embedding file web/index.html:web/index.html
Embedding file web/js/jquery.min.js:web/js/jquery.min.js
Embedding file web/js/tools.js:web/js/tools.js
Embedding file web/styles/main.css:web/styles/main.css
Building ESP32S3_DEV on esp32s3
In file included from /media/shalomc/home/workspace/opensource/arduremoteid/RemoteIDModule/mavlink_msgs.h:18,
                 from /media/shalomc/home/workspace/opensource/arduremoteid/RemoteIDModule/transport.h:6,
                 from /media/shalomc/home/workspace/opensource/arduremoteid/RemoteIDModule/mavlink.h:5,
                 from /media/shalomc/home/workspace/opensource/arduremoteid/RemoteIDModule/RemoteIDModule.ino:15:
/media/shalomc/home/Arduino/libraries/mavlink2/mavlink2.h:1:10: fatal error: generated/all/version.h: No such file or directory
 #include "generated/all/version.h"
          ^~~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated.


Used library   Version Path                                                                                           
libopendroneid         /media/shalomc/home/workspace/opensource/arduremoteid/modules/opendroneid-core-c/libopendroneid
mavlink2       1.0     /media/shalomc/home/workspace/opensource/arduremoteid/libraries/mavlink2                       

Used platform Version Path                                                              
esp32:esp32   2.0.3   /media/shalomc/home/.arduino15/packages/esp32/hardware/esp32/2.0.3

Error during build: exit status 1
make: *** [Makefile:61: ArduRemoteID-ESP32S3_DEV.bin] Error 1

Session ID Support?

This is a question I ask after experimenting with this code and a particular behavior made me question how Session IDs would be supported with this firmware (without modifications with my current understanding).

The current code checks if their is Basic ID data persisted in the parameters and pulls from this to fill in the UAS data structure. This can be filled by hard-coding it at compile time or be filled in dynamically with the first Basic ID message obtained via DroneCAN or MAVLink (only when the parameter is empty to begin with). Note this dynamic fill only happens with Basic ID 1, not Basic ID 2 which seems to have its parameter settings only be hard-coded.

From F3586-22:

A unique Session ID (UTM Assigned universally unique identifier (UUID) or Specific Session ID) as described in Specification F3411, Table 1 and Subsection 5.4.5.6, which can be resolved to the corresponding serial number, with access limited to authorized parties only, through a system and process accepted by the FAA.

If a user is to use a Session ID then the Serial Number should, at least by my reading of this statement, never be broadcast as it is considered something that has "access limited to authorized parties only, through a system and process accepted by the FAA".

With the current code setup the first Session ID seen over external transport would be filled in permanently and be re-used until the system is re-flashed or have its parameter cleared (only possible via DroneCAN with strings).

Is there a desired way to accomplish the goal of F3586-22 without having to modify the code or have the external system connect and clear the parameter?

Beacon Broadcasts do not appear to work

I have modified both RemoteIDModule.ino and parameters.h in an attempt to verify that the changes I made to the source code worked when I created the .bin and flashed the chip.

My changes indeed worked and so when I forced the beacon broadcast to work, nothing happened. The only 802.11 traffic I see is the Beacon so that you can access 192.168.4.1, there is no discernible Remote ID traffic that I could see within any payload on those beacons.

What change needs to be done so that Beaconing works as expected?

Add ability to receive RemoteId info from other vehicles

It could be useful for various reasons to be able to receive the location of other drones that are publishing using a remote id. Some examples are:

  • warning the pilot of other drones in the area
  • object avoidance of other drones
  • automatic monitoring/filming of drones in the area

Need Failure Mode Simulation for DOC testing

In order to meet the requirements of the DOC for testing in MOC Section 8, we need the ability to simulate failures in the following items:

  • Need to simulate fail the transmitter so the PFST fails, and the operator is provided indication of this failure. This has to be done on the ground, and in the air.
  • Need to simulate UAS unable to recover from uncontrolled descent (7.7.1.2.1) and loss of control of flight trajectory (7.7.1.2.2)
  • Need to simulate loss of GPS position from the GPS. May not need any action. (on ground test, easily done with No Fix)

Operator id issue

In the 1.14 firmware (likely previous ones as well) it requires an operator id otherwise you get the op_id arm error. Since only required in EU jurisdictions some type of mechanism to disable is needed for US based flights. @BluemarkInnovations

ArduRemoteID - Uncontrolled descent or loss of control

In order to meet the requirements of MOV 7.7.1.2, the RID module must report an emergency status (overrides SELF ID) when the UA experiences uncontrolled descent or loss of control.

Possible solutions may include a flag or code from the AP OpenDroneID module to the RID module to indicate this status.

Unable to connect to DroneCanGUI Tool or Ardupilot

I was trying to test the ArduRemoteID with the recommend hardware the ESP32-S3 dev board: https://au.mouser.com/ProductDetail/356-ESP32S3DEVKTM1N8, but I cannot se the device in either DroneCanGUI Tool (here I'm using the usb and uart connection ) or Ardupilot software (using can bus explained in the Ardupilot documentation) but in either case I'm getting the configuration data of the DroneCanDevice, don't know if i have to send opendroneid messages in order to activate the device or em I missing something, the device RGB just turn red even one I connected to Pixhawk can bus with opendroneid firmware enabled.

Captura de pantalla 2023-01-10 a la(s) 18 54 01

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.