ROS2 package for dynamically sabotaging and editing PX4 drone parameters during flight operations via MAVLink.
MAV_INJECT enables real-time modification of PX4 drone flight parameters as part of an autonomous diagnostics and testing system. The system can:
- Connect to PX4 via MAVLink protocol (udp:127.0.0.1:14550)
- Read all current parameter values from a running PX4 instance
- Set parameters with automatic type detection (FLOAT/INT32)
- Disable safety checks to allow extreme parameter modifications
- Sabotage flight control with inverted axes, extreme gains, and disabled stabilization
- Export complete parameter lists as JSON for analysis
- Run automated test sequences that progressively degrade drone performance
The easiest way to get started is using the automated deployment script:
# Normal startup (sabotage tests)
./RunEnv.sh
# Startup + export all parameters to JSON
./RunEnv.sh --list-paramsThis will:
- Sync files from shared folder to VM
- Build the PX4 Parameter Bridge C library
- Launch PX4 SITL with Gazebo simulation
- Launch MAVProxy
- (Optional) Export all parameters to timestamped JSON file
- Launch mav_inject with automated sabotage tests
- Launch drone movement test script
MavInject/
├── mav_inject/
│ ├── __init__.py
│ ├── injection_test.py # Main ROS2 node with automated sabotage tests
│ ├── config_controller.py # Config file controller (legacy)
│ ├── param_lister.py # Parameter export utility
│ ├── px4_param_api.py # Python ctypes wrapper for C API
│ ├── px4_param_bridge.c # C bridge library (direct PX4 access)
│ └── CMakeLists.txt # CMake build config for C bridge
├── build_bridge.sh # Script to build C bridge library
├── RunEnv.sh # Automated environment setup
├── package.xml # ROS2 package manifest
├── setup.py # Python package setup
└── README.md
The primary ROS2 node that connects to PX4 and runs automated sabotage tests.
Features:
- Dual-mode operation: Direct C API (if available) or MAVLink fallback
- Automatic MAVLink heartbeat detection
- Asynchronous message handling with proper request/response matching
- 7 automated sabotage tests that progressively destroy flight stability
Automated Test Sequence:
- Disable Preflight Checks - Disables circuit breakers and arming checks
- Invert Roll Control - Makes roll respond backwards (MC_ROLL_P = -7.0)
- Invert Pitch Control - Makes pitch respond backwards (MC_PITCH_P = -7.0)
- Extreme Oscillation - Massive I gains + zero D (MC_ROLLRATE_I = 5.0)
- Disable Altitude Control - Zero altitude stabilization (MPC_Z_P = 0.0)
- Inverted Yaw + Fast Spin - Backwards yaw + 400°/s max rate
- Verify All Parameters - Read back all sabotaged values
Expected Results:
- Drone will flip immediately when trying to stabilize
- Violent oscillations and shaking
- Uncontrollable spinning
- Altitude drop/loss of height control
- Failed movement tests
Fetches all available parameters from PX4 via MAVLink and exports as JSON.
Usage:
# Via RunEnv.sh (automatic)
./RunEnv.sh --list-params
# Standalone after building
ros2 run mav_inject param_lister --output params.json
# Direct Python
python3 mav_inject/param_lister.py --output params.json
# Custom connection and timeout
ros2 run mav_inject param_lister \
--connection udp:127.0.0.1:14550 \
--timeout 60 \
--output my_params.jsonCommand Line Options:
--connection,-c: MAVLink connection string (default: udp:127.0.0.1:14550)--timeout,-t: Timeout in seconds (default: 30)--output,-o: Output JSON file path (default: stdout)
Output Format:
{
"timestamp": 1700000000.0,
"system_id": 1,
"component_id": 0,
"total_parameters": 1018,
"parameters": {
"MC_ROLL_P": {
"value": 7.0,
"type": "REAL32",
"type_id": 9,
"index": 549
},
"CBRK_USB_CHK": {
"value": 197848,
"type": "INT32",
"type_id": 6,
"index": 123
}
}
}Parameter Types:
UINT8,INT8: 8-bit unsigned/signed integersUINT16,INT16: 16-bit unsigned/signed integersUINT32,INT32: 32-bit unsigned/signed integers (circuit breakers)UINT64,INT64: 64-bit unsigned/signed integersREAL32: 32-bit floating point (most flight parameters)REAL64: 64-bit floating point
JSON Queries with jq:
# Find all circuit breakers
ros2 run mav_inject param_lister | jq '.parameters | to_entries[] | select(.key | startswith("CBRK_"))'
# Find roll-related parameters
ros2 run mav_inject param_lister | jq '.parameters | to_entries[] | select(.key | contains("ROLL"))'
# Count parameters
ros2 run mav_inject param_lister | jq '.total_parameters'Attempts to provide direct C-level access to PX4's parameter functions, bypassing MAVLink.
Status: Currently non-functional because PX4's param_set()/param_get() functions are not exported as shared library symbols. Falls back to MAVLink automatically.
Build:
./build_bridge.sh /path/to/PX4-Autopilot- ROS2 Kilted
- PX4-Autopilot (SITL)
- MAVProxy
- Python 3 with pymavlink
# 1. Clone to ROS2 workspace
cd ~/ros2_ws/src
git clone <repo> MavInject
# 2. Build C bridge (optional, will fall back to MAVLink if fails)
cd MavInject
./build_bridge.sh ~/Documents/PX4-Autopilot
# 3. Build ROS2 package
cd ~/ros2_ws
colcon build --packages-select mav_inject
source install/setup.bashcd ~/Documents/PX4-Autopilot
make px4_sitl gz_x500cd ~/Documents/MAVProxy
mavproxy.py --master=udp:127.0.0.1:14550cd ~/ros2_ws
source install/setup.bash
ros2 run mav_inject injection_test --ros-args -p px4_build_path:=/path/to/PX4-Autopilot/px4_injector/status(std_msgs/String): Status updates and health checks
/px4_injector/command(std_msgs/String): JSON commands for config injection
CBRK_SUPPLY_CHK: 894281 (INT32) - Disable power supply checkCBRK_USB_CHK: 197848 (INT32) - Allow arming with USBCBRK_IO_SAFETY: 22027 (INT32) - Disable IO safety switchCBRK_FLIGHTTERM: 121212 (INT32) - Disable flight terminationCOM_ARM_IMU_ACC: 1000.0 (FLOAT) - Disable accel checkCOM_ARM_IMU_GYR: 1000.0 (FLOAT) - Disable gyro checkCOM_DISARM_PRFLT: -1.0 (FLOAT) - Disable auto-disarm
MC_ROLL_P: -7.0 (INVERTED! Normal: 7.0)MC_PITCH_P: -7.0 (INVERTED! Normal: 7.0)MC_ROLLRATE_P: -0.15 (INVERTED! Normal: 0.15)MC_PITCHRATE_P: -0.15 (INVERTED! Normal: 0.15)MC_YAW_P: -2.8 (INVERTED! Normal: 2.8)MC_YAWRATE_P: -0.2 (INVERTED! Normal: 0.2)
MC_ROLLRATE_I: 5.0 (25x normal! Causes oscillation)MC_PITCHRATE_I: 5.0 (25x normal! Causes oscillation)MC_ROLLRATE_D: 0.0 (No damping! Normal: 0.003)MC_PITCHRATE_D: 0.0 (No damping! Normal: 0.003)MC_YAWRATE_MAX: 400.0 (2x normal! Normal: 200.0)
MPC_XY_P: 0.1 (10x smaller! Normal: 0.95)MPC_Z_P: 0.0 (DISABLED! Normal: 1.0)MPC_XY_VEL_P_ACC: 0.5 (2x smaller! Normal: 1.8)MPC_Z_VEL_P_ACC: 0.0 (DISABLED! Normal: 4.0)MPC_THR_HOVER: 0.3 (Too low! Normal: 0.5)
-
MAVLink Protocol (Primary): Uses
PARAM_SETandPARAM_VALUEmessages- Handles both REAL32 (float) and INT32 parameter types
- Asynchronous message handling with proper request/response matching
- Robust against out-of-order MAVLink responses
-
Direct C API (Fallback): Attempts to load
libpx4_param_bridge.so- Currently non-functional (symbols not available)
- Automatically falls back to MAVLink if loading fails
The system correctly handles different parameter types:
# FLOAT parameters (most common)
mav.mav.param_set_send(
system, component,
param_name.encode('utf-8'),
float_value,
mavutil.mavlink.MAV_PARAM_TYPE_REAL32
)
# INT32 parameters (circuit breakers)
mav.mav.param_set_send(
system, component,
param_name.encode('utf-8'),
float(int_value), # Sent as float with INT32 flag
mavutil.mavlink.MAV_PARAM_TYPE_INT32
)This is normal for some parameters that don't exist or are read-only. The system continues with other parameters.
Run the automated tests - Test 1 disables all preflight checks. Or manually set:
ros2 topic pub /px4_injector/command std_msgs/String \
"data: '{\"action\": \"disable_checks\"}'"Restart PX4 SITL terminal. The Gazebo GUI sometimes crashes in SITL.
Check that:
- MAVLink is connected (check logs for "MAVLink connected!")
- Parameters are being confirmed (look for "SUCCESS:" messages)
- PX4 hasn't rejected the values (check PX4 terminal for errors)
Edit injection_test.py and add to run_automated_tests():
# Test X: Description
self.get_logger().info('--- Test X: Description ---')
self.set_parameters({
'PARAM_NAME': value,
})
time.sleep(0.5)# Read a parameter
ros2 run mav_inject param_lister | jq '.parameters.MC_ROLL_P'
# Or use MAVProxy
param show MC_ROLL_P
param set MC_ROLL_P 7.0- C API bridge doesn't work (PX4 symbols not exported) - using MAVLink instead
- Some circuit breaker parameters don't exist on all PX4 versions
- Extreme parameter values may cause PX4 to crash or reject changes
- Inverted controls are VERY dangerous - drone will crash immediately
- Only use in SITL simulation
- Never use on real hardware
- Inverted control parameters will cause immediate crashes
- Extreme I gains will cause violent oscillations
- Zero altitude control will cause the drone to drop
MIT
MAV_INJECT Team - Cornell MAGPIE Project