diff --git a/en/SUMMARY.md b/en/SUMMARY.md index d80acbdee378..b85b0d475588 100644 --- a/en/SUMMARY.md +++ b/en/SUMMARY.md @@ -165,7 +165,7 @@ - [AirMind MindPX](flight_controller/mindpx.md) - [AirMind MindRacer](flight_controller/mindracer.md) - [ARK Electronics ARKV6X](flight_controller/ark_v6x.md) - - [ARK FPV Flight Controller](flight_controller/ark_fpv.md) + - [ARK FPV Flight Controller](flight_controller/ark_fpv.md) - [ARK Pi6X Flow Flight Controller](flight_controller/ark_pi6x.md) - [CUAV X7](flight_controller/cuav_x7.md) - [CUAV Nora](flight_controller/cuav_nora.md) @@ -252,7 +252,7 @@ - [Avionics Anonymous Laser Altimeter UAVCAN Interface (CAN)](dronecan/avanon_laser_interface.md) - [GNSS (GPS)](gps_compass/index.md) - [ARK GPS (CAN)](dronecan/ark_gps.md) - - [ARK TESEO GPS](dronecan/ark_teseo_gps.md) + - [ARK TESEO GPS](dronecan/ark_teseo_gps.md) - [CUAV NEO 3 GPS](gps_compass/gps_cuav_neo_3.md) - [CUAV NEO 3 Pro GPS (CAN)](gps_compass/gps_cuav_neo_3pro.md) - [CUAV NEO 3X GPS (CAN)](gps_compass/gps_cuav_neo_3x.md) @@ -609,6 +609,7 @@ - [MountOrientation](msg_docs/MountOrientation.md) - [NavigatorMissionItem](msg_docs/NavigatorMissionItem.md) - [NavigatorStatus](msg_docs/NavigatorStatus.md) + - [NeuralControl](msg_docs/NeuralControl.md) - [NormalizedUnsignedSetpoint](msg_docs/NormalizedUnsignedSetpoint.md) - [NpfgStatus](msg_docs/NpfgStatus.md) - [ObstacleDistance](msg_docs/ObstacleDistance.md) @@ -762,6 +763,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) diff --git a/en/advanced/neural_networks.md b/en/advanced/neural_networks.md new file mode 100644 index 000000000000..1e1ba9b952bc --- /dev/null +++ b/en/advanced/neural_networks.md @@ -0,0 +1,42 @@ +# Neural Networks + +There are several reasons you might want to use neural networks inside of PX4, this documentation together with an example module will help you to get started with this. The code is made to run directly on an embedded flight controller (FCU), but it can easily be modified to run on a more powerful companion computer as well. + +The example module only handles inference as of now, so you will need to train the network in another framework and import it here. You can find a rough guide to that as well. + +## Inference library + +First of all we need a way to run inference on the neural network. In this example implementation TensorFlow Lite Micro ([TFLM](https://github.com/tensorflow/tflite-micro)) is used, but there are several other possibilities, like [Eigen](https://eigen.tuxfamily.org/index.php?title=Main_Page) and [Executorch](https://pytorch.org/executorch-overview). Do note however that importing new libraries into PX4 is not necessarily straight forward. + +TFLM already has support for several architectures, so there is a high likelihood that you can build it for the board you want to use. The build is already tested for three configurations and can be created with the following commands: + + ```sh + make px4_sitl_neural + ``` + + ```sh + make px4_fmu-v6c_neural + ``` + + ```sh + make mro_pixracerpro_neural + ``` + +:::tip +If you have a board you want to test neural control on, which is supported by px4, but not part of the examples: got to boards/"your board" and add "CONFIG_MODULES_MC_NN_CONTROL=y" to your .px4board file +::: + + +## Neural Control +(maybe create this as a separate page) +Nerual networks can be used for a broad range of implementations, like estimation and computer vision, in the example module it is used to replace the [controllers](../flight_stack/controller_diagrams.md). + +The module is called mc_nn_control and replaces the entire controller structure as well as the control allocator. + +## Input +The input is + +## Output + +## Frame Representation +ENU, NED \ No newline at end of file diff --git a/en/advanced/nn_module_utilities.md b/en/advanced/nn_module_utilities.md new file mode 100644 index 000000000000..7cf315df5251 --- /dev/null +++ b/en/advanced/nn_module_utilities.md @@ -0,0 +1,31 @@ +# Neural Network Module Utilities + +This page will explain the parts of the module that does not directly concern something with the neural network, but PX4 related implementations, so that you more easily can shape the module to your needs. + +To learn more about how PX4 works in general, it is recommended to start with [Getting started](../dev_setup/getting_started.md). + +## Autostart + +In the PX4-Autopilot source code there are startup scripts, in these I have added a line for the mc_nn_control module. in ROMFS/px4fmu_common/init.d/rc.mc_apps it checks wether the module is included by looking for the parameter MC_NN_EN. If this is set to 1, which is the default value, the module will be started when booting PX4. Similarly you could create other parameters in the src/modules/mc_nn_control/mc_nn_control_params.c file for other startup script checks. + +:::info +Note that it's only the first time you build that the default param value will overwrite the current one. So if you change it in the param file it will not be changed when flashing to the controller again. Todo this you can change it in QGC or in the [terminal](../modules/modules_command.md#param). +::: + +## 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: + +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. +1. 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. +1. [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. +1. [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. +1. 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. +1. Listen to the [VehicleStatus](../msg_docs/VehicleStatus.md) topic. If the nav_state equals the assigned mode_id, then the Neural Controller is activated. +1. 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. + +## 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 under the debug category. So for these messages to be saved in you ulog logs you need to include debug in the SDLOG_PROFILE parameter. + +## Timing \ No newline at end of file diff --git a/en/advanced/tflm.md b/en/advanced/tflm.md new file mode 100644 index 000000000000..c6d03d654182 --- /dev/null +++ b/en/advanced/tflm.md @@ -0,0 +1,15 @@ +# TensorFlow Lite Micro (TFLM) + +TFLM is a mature inference library intended for use on embedded devices. It is therefore a solid library for doing inference on an FCU within PX4. This is a guide on how to use the TFLM library, not so much to explain the exact implementation in the mc_nn_control module. + +## Network Format + +## Network Conversion + +## Operations and Resolver + +## Interpreter + +## Inputs + +## Outputs \ No newline at end of file diff --git a/en/msg_docs/NeuralControl.md b/en/msg_docs/NeuralControl.md new file mode 100644 index 000000000000..59c480fec270 --- /dev/null +++ b/en/msg_docs/NeuralControl.md @@ -0,0 +1,19 @@ +# NeuralControl (UORB message) + +Logging topic from mc_nn_control module + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/NeuralControl.msg) + +```c +# Neural control logging +uint64 timestamp # time since system start (microseconds) + +float32[15] observation # Observation vector (pos error (3), att (6d), lin vel (3), ang vel (3)) +float32[6] wrench # Forces and Torques before allocation +float32[4] motor_thrust # Thrust per motor + +int32 controller_time # Time spent from input to output in microseconds +int32 control_inference_time # Time spent in the control inference in microseconds +int32 allocation_inference_time # Time spent in the allocation inference in microseconds + +```