Neural Control Mode (#24366)

* Add tflm to px4 with module

 - Add TensorFlow Lite Micro(TFLM) as a library in px4
 - Make a module that uses neural network inference for control, which uses TFLM for inference
 - Make board config files for PX4 with neural module

* Added neural flight mode

* Add posibility to read of inference times

* Fix comments from review:

- Switch ssh link to https link in submodule
- Remove mc_nn_control from startup

* Add tflm to px4 with module

 - Add TensorFlow Lite Micro(TFLM) as a library in px4
 - Make a module that uses neural network inference for control, which uses TFLM for inference
 - Make board config files for PX4 with neural module

* Added neural flight mode

* Add posibility to read of inference times

* Remove auto start

* Add logging from neural control module

* Fix automatic startup to only be when module is included

* Switch to flight mode registration

* Add docs

* Change min/max/coeff to actual parameters

* add figures to neural network docs

* Switch to e2e network

* Remove toolchain changes and replace with instructions in docs

* Get ready for merge after toolchain upgrade

* switch back to submodule

* Try to figure out cmake

* Get CI working with new toolchain

* Remove fork dependency

* Finalize PR

* fix toolchain inclusion

* Fix ctype_base.h include

* Cleanup includes for TFLM

* Remove redundant std

* Update FW module names in board files

* Fix docs

* Remove cstdlib copy

* Copy header from nuttx

* Prettier, markup, layout

* NeuralControl.msg - update uorb comments to current standard

* Add description to neural topic

* Fix typo

* Typo

* TFLM and Module utitlities

* Neural networks top level

* Update docs

* Add manual control

* Update docs

* Revert the manual control attempt

* Update docs/en/advanced/nn_module_utilities.md

* Add posibility to set trajectory setpoint with manual control

---------

Co-authored-by: Pedro Roque <padr@kth.se>
Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
Co-authored-by: Ramon Roche <mrpollo@gmail.com>
This commit is contained in:
Sindre Meyer Hegre
2025-07-25 19:42:12 +02:00
committed by GitHub
parent 132f7e9e0d
commit 3be0cb077c
29 changed files with 2944 additions and 3 deletions

3
.gitmodules vendored
View File

@@ -92,3 +92,6 @@
[submodule "test/fuzztest"]
path = test/fuzztest
url = https://github.com/google/fuzztest.git
[submodule "src/lib/tensorflow_lite_micro/tflite_micro"]
path = src/lib/tensorflow_lite_micro/tflite_micro
url = https://github.com/PX4/tflite-micro.git

View File

@@ -36,3 +36,8 @@ mc_pos_control start
# Start Multicopter Land Detector.
#
land_detector start multicopter
if param compare -s MC_NN_EN 1
then
mc_nn_control start
fi

View File

@@ -0,0 +1,101 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2"
CONFIG_DRIVERS_ADC_ADS1115=y
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_DPS310=y
CONFIG_DRIVERS_BATT_SMBUS=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI085=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_LIB_TFLM=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_FW_MODE_MANAGER=n
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n
CONFIG_MODULES_FW_RATE_CONTROL=n
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_MC_NN_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=n
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UUV_ATT_CONTROL=n
CONFIG_MODULES_UUV_POS_CONTROL=n
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=n
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_REFLECT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
CONFIG_SYSTEMCMDS_SERIAL_TEST=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y

View File

@@ -0,0 +1,95 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS6"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS5"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_MS5611=y
CONFIG_DRIVERS_BATT_SMBUS=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_HEATER=y
CONFIG_DRIVERS_IMU_BOSCH_BMI055=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_COMMON_INS=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PX4IO=y
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2
CONFIG_LIB_TFLM=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_FW_MODE_MANAGER=n
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n
CONFIG_MODULES_FW_RATE_CONTROL=n
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_NN_CONTROL=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=n
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=n
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y

View File

@@ -0,0 +1,81 @@
CONFIG_PLATFORM_POSIX=y
CONFIG_BOARD_TESTING=y
CONFIG_BOARD_ETHERNET=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_LIB_TFLM=y
CONFIG_MODULES_AIRSHIP_ATT_CONTROL=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE=y
CONFIG_MODULES_EKF2=y
CONFIG_EKF2_VERBOSE_STATUS=y
CONFIG_EKF2_AUX_GLOBAL_POSITION=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL=y
CONFIG_FIGURE_OF_EIGHT=y
CONFIG_MODULES_FW_RATE_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MAVLINK_DIALECT="development"
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_NN_CONTROL=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
CONFIG_MODULES_PAYLOAD_DELIVERER=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_REPLAY=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_COMMON_SIMULATION=y
CONFIG_MODULES_SIMULATION_GZ_BRIDGE=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DYN=y
CONFIG_SYSTEMCMDS_FAILURE=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SHUTDOWN=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_DYN_HELLO=y
CONFIG_EXAMPLES_FAKE_GPS=y
CONFIG_EXAMPLES_FAKE_IMU=y
CONFIG_EXAMPLES_FAKE_MAGNETOMETER=y
CONFIG_EXAMPLES_HELLO=y
CONFIG_EXAMPLES_PX4_MAVLINK_DEBUG=y
CONFIG_EXAMPLES_PX4_SIMPLE_APP=y
CONFIG_EXAMPLES_WORK_ITEM=y

Binary file not shown.

After

Width:  |  Height:  |  Size: 55 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 50 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 30 KiB

View File

@@ -782,6 +782,9 @@
- [Camera Integration/Architecture](camera/camera_architecture.md)
- [Computer Vision](advanced/computer_vision.md)
- [Motion Capture (VICON, Optitrack, NOKOV)](tutorials/motion-capture.md)
- [Neural Networks](advanced/neural_networks.md)
- [Neural Network Module Utilities](advanced/nn_module_utilities.md)
- [TensorFlow Lite Micro (TFLM)](advanced/tflm.md)
- [Installing driver for Intel RealSense R200](advanced/realsense_intel_driver.md)
- [Switching State Estimators](advanced/switching_state_estimators.md)
- [Out-of-Tree Modules](advanced/out_of_tree_modules.md)

View File

@@ -0,0 +1,116 @@
# Neural Networks
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
::: warning
This is an experimental module.
Use at your own risk.
:::
The Multicopter Neural Network (NN) module ([mc_nn_control](../modules/modules_controller.md#mc_nn_control)) is an example module that allows you to experiment with using a pre-trained neural network on PX4.
It might be used, for example, to experiment with controllers for non-traditional drone morphologies, computer vision tasks, and so on.
The module integrates a pre-trained neural network based on the [TensorFlow Lite Micro (TFLM)](../advanced/tflm.md) module.
The module is trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md) multicopter frame.
While the controller is fairly robust, and might work on other platforms, we recommend [Training your own Network](#training-your-own-network) if you use a different vehicle.
Note that after training the network you will need to update and rebuild PX4.
TLFM is a mature inference library intended for use on embedded devices.
It has support for several architectures, so there is a high likelihood that you can build it for the board you want to use.
If not, there are other possible NN frameworks, such as [Eigen](https://eigen.tuxfamily.org/index.php?title=Main_Page) and [Executorch](https://pytorch.org/executorch-overview).
This document explains how you can include the module in your PX4 build, and provides a broad overview of how it works.
The other documents in the section provide more information about the integration, allowing you to replace the NN with a version trained on different data, or even to replace the TLFM library altogether.
If you are looking for more resources to learn about the module, a website has been created with links to a youtube video and a workshop paper. A full master's thesis will be added later. [A Neural Network Mode for PX4 on Embedded Flight Controllers](https://ntnu-arl.github.io/px4-nns/).
## Neural Network PX4 Firmware
The module has been tested on a number of configurations, which can be build locally using the commands:
```sh
make px4_sitl_neural
```
```sh
make px4_fmu-v6c_neural
```
```sh
make mro_pixracerpro_neural
```
You can add the module to other board configurations by modifying their `default.px4board file` configuration to include these lines:
```sh
CONFIG_LIB_TFLM=y
CONFIG_MODULES_MC_NN_CONTROL=y
```
:::tip
The `mc_nn_control` module takes up roughly 50KB, and many of the `default.px4board file` are already close to filling all the flash on their boards. To make room for the neural control module you can remove the include statements for other modules, such as FW, rover, VTOL and UUV.
:::
## Example Module Overview
The example module replaces the entire controller structure as well as the control allocator, as shown in the diagram below:
![neural_control](../../assets/advanced/neural_control.png)
In the [controller diagram](../flight_stack/controller_diagrams.md) you can see the [uORB message](../middleware/uorb.md) flow.
We hook into this flow by subscribing to messages at particular points, using our neural network to calculate outputs, and then publishing them into the next point in the flow.
We also need to stop the module publishing the topic to be replaced, which is covered in [Neural Network Module: System Integration](nn_module_utilities.md)
### Input
The input can be changed to whatever you want.
Set up the input you want to use during training and then provide the same input in PX4.
In the Neural Control module the input is an array of 15 numbers, and consists of these values in this order:
- [3] Local position error. (goal position - current position)
- [6] The first 2 rows of a 3 dimensional rotation matrix.
- [3] Linear velocity
- [3] Angular velocity
All the input values are collected from uORB topics and transformed into the correct representation in the `PopulateInputTensor()` function.
PX4 uses the NED frame representation, while the Aerial Gym Simulator, in which the NN was trained, uses the ENU representation.
Therefore two rotation matrices are created in the function and all the inputs are transformed from the NED representation to the ENU one.
![ENU-NED](../../assets/advanced/ENU-NED.png)
ENU and NED are just rotation representations, the translational difference is only there so both can be seen in the same figure.
### Output
The output consists of 4 values, the motor forces, one for each motor.
These are transformed in the `RescaleActions()` function.
This is done because PX4 expects normalized motor commands while the Aerial Gym Simulator uses physical values.
So the output from the network needs to be normalized before they can be sent to the motors in PX4.
The commands are published to the [ActuatorMotors](../msg_docs/ActuatorMotors.md) topic.
The publishing is handled in `PublishOutput(float* command_actions)` function.
:::tip
If the neural control mode is too aggressive or unresponsive the [MC_NN_THRST_COEF](../advanced_config/parameter_reference.md#MC_NN_THRST_COEF) parameter can be tuned.
Decrease it for more thrust.
:::
## Training your own Network
The network is currently trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md).
But the controller is somewhat robust, so it could work directly on other platforms, but performing system identification and training a new network is recommended.
Since the Aerial Gym Simulator is open-source you can download it and train your own networks as long as you have access to an NVIDIA GPU.
If you want to train a control network optimized for your platform you can follow the instructions in the [Aerial Gym Documentation](https://ntnu-arl.github.io/aerial_gym_simulator/9_sim2real/).
You should do one system identification flight for this and get an approximate inertia matrix for your platform.
On the `sys-id` flight you need ESC telemetry, you can read more about that in [DSHOT](../peripherals/dshot.md).
Then do the following steps:
- Do a hover flight
- Read of the logs what RPM is required for the drone to hover.
- Use the weight of each motor, length of the motor arms, total weight of the platform with battery to calculate an approximate inertia matrix for the platform.
- Insert these values into the Aerial Gym configuration and train your network.
- Convert the network as explained in [TFLM](tflm.md).

View File

@@ -0,0 +1,86 @@
# Neural Network Module: System Integration
The neural control module ([mc_nn_control](../modules/modules_controller.md#mc_nn_control)) implements an end-to-end controller utilizing neural networks.
The parts of the module directly concerned with generating the code for the trained neural network and integrating it into the module are covered in [TensorFlow Lite Micro (TFLM)](../advanced/tflm.md).
This page covers the changes that were made to integrate the module into PX4, both within the module, and in larger system configuration.
::: tip
This topic should help you to shape the module to your own needs.
You will need some familiarity with PX4 development.
For more information see the developer [Getting Started](../dev_setup/getting_started.md).
:::
## Autostart
A line to autostart the [mc_nn_control](../modules/modules_controller.md#mc_nn_control) module has been added in the [`ROMFS/px4fmu_common/init.d/rc.mc_apps`](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d/rc.mc_apps) startup script.
It checks whether the module is included by looking for the parameter [MC_NN_EN](../advanced_config/parameter_reference.md#MC_NN_EN).
If this is set to `1` (the default value), the module will be started when booting PX4.
Similarly you could create other parameters in the [`mc_nn_control_params.c`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mc_nn_control/mc_nn_control_params.c) file for other startup script checks.
## Custom Flight Mode
The module creates its own flight mode "Neural Control" which lets you choose it from the flight mode menu in QGC and bind it to a switch on you RC controller.
This is done by using the [ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) internally.
This involves several steps and is visualized here:
:::info
The module does not actually use ROS 2, it just uses the API exposed through uORB topics.
:::
:::info
In some QGC versions the flight mode does not show up, so make sure to update to the newest version.
This only works for some flight controllers, so you might have to use an RC controller to switch to the correct external flight mode.
:::
![neural_mode_registration](../../assets/advanced/neural_mode_registration.png)
1. Publish a [RegisterExtComponentRequest](../msg_docs/RegisterExtComponentRequest.md).
This specifies what you want to create, you can read more about this in the [Control Interface](../ros2/px4_ros2_control_interface.md).
In this case we register an arming check and a mode.
2. Wait for a [RegisterExtComponentReply](../msg_docs/RegisterExtComponentReply.md).
This will give feedback on wether the mode registration was successful, and what the mode and arming check id is for the new mode.
3. [Optional] With the mode id, publish a [VehicleControlMode](../msg_docs/VehicleControlMode.md) message on the `config_control_setpoints` topic.
Here you can configure what other modules run in parallel.
The example controller replaces everything, so it turns off allocation.
If you want to replace other parts you can enable or disable the modules accordingly.
4. [Optional] With the mode id, publish a [ConfigOverrides](../msg_docs/ConfigOverrides.md) on the `config_overrides_request` topic.
(This is not done in the example module) This will let you defer failsafes or stop it from automatically disarming.
5. When the mode has been registered a [ArmingCheckRequest](../msg_docs/ArmingCheckRequest.md) will be sent, asking if your mode has everything it needs to run.
This message must be answered with a [ArmingCheckReply](../msg_docs/ArmingCheckReply.md) so the mode is not flagged as unresponsive.
In this response it is possible to set what requirements the mode needs to run, like local position.
If any of these requirements are set the commander will stop you from switching to the mode if they are not fulfilled.
It is also important to set health_component_index and num_events to 0 to not get a segmentation fault.
Unless you have a health component or events.
6. Listen to the [VehicleStatus](../msg_docs/VehicleStatus.md) topic.
If the nav_state equals the assigned `mode_id`, then the Neural Controller is activated.
7. When active the module will run the controller and publish to [ActuatorMotors](../msg_docs/ActuatorMotors.md).
If you want to replace a different part of the controller, you should find the appropriate topic to publish to.
To see how the requests are handled you can check out [src/modules/commander/ModeManagement.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/commander/ModeManagement.cpp).
## Logging
To add module-specific logging a new topic has been added to [uORB](../middleware/uorb.md) called [NeuralControl](../msg_docs/NeuralControl.md).
The message definition is also added in `msg/CMakeLists.txt`, and to [`src/modules/logger/logged_topics.cpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/logger/logged_topics.cpp) under the debug category.
For these messages to be saved in your logs you need to include `debug` in the [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) parameter.
## Timing
The module has two includes for measuring the inference times.
The first one is a driver that works on the actual flight controller units, but a second one, `chrono`, is loaded for SITL testing.
Which timing library is included and used is based on wether PX4 is built with NUTTX or not.
## Changing the setpoint
The module uses the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages position fields to define its target.
To follow a trajectory, you can send updated setpoints.
For an example of how to do this in a PX4 module, see the [mc_nn_testing](https://github.com/SindreMHegre/PX4-Autopilot-public/tree/main/src/modules/mc_nn_testing) module in this fork.
Note that this is not included in upstream PX4.
To use it, copy the module folder from the linked repository into your workspace, and enable it by adding the following line to your `.px4board` file:
```sh
CONFIG_MODULES_MC_NN_TESTING=y
```

77
docs/en/advanced/tflm.md Normal file
View File

@@ -0,0 +1,77 @@
# TensorFlow Lite Micro (TFLM)
The PX4 [Multicopter Neural Network](advanced/neural_networks.md) module ([mc_nn_control](../modules/modules_controller.md#mc_nn_control)) integrates a neural network that uses the [TensorFlow Lite Micro (TFLM)](https://github.com/tensorflow/tflite-micro) inference library.
This is a mature inference library intended for use on embedded devices, and is hence a suitable choice for PX4.
This guide explains how the TFLM library is integrated into the [mc_nn_control](../modules/modules_controller.md#mc_nn_control) module, and the changes you would have to make to use it for your own neural network.
::: tip
For more information, see the [TFLM guide](https://ai.google.dev/edge/litert/microcontrollers/get_started).
:::
## TLMF NN Formats
TFLM uses networks in its own [tflite format](https://ai.google.dev/edge/litert/models/convert).
However, since many microcontrollers do not have native filesystem support, a tflite file can be converted to a C++ source and header file.
This is what is done in `mc_nn_control`.
The tflight neural network is represented in code by the files [`control_net.cpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mc_nn_control/control_net.cpp) and [`control_net.hpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mc_nn_control/control_net.hpp).
### Getting a Network in tflite Format
There are many online resource for generating networks in the `.tflite` format.
For this example we trained the network in the open source [Aerial Gym Simulator](https://ntnu-arl.github.io/aerial_gym_simulator/).
Aerial Gym includes a guide, and supports RL both for control and vision-based navigation tasks.
The project includes conversion code for `PyTorch -> TFLM` in the [resources/conversion](https://github.com/ntnu-arl/aerial_gym_simulator/tree/main/resources/conversion) folder.
### Updating `mc_nn_control` with your own NN
You can convert a `.tflite` network into a `.cc` file in the ubuntu terminal with this command:
```sh
xxd -i converted_model.tflite > model_data.cc
```
You will then have to modify the `control_net.hpp` and `control_net.cpp` to include the data from `model_data.cc`:
- Take the size of the network in the bottom of the `.cc` file and replace the size in `control_net.hpp`.
- Take the data in the model array in the `cc` file, and replace the ones in `control_net.cpp`.
You are now ready to run your own network.
## Code Explanation
This section explains the code used to integrate the NN in `control_net.cpp`.
### Operations and Resolver
Firstly we need to create the resolver and load the needed operators to run inference on the NN.
This is done in the top of `mc_nn_control.cpp`.
The number in `MicroMutableOpResolver<3>` represents how many operations you need to run the inference.
A full list of the operators can be found in the [micro_mutable_op_resolver.h](https://github.com/tensorflow/tflite-micro/blob/main/tensorflow/lite/micro/micro_mutable_op_resolver.h) file.
There are quite a few supported operators, but you will not find the most advanced ones.
In the control example the network is fully connected so we use `AddFullyConnected()`.
Then the activation function is ReLU, and we `AddAdd()` for the bias on each neuron.
### Interpreter
In the `InitializeNetwork()` we start by setting up the model that we loaded from the source and header file.
Next is to set up the interpreter, this code is taken from the TFLM documentation and is thoroughly explained there.
The end state is that the `_control_interpreter` is set up to later run inference with the `Invoke()` member function.
The `_input_tensor` is also defined, it is fetched from `_control_interpreter->input(0)`.
### Inputs
The `_input_tensor` is filled in the `PopulateInputTensor()` function.
`_input_tensor` works by accessing the `->data.f` member array and fill in the required inputs for your network.
The inputs used in the control network is covered in [Neural Networks](../advanced/neural_networks.md).
### Outputs
For the outputs the approach is fairly similar to the inputs.
After setting the correct inputs, calling the `Invoke()` function the outputs can be found by getting `_control_interpreter->output(0)`.
And from the output tensor you get the `->data.f` array.

View File

@@ -141,6 +141,7 @@ set(msg_files
MountOrientation.msg
NavigatorMissionItem.msg
NavigatorStatus.msg
NeuralControl.msg
NormalizedUnsignedSetpoint.msg
ObstacleDistance.msg
OffboardControlMode.msg

13
msg/NeuralControl.msg Normal file
View File

@@ -0,0 +1,13 @@
# Neural control
#
# Debugging topic for the Neural controller, logs the inputs and output vectors of the neural network, and the time it takes to run
# Publisher: mc_nn_control
# Subscriber: logger
uint64 timestamp # [us] Time since system start
float32[15] observation # Observation vector (pos error (3), att (6d), lin vel (3), ang vel (3))
float32[4] network_output # Output from neural network
int32 controller_time # [us] Time spent from input to output
int32 inference_time # [us] Time spent for NN inference

View File

@@ -52,10 +52,26 @@ function(px4_os_add_flags)
include_directories(BEFORE SYSTEM
${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/nuttx/include
)
if(CONFIG_LIB_TFLM) # Since TFLM uses the standard C++ library, we need to exclude the NuttX C++ include path
add_custom_target(copy_header ALL
COMMAND ${CMAKE_COMMAND} -E copy # One of the header files from nuttx is needed
${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/nuttx/include/cxx/cstdlib
${PX4_SOURCE_DIR}/src/lib/tensorflow_lite_micro/include/cstdlib
)
include_directories(BEFORE SYSTEM
${PX4_SOURCE_DIR}/src/lib/tensorflow_lite_micro/include
)
else()
include_directories(BEFORE SYSTEM
${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/nuttx/include/cxx
${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/include/cxx # custom new
)
endif()
include_directories(
${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/nuttx/arch/${CONFIG_ARCH}/src/${CONFIG_ARCH_FAMILY}
${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/nuttx/arch/${CONFIG_ARCH}/src/chip
@@ -71,9 +87,12 @@ function(px4_os_add_flags)
-fno-rtti
-fno-sized-deallocation
-fno-threadsafe-statics
-nostdinc++ # prevent using the toolchain's std c++ library
)
if(NOT CONFIG_LIB_TFLM)
list(APPEND cxx_flags -nostdinc++) # prevent using the toolchain's std c++ library if building for anything else than TFLM
endif()
foreach(flag ${cxx_flags})
add_compile_options($<$<COMPILE_LANGUAGE:CXX>:${flag}>)
endforeach()

View File

@@ -75,6 +75,7 @@ add_subdirectory(stick_yaw EXCLUDE_FROM_ALL)
add_subdirectory(systemlib EXCLUDE_FROM_ALL)
add_subdirectory(system_identification EXCLUDE_FROM_ALL)
add_subdirectory(tecs EXCLUDE_FROM_ALL)
add_subdirectory(tensorflow_lite_micro EXCLUDE_FROM_ALL)
add_subdirectory(terrain_estimation EXCLUDE_FROM_ALL)
add_subdirectory(timesync EXCLUDE_FROM_ALL)
add_subdirectory(tinybson EXCLUDE_FROM_ALL)

View File

@@ -0,0 +1,110 @@
############################################################################
#
# Copyright (c) 2025 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.
#
############################################################################
if(CONFIG_LIB_TFLM)
px4_add_git_submodule(TARGET git_tflite-micro PATH tflite_micro)
set(TFLITE_DOWNLOADS_DIR ${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/lite/micro/tools/make/downloads)
get_directory_property(FLAGS COMPILE_OPTIONS)
list(REMOVE_ITEM FLAGS "-Wcast-align")
set_directory_properties(PROPERTIES COMPILE_OPTIONS "${FLAGS}")
file(GLOB TFLITE_MICRO_SRCS
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/lite/*.cc
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/lite/micro/*.cc
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/lite/micro/arena_allocator/*.cc
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/lite/micro/memory_planner/*.cc
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/lite/micro/tflite_bridge/*.cc
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/lite/micro/kernels/*.cc
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/lite/kernels/*.cc
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/lite/kernels/internal/*.cc
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/lite/kernels/internal/reference/*.cc
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/lite/core/api/*.cc
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/lite/core/c/*.cc
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/lite/schema/*.cc
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/compiler/mlir/lite/core/api/*.cc
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/compiler/mlir/lite/schema/*.cc
)
# Filter out tests as they cause errors
list(FILTER TFLITE_MICRO_SRCS EXCLUDE REGEX ".*_test.*\\.cc$")
set(TFLM_INCLUDE_DIRS
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro
${TFLITE_DOWNLOADS_DIR}
${TFLITE_DOWNLOADS_DIR}/flatbuffers/include
${TFLITE_DOWNLOADS_DIR}/ruy
${TFLITE_DOWNLOADS_DIR}/gemmlowp
${TFLITE_DOWNLOADS_DIR}/cmsis/Cortex_DFP/Device/ARMCM7/Include
${TFLITE_DOWNLOADS_DIR}/cmsis/CMSIS/Core/Include
${TFLITE_DOWNLOADS_DIR}/cmsis
)
set(TFLM_BUILD_TIMESTAMP ${CMAKE_CURRENT_BINARY_DIR}/tflm_build_complete.timestamp)
add_custom_command(
OUTPUT ${TFLM_BUILD_TIMESTAMP}
COMMAND ${CMAKE_COMMAND} -E copy_if_different
${CMAKE_CURRENT_SOURCE_DIR}/generate_cc_arrays.py
${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro/tensorflow/lite/micro/tools/generate_cc_arrays.py
# TODO maybe change this if building for other architectures
COMMAND make -f tensorflow/lite/micro/tools/make/Makefile MICRO_LITE_EXAMPLE_TESTS= MICRO_LITE_BENCHMARKS= MICRO_LITE_TEST_SRCS= MICRO_LITE_INTEGRATION_TESTS= third_party_downloads
# Create timestamp file to mark completion
COMMAND ${CMAKE_COMMAND} -E touch ${TFLM_BUILD_TIMESTAMP}
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/tflite_micro
COMMENT "Downloading TFLM third party dependencies"
DEPENDS git_tflite-micro
VERBATIM
)
add_custom_target(build_tflm_native
DEPENDS ${TFLM_BUILD_TIMESTAMP}
)
px4_add_library(tensorflow_lite_micro ${TFLITE_MICRO_SRCS})
if(CONFIG_BOARD_TOOLCHAIN STREQUAL "arm-none-eabi")
add_definitions(-include "${CMAKE_CURRENT_SOURCE_DIR}/include/px4_tflm_fix.h")
endif()
target_include_directories(tensorflow_lite_micro PUBLIC ${TFLM_INCLUDE_DIRS})
add_dependencies(tensorflow_lite_micro build_tflm_native)
target_compile_features(tensorflow_lite_micro PRIVATE cxx_std_17)
target_compile_options(tensorflow_lite_micro PUBLIC
-Wno-float-equal
-Wno-shadow
)
endif()

View File

@@ -0,0 +1,7 @@
config LIB_TFLM
bool "TensorFlow Lite Micro"
default n
---help---
TensorFlow Lite Micro is a lightweight version of TensorFlow Lite designed for microcontrollers and other resource-constrained devices.
It enables running machine learning models on devices with limited computational power and memory.
This library is used for running neural networks on the PX4 autopilot.

View File

@@ -0,0 +1,11 @@
#pragma once
// Fix for ctype_base.h character class masks
#define _U 0x01
#define _L 0x02
#define _N 0x04
#define _X 0x08
#define _S 0x10
#define _P 0x20
#define _B 0x40
#define _C 0x80

View File

@@ -296,6 +296,7 @@ void LoggedTopics::add_debug_topics()
add_topic("mag_worker_data");
add_topic("sensor_preflight_mag", 500);
add_topic("actuator_test", 500);
add_topic("neural_control", 50);
}
void LoggedTopics::add_estimator_replay_topics()

View File

@@ -0,0 +1,54 @@
############################################################################
#
# Copyright (c) 2025 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.
#
############################################################################
add_compile_options(-Wno-float-equal)
get_directory_property(FLAGS COMPILE_OPTIONS)
list(REMOVE_ITEM FLAGS "-Wcast-align")
set_directory_properties(PROPERTIES COMPILE_OPTIONS "${FLAGS}")
px4_add_module(
MODULE mc_nn_control
MAIN mc_nn_control
COMPILE_FLAGS
SRCS
mc_nn_control.cpp
mc_nn_control.hpp
control_net.cpp
control_net.hpp
DEPENDS
tensorflow_lite_micro
px4_work_queue
mathlib
)
target_link_libraries(mc_nn_control PRIVATE tensorflow_lite_micro)
target_include_directories(mc_nn_control PRIVATE
${CMAKE_SOURCE_DIR}/src/lib/tensorflow_lite_micro)

View File

@@ -0,0 +1,12 @@
menuconfig MODULES_MC_NN_CONTROL
bool "mc_nn_control"
default n
---help---
Enable support for mc_nn_control"
menuconfig USER_MC_NN_CONTROL
bool "mc_nn_control running as userspace module"
default y
depends on BOARD_PROTECTED && MODULES_MC_NN_CONTROL
---help---
Put mc_nn_control in userspace memory

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,4 @@
#include <cstdint>
constexpr unsigned int control_net_tflite_size = 15088;
extern const unsigned char control_net_tflite[];

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,166 @@
/****************************************************************************
*
* Copyright (c) 2025 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.
*
****************************************************************************/
/**
* @file mc_nn_control.h
* Multicopter Neural Network Control module, from position setpoints to control allocator.
*
* @author Sindre Meyer Hegre <sindre.hegre@gmail.com>
* @author Welf Rehberg <welf.rehberg@ntnu.no>
*/
#pragma once
#include <perf/perf_counter.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/log.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/px4_work_queue/WorkItem.hpp>
#include <matrix/matrix/math.hpp>
#include <tflite_micro/tensorflow/lite/micro/micro_mutable_op_resolver.h>
#include <tflite_micro/tensorflow/lite/micro/micro_interpreter.h>
#include <tflite_micro/tensorflow/lite/schema/schema_generated.h>
// Include model
#include "control_net.hpp"
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionCallback.hpp>
// Subscriptions
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/trajectory_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_angular_velocity.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/register_ext_component_reply.h>
#include <uORB/topics/arming_check_request.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/manual_control_setpoint.h>
// Publications
#include <uORB/topics/actuator_motors.h>
#include <uORB/topics/neural_control.h>
#include <uORB/topics/register_ext_component_request.h>
#include <uORB/topics/unregister_ext_component.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/arming_check_reply.h>
using namespace time_literals; // For the 1_s in the subscription interval
class MulticopterNeuralNetworkControl : public ModuleBase<MulticopterNeuralNetworkControl>, public ModuleParams,
public px4::WorkItem
{
public:
MulticopterNeuralNetworkControl();
~MulticopterNeuralNetworkControl() override;
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
/** @see ModuleBase */
static int custom_command(int argc, char *argv[]);
/** @see ModuleBase */
static int print_usage(const char *reason = nullptr);
/** @see ModuleBase */
int print_status() override;
bool init();
private:
void Run() override;
// Functions
void PopulateInputTensor();
void PublishOutput(float *command_actions);
void RescaleActions();
int InitializeNetwork();
int32_t GetTime();
void RegisterNeuralFlightMode();
void UnregisterNeuralFlightMode(int8 arming_check_id, int8 mode_id);
void ConfigureNeuralFlightMode(int8 mode_id);
void ReplyToArmingCheck(int8 request_id);
void CheckModeRegistration();
void generate_trajectory_setpoint(float dt);
void reset_trajectory_setpoint(vehicle_local_position_s &_position);
void check_setpoint_validity(vehicle_local_position_s &_position);
// Subscriptions
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
uORB::Subscription _register_ext_component_reply_sub{ORB_ID(register_ext_component_reply)};
uORB::Subscription _arming_check_request_sub{ORB_ID(arming_check_request)};
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
uORB::Subscription _position_sub{ORB_ID(vehicle_local_position)};
uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)};
uORB::Subscription _attitude_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
uORB::SubscriptionCallbackWorkItem _angular_velocity_sub{this, ORB_ID(vehicle_angular_velocity)};
// Publications
uORB::Publication<actuator_motors_s> _actuator_motors_pub{ORB_ID(actuator_motors)};
uORB::Publication<neural_control_s> _neural_control_pub{ORB_ID(neural_control)};
uORB::Publication<register_ext_component_request_s> _register_ext_component_request_pub{ORB_ID(register_ext_component_request)};
uORB::Publication<unregister_ext_component_s> _unregister_ext_component_pub{ORB_ID(unregister_ext_component)};
uORB::Publication<vehicle_control_mode_s> _config_control_setpoints_pub{ORB_ID(config_control_setpoints)};
uORB::Publication<arming_check_reply_s> _arming_check_reply_pub{ORB_ID(arming_check_reply)};
// Variables
bool _use_neural{false};
bool _sent_mode_registration{false};
perf_counter_t _loop_perf; /**< loop duration performance counter */
hrt_abstime _last_run{0};
uint8 _mode_request_id{231}; //Random value
int8 _arming_check_id{-1};
int8 _mode_id{-1};
tflite::MicroInterpreter *_interpreter;
TfLiteTensor *_input_tensor;
TfLiteTensor *_output_tensor;
float _input_data[15];
trajectory_setpoint_s _trajectory_setpoint;
vehicle_angular_velocity_s _angular_velocity;
vehicle_local_position_s _position;
vehicle_attitude_s _attitude;
manual_control_setpoint_s _manual_control_setpoint{};
DEFINE_PARAMETERS(
(ParamInt<px4::params::MC_NN_MAX_RPM>) _param_max_rpm,
(ParamInt<px4::params::MC_NN_MIN_RPM>) _param_min_rpm,
(ParamFloat<px4::params::MC_NN_THRST_COEF>) _param_thrust_coeff,
(ParamBool<px4::params::MC_NN_MANL_CTRL>) _param_manual_control
)
};

View File

@@ -0,0 +1,83 @@
/****************************************************************************
*
* Copyright (c) 2025 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.
*
****************************************************************************/
/**
* @file mc_nn_control_params.c
* Parameters for the Multicopter Neural Network Control module
*
* @author Sindre Meyer Hegre <sindre.hegre@gmail.com>
*/
/**
* If true the neural network control is automatically started on boot.
*
* @boolean
* @group Neural Control
*/
PARAM_DEFINE_INT32(MC_NN_EN, 1);
/**
* The maximum RPM of the motors. Used to normalize the output of the neural network.
*
* @min 0
* @max 80000
* @group Neural Control
*/
PARAM_DEFINE_INT32(MC_NN_MAX_RPM, 22000);
/**
* The minimum RPM of the motors. Used to normalize the output of the neural network.
*
* @min 0
* @max 80000
* @group Neural Control
*/
PARAM_DEFINE_INT32(MC_NN_MIN_RPM, 1000);
/**
* Thrust coefficient of the motors. Used to normalize the output of the neural network. Divided by 100 000
*
* @min 0.0
* @max 5.0
* @group Neural Control
*/
PARAM_DEFINE_FLOAT(MC_NN_THRST_COEF, 1.2f);
/**
* Enable or disable setting the trajectory setpoint with manual control.
*
* @boolean
* @reboot_required true
* @group Neural Control
*/
PARAM_DEFINE_INT32(MC_NN_MANL_CTRL, 1);