* moving raptor bump compiles and raptor mode appears hovering with RAPTOR seems to work Using Raptor to execute offboard commands works (using multirobot f03825a5795a77c5a095f799eeb8e0b646fe7176 to feed the trajectory_setpoint). Requires more testing simplified rotmat runtime inference frequency multiple arming request response reflects actual readiness adjusting to fit IMU gyro ratemax relaxing control timing warning thresholds for SITL Using mode registration to signal if offboard commands should be forwarded to trajectory_setpoint instead of just hardcoding vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_OFFBOARD adopting new "request_offboard_setpoint" in raptor module replace offboard seems good mc_raptor: overwrite offboard parameter separate raptor config addendum Raptor off by default RAPTOR readme Loading raptor checkpoint from tar works. check if load was successful refactoring: cutting out the pure C interface to allow direct testing of the policy input/output behavior from the file, without fully loading it into memory first adapter not needed anymore ripping out test observation mode (not used in a long time) fixing warnings bump RLtools to fix the remaining warnings Loading RAPTOR checkpoint from sdcard seems to work on FMU-6C embedding Raptor policy into flash works again also printing checkpoint name when using the embedded policy cleaner handling of the checkpoint name back to reading from file ripping out visual odometry checks cleaner more debug but no success bump rlt bump pre next rebase we can publish the no angvel update because we latch onto it with the scheduled work item anyways this kind of runs on the 6c still bad SIH almost flying saving stale traj setpoint yaw new error. timestamp not the problem anymore bump rlt; SIH works with executor shaping up bumping blob (include tar checkpoint) cleaning up fixing formatting update readme * moving raptor bump compiles and raptor mode appears hovering with RAPTOR seems to work Using Raptor to execute offboard commands works (using multirobot f03825a5795a77c5a095f799eeb8e0b646fe7176 to feed the trajectory_setpoint). Requires more testing simplified rotmat runtime inference frequency multiple arming request response reflects actual readiness adjusting to fit IMU gyro ratemax relaxing control timing warning thresholds for SITL Using mode registration to signal if offboard commands should be forwarded to trajectory_setpoint instead of just hardcoding vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_OFFBOARD adopting new "request_offboard_setpoint" in raptor module replace offboard seems good mc_raptor: overwrite offboard parameter separate raptor config addendum Raptor off by default RAPTOR readme Loading raptor checkpoint from tar works. check if load was successful refactoring: cutting out the pure C interface to allow direct testing of the policy input/output behavior from the file, without fully loading it into memory first adapter not needed anymore ripping out test observation mode (not used in a long time) fixing warnings bump RLtools to fix the remaining warnings Loading RAPTOR checkpoint from sdcard seems to work on FMU-6C embedding Raptor policy into flash works again also printing checkpoint name when using the embedded policy cleaner handling of the checkpoint name back to reading from file ripping out visual odometry checks cleaner more debug but no success bump rlt bump pre next rebase we can publish the no angvel update because we latch onto it with the scheduled work item anyways this kind of runs on the 6c still bad SIH almost flying saving stale traj setpoint yaw new error. timestamp not the problem anymore bump rlt; SIH works with executor shaping up bumping blob (include tar checkpoint) cleaning up fixing formatting update readme updating gitignore * fixing format and declaring submodules as cmake dependencies * adding uORB message documentation * fixing comment alignment * Adding option to restrict mc_raptor to not listen to the trajectory_setpoint (use the position and yaw at activation time as reference instead) * bump RLtools; relax timing thresholds and adding real world readme * smooth traj tracking performance * Measuring trajectory_setpoint timing (providing stats in raptor_status); reverting accidental .gitignore modification * More ideomatic way of setting the path to the policy checkpoint * Reset trajectory_setpoint on raptor mode activation * Adding internal trajectory generation (feeding trajectory_setpoint over Mavlink is too noisy). Quite agile trajectory tracking, good performance * stable flight * Update msg/versioned/RaptorInput.msg Co-authored-by: Hamish Willee <hamishwillee@gmail.com> * adopting message formatting conventions * sort raptor.px4board * Archiving RegisterExtComponentRequestV1.msg * Add message versioning for VehicleStatus v2 and RegisterExtComponentRequest v2 * fixing formatting * making internal reference configurable via command * RAPTOR docs wip * raptor internal reference documentation * Finishing RAPTOR docs first draft * adding logging instructions * Fixing missing command documentation test error * fixing format * adding motor layout warning * raptor minimal subedit - prettier, images etc * Improve intro * Fix up Neural_Networks version * Mentioning "Adaptive" in the RAPTOR documentation's title * Adding clarifications about the internal reference trajectory generator * Removing "foundation policy" wording * Fixing new-line check * Removing redundant (evident through directory hierarchy) raptor_ from filenames * Unifying Neural Network docs (mc_nn_control and mc_raptor) under the "Neural Network" topic * Fix to standard structure * Making the distinction between mc_nn_control and mc_raptor more clear and fixing the comparison table * Removing trajectory_setpoint forwarding flag from external mode registration request and from the vehicle status * Trivial layout and wording fixes * fixing docs error --------- Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
6.0 KiB
Neural Network Module: System Integration
The neural control module (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). 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. :::
Autostart
A line to autostart the mc_nn_control module has been added in the 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.
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 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 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. :::
- Publish a RegisterExtComponentRequest. This specifies what you want to create, you can read more about this in the Control Interface. In this case we register an arming check and a mode.
- Wait for a RegisterExtComponentReply. This will give feedback on wether the mode registration was successful, and what the mode and arming check id is for the new mode.
- [Optional] With the mode id, publish a VehicleControlMode message on the
config_control_setpointstopic. 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. - [Optional] With the mode id, publish a ConfigOverrides on the
config_overrides_requesttopic. (This is not done in the example module) This will let you defer failsafes or stop it from automatically disarming. - When the mode has been registered a ArmingCheckRequest will be sent, asking if your mode has everything it needs to run. This message must be answered with a ArmingCheckReply 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.
- Listen to the VehicleStatus topic.
If the nav_state equals the assigned
mode_id, then the Neural Controller is activated. - When active the module will run the controller and publish to ActuatorMotors. 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 called NeuralControl.
The message definition is also added in msg/CMakeLists.txt, and to 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 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 message's 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 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:
CONFIG_MODULES_MC_NN_TESTING=y
