Compare commits

..

3 Commits

Author SHA1 Message Date
Jacob Dahl 41aeb9ec70 use tmux, with 3+ vehiles I see sporadic 100ms IMU dropouts 2025-10-14 15:37:54 -08:00
Jacob Dahl 83dc437ece multi vehicle gz sim convenience script 2025-10-14 15:05:34 -08:00
Jacob Dahl a64536802b gz: fix gimbal yaw, add dds publisher (#25754)
* gz: correct gimbal yaw

* uxrce_dds: add publisher /fmu/out/gimbal_device_attitude_status

* chore: use explicit ENU_to_NED rotation

Signed-off-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>

* format

---------

Signed-off-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>
Co-authored-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>
2025-10-14 11:45:43 -08:00
17 changed files with 425 additions and 268 deletions
+174
View File
@@ -0,0 +1,174 @@
# Multi-Vehicle Gazebo Simulation Script
## Overview
`gz_multi_vehicle.sh` is a script to easily launch multiple PX4 gz_x500 drones in Gazebo simulation with configurable positioning. All drone instances run in a tmux grid layout within your current terminal, making it easy to monitor all vehicles simultaneously.
**Platform**: Ubuntu Linux only
## Prerequisites
1. PX4 SITL must be built:
```bash
make px4_sitl
```
2. Gazebo (gz) must be installed (Harmonic, Ionic, or Jetty)
3. **Required**: terminator and tmux:
```bash
sudo apt install terminator tmux
```
## Usage
```bash
./Tools/simulation/gz_multi_vehicle.sh [num_vehicles] [spacing]
```
### Parameters
- `num_vehicles` (optional, default: 2, max: 10): Number of drones to spawn
- `spacing` (optional, default: 0.5): Distance between drones in meters along the Y-axis
### Examples
Launch 3 drones with default 0.5m spacing:
```bash
./Tools/simulation/gz_multi_vehicle.sh 3
```
Launch 5 drones with 1.0m spacing:
```bash
./Tools/simulation/gz_multi_vehicle.sh 5 1.0
```
Launch 2 drones (default configuration):
```bash
./Tools/simulation/gz_multi_vehicle.sh
```
## What the Script Does
1. **Validates** that PX4 SITL is built, terminator and tmux are installed
2. **Prepares** working directories for all vehicle instances
3. **Creates a tmux session** with a grid layout in your current terminal
4. **Launches all vehicles** in separate tmux panes:
- **Instance 0** (first pane):
- Starts Gazebo server and GUI
- Spawns x500_0 at position (0, 0, 0)
- MAV_SYS_ID = 1
- **Instances 1+** (additional panes):
- Connect to running Gazebo instance
- Spawn x500_N at position (0, N×spacing, 0)
- MAV_SYS_ID = N+1
- Wait appropriately for Gazebo to be ready
All vehicles are displayed in a tiled grid layout within the current terminal window, allowing you to see all outputs simultaneously.
## Vehicle Configuration
Each vehicle gets:
- **Unique instance number**: 0, 1, 2, ...
- **Unique MAV_SYS_ID**: instance + 1 (1, 2, 3, ...)
- **Unique model name**: x500_0, x500_1, x500_2, ...
- **Unique position**: Spaced along Y-axis
- **Unique ROS 2 namespace** (if using ROS 2): px4_1, px4_2, px4_3, ...
- **Dedicated tmux pane**: Each instance displays its output in a separate pane in the grid
## Using with QGroundControl
QGroundControl should automatically detect and connect to all vehicles. You can switch between them in the vehicle dropdown menu.
## Using with ROS 2
To use the vehicles with ROS 2:
1. Start the MicroXRCE-DDS Agent (all vehicles connect to the same agent):
```bash
MicroXRCEAgent udp4 -p 8888
```
2. List topics to see all vehicles:
```bash
ros2 topic list
```
You should see topics namespaced by vehicle:
- `/px4_1/fmu/in/...`
- `/px4_1/fmu/out/...`
- `/px4_2/fmu/in/...`
- `/px4_2/fmu/out/...`
- etc.
## Stopping the Simulation
To stop all vehicles:
1. **Exit tmux session**: Press `Ctrl+B` then `D` to detach (vehicles keep running) or `Ctrl+C` in each pane to stop
2. **Kill the tmux session**:
```bash
tmux kill-session -t px4_multi_<timestamp>
```
Or kill all PX4 multi-vehicle sessions:
```bash
tmux list-sessions | grep px4_multi | cut -d: -f1 | xargs -I {} tmux kill-session -t {}
```
3. **Kill all PX4 processes**:
```bash
pkill -x px4
```
## Tmux Navigation
Useful tmux commands while in the session:
- **Navigate panes**: `Ctrl+B` then arrow keys
- **Zoom pane**: `Ctrl+B` then `Z` (toggle fullscreen for current pane)
- **Scroll in pane**: `Ctrl+B` then `[`, then use arrow keys or Page Up/Down (press `q` to exit scroll mode)
- **Detach from session**: `Ctrl+B` then `D`
- **Reattach to session**: `tmux attach-session -t px4_multi_<timestamp>`
## Troubleshooting
### Vehicles not spawning
- Check the tmux pane for the specific vehicle - all output is displayed there
- Ensure Gazebo is installed: `gz sim --versions`
- Make sure the first vehicle (instance 0) has fully started Gazebo before others spawn
- Zoom into the first pane (`Ctrl+B` then `Z`) to see full output
### Gazebo GUI not appearing
- Check the first pane (instance 0) for Gazebo startup messages
- Try setting display: `export DISPLAY=:0`
### Missing terminator or tmux
- Install required tools:
```bash
sudo apt install terminator tmux
```
### Port conflicts
- The script automatically handles MAVLink ports (14540 + instance)
- UXRCE-DDS uses unique keys for namespacing
## Monitoring Output
All vehicles are displayed in a grid layout using tmux panes. Each pane shows the output for one vehicle instance. You can:
- View all vehicles simultaneously in the grid
- Zoom into any pane for detailed viewing (`Ctrl+B` then `Z`)
- Scroll through output history in any pane (`Ctrl+B` then `[`)
- Navigate between panes using arrow keys (`Ctrl+B` then arrow key)
## Architecture Details
The script uses tmux for terminal multiplexing and implements the multi-vehicle pattern described in the PX4 docs:
- **Tmux session**: Creates a single tmux session with multiple panes in a tiled grid layout
- **Instance 0**: Launches Gazebo server (no PX4_GZ_STANDALONE)
- **Instances 1+**: Connect to running Gazebo server (PX4_GZ_STANDALONE=1)
- **Positioning**: Each instance uses PX4_GZ_MODEL_POSE for spawn location
- **Identifiers**: Automatic MAV_SYS_ID and UXRCE_DDS_KEY assignment based on instance number
- **Synchronization**: Sequential startup with delays to ensure Gazebo is ready
## References
- [PX4 Multi-Vehicle Gazebo Docs](https://docs.px4.io/main/en/sim_gazebo_gz/multi_vehicle_simulation.html)
- [PX4 ROS 2 Multi-Vehicle](https://docs.px4.io/main/en/ros2/multi_vehicle.html)
+205
View File
@@ -0,0 +1,205 @@
#!/bin/bash
# Multi-vehicle Gazebo (gz) simulation launcher for PX4
# Spawns multiple gz_x500 drones with configurable spacing
# Each instance runs in its own terminal window
# Usage: ./gz_multi_vehicle.sh [num_vehicles] [spacing]
# num_vehicles: Number of drones to spawn (default: 2, max: 10)
# spacing: Distance between drones in meters (default: 0.5)
set -e
# Configuration
num_vehicles=${1:-2}
spacing=${2:-1}
MAX_VEHICLES=10
# Get script directory and PX4 root
SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"
PX4_DIR="$SCRIPT_DIR/../.."
# Build directory
BUILD_DIR="${PX4_DIR}/build/px4_sitl_default"
# Check for required tools
if ! command -v terminator &> /dev/null; then
echo "ERROR: terminator is required"
echo "Please install terminator:"
echo " sudo apt install terminator"
exit 1
fi
if ! command -v tmux &> /dev/null; then
echo "ERROR: tmux is required for grid layout"
echo "Please install tmux:"
echo " sudo apt install tmux"
exit 1
fi
echo "Using terminator with tmux grid layout"
# Validate inputs
if ! [[ "$num_vehicles" =~ ^[0-9]+$ ]] || [ "$num_vehicles" -lt 1 ]; then
echo "ERROR: Number of vehicles must be a positive integer"
echo "Usage: $0 [num_vehicles] [spacing]"
exit 1
fi
if [ "$num_vehicles" -gt "$MAX_VEHICLES" ]; then
echo "ERROR: Number of vehicles cannot exceed $MAX_VEHICLES"
echo "Usage: $0 [num_vehicles] [spacing]"
exit 1
fi
if ! [[ "$spacing" =~ ^[0-9]+\.?[0-9]*$ ]]; then
echo "ERROR: Spacing must be a positive number"
echo "Usage: $0 [num_vehicles] [spacing]"
exit 1
fi
# Check if PX4 is built
if [ ! -f "${BUILD_DIR}/bin/px4" ]; then
echo "ERROR: PX4 SITL not built. Please run 'make px4_sitl' first"
exit 1
fi
echo "=================================================="
echo "PX4 Multi-Vehicle Gazebo Launcher"
echo "=================================================="
echo "Number of vehicles: $num_vehicles"
echo "Spacing: ${spacing}m"
echo "Model: gz_x500"
echo "PX4 Directory: $PX4_DIR"
echo "=================================================="
echo ""
# Kill any existing PX4 instances (exact match only, won't kill this script)
echo "Cleaning up any existing PX4 instances..."
pkill -x px4 || true
# Kill any existing Gazebo instances (use exact match to avoid killing this script)
echo "Cleaning up any existing Gazebo instances..."
pkill -x gz || true
echo ""
echo "Launching vehicles..."
echo ""
# Prepare all vehicle instances
for i in $(seq 0 $((num_vehicles - 1))); do
# Create working directory for this instance
working_dir="${BUILD_DIR}/instance_${i}"
mkdir -p "$working_dir"
# Create symlink to gz_env.sh if it doesn't exist
if [ ! -f "$working_dir/gz_env.sh" ]; then
ln -sf "${BUILD_DIR}/rootfs/gz_env.sh" "$working_dir/gz_env.sh"
fi
# Calculate Y position (spacing along Y-axis)
y_pos=$(echo "$i * $spacing" | bc -l)
mav_sys_id=$((i + 1))
echo "----------------------------------------"
echo "Preparing Vehicle $i"
echo " Working directory: $working_dir"
echo " Position: (0, $y_pos, 0)"
echo " MAV_SYS_ID: $mav_sys_id"
echo " Model name: x500_${i}"
echo "----------------------------------------"
done
echo ""
# Create tmux session with grid layout
SESSION_NAME="px4_multi_$(date +%s)"
echo "Creating tmux session with $num_vehicles panes in grid layout..."
# Start tmux session with first pane
working_dir_0="${BUILD_DIR}/instance_0"
tmux new-session -d -s "$SESSION_NAME" -c "$working_dir_0"
# Create additional panes (one for each vehicle after the first)
for i in $(seq 1 $((num_vehicles - 1))); do
tmux split-window -t "$SESSION_NAME:0" -c "${BUILD_DIR}/instance_${i}"
tmux select-layout -t "$SESSION_NAME:0" tiled
done
# Send commands to each pane
for i in $(seq 0 $((num_vehicles - 1))); do
working_dir="${BUILD_DIR}/instance_${i}"
y_pos=$(echo "$i * $spacing" | bc -l)
mav_sys_id=$((i + 1))
# Send commands to pane
tmux send-keys -t "$SESSION_NAME:0.$i" "cd '$working_dir'" C-m
tmux send-keys -t "$SESSION_NAME:0.$i" "echo '========================================='" C-m
tmux send-keys -t "$SESSION_NAME:0.$i" "echo 'PX4 Vehicle $i (MAV_SYS_ID=$mav_sys_id)'" C-m
tmux send-keys -t "$SESSION_NAME:0.$i" "echo '========================================='" C-m
if [ $i -eq 0 ]; then
tmux send-keys -t "$SESSION_NAME:0.$i" "echo 'Mode: Primary (launching Gazebo)'" C-m
tmux send-keys -t "$SESSION_NAME:0.$i" "export PX4_SYS_AUTOSTART=4001" C-m
tmux send-keys -t "$SESSION_NAME:0.$i" "export PX4_SIM_MODEL=gz_x500" C-m
tmux send-keys -t "$SESSION_NAME:0.$i" "'$BUILD_DIR/bin/px4' -i $i -d '$BUILD_DIR/etc'" C-m
else
tmux send-keys -t "$SESSION_NAME:0.$i" "echo 'Mode: Secondary (connecting to Gazebo)'" C-m
tmux send-keys -t "$SESSION_NAME:0.$i" "echo 'Position: (0, $y_pos, 0)'" C-m
# For secondary instances, wait for Gazebo to start
if [ $i -eq 1 ]; then
tmux send-keys -t "$SESSION_NAME:0.$i" "echo 'Waiting for Gazebo to start...'" C-m
tmux send-keys -t "$SESSION_NAME:0.$i" "sleep 15" C-m
else
tmux send-keys -t "$SESSION_NAME:0.$i" "sleep $((15 + (i-1) * 2))" C-m
fi
tmux send-keys -t "$SESSION_NAME:0.$i" "export PX4_SYS_AUTOSTART=4001" C-m
tmux send-keys -t "$SESSION_NAME:0.$i" "export PX4_SIM_MODEL=gz_x500" C-m
tmux send-keys -t "$SESSION_NAME:0.$i" "export PX4_GZ_MODEL_POSE='0,$y_pos'" C-m
tmux send-keys -t "$SESSION_NAME:0.$i" "export PX4_GZ_STANDALONE=1" C-m
tmux send-keys -t "$SESSION_NAME:0.$i" "'$BUILD_DIR/bin/px4' -i $i -d '$BUILD_DIR/etc'" C-m
fi
done
echo ""
echo "All vehicles configured in tmux session: $SESSION_NAME"
echo "Attaching to tmux session..."
echo ""
echo "Tmux Commands:"
echo " - Detach from tmux: Ctrl+B then D"
echo " - Kill session: tmux kill-session -t $SESSION_NAME"
echo " - Navigate panes: Ctrl+B then arrow keys"
echo " - Zoom pane: Ctrl+B then Z (toggle)"
echo ""
# Attach to the session
exec tmux attach-session -t "$SESSION_NAME"
echo ""
echo "=================================================="
echo "All vehicles launched successfully!"
echo "=================================================="
echo ""
echo "Vehicle Summary:"
echo "----------------"
for i in $(seq 0 $((num_vehicles - 1))); do
y_pos=$(echo "$i * $spacing" | bc -l)
mav_sys_id=$((i + 1))
echo "Vehicle $i:"
echo " - MAV_SYS_ID: $mav_sys_id"
echo " - Model name: x500_${i}"
echo " - Position: (0, $y_pos, 0)"
echo " - ROS 2 namespace: px4_${mav_sys_id}"
echo " - Terminal: PX4 Vehicle $i (MAV_SYS_ID=$mav_sys_id)"
echo ""
done
echo "Tips:"
echo "-----"
echo "- Each vehicle runs in its own tmux pane in the grid"
echo "- QGroundControl should auto-connect to all vehicles"
echo "- For ROS 2, start MicroXRCEAgent: MicroXRCEAgent udp4 -p 8888"
echo "- Navigate panes: Ctrl+B then arrow keys"
echo "- Zoom pane: Ctrl+B then Z"
echo "- To stop all: Ctrl+C in each pane or pkill -x px4"
echo ""
echo "=================================================="
@@ -54,8 +54,3 @@ CONFIG_STM32_NOEXT_VECTORS=y
CONFIG_STM32_TIM8=y
CONFIG_TASK_NAME_SIZE=0
CONFIG_USEC_PER_TICK=1000
CONFIG_STM32_USART2=y
CONFIG_USART2_BAUD=57600
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_SERIAL_CONSOLE=y
CONFIG_USART2_TXBUFSIZE=1100
-5
View File
@@ -128,8 +128,3 @@
*
*/
#define GPIO_GETNODEINFO_JUMPER (GPIO_BOOT_CONFIG & ~GPIO_EXTI)
/* Debug output option - set to 1 to enable bootloader debug messages */
#ifndef OPT_ENABLE_DEBUG
# define OPT_ENABLE_DEBUG 1
#endif
+3 -4
View File
@@ -83,10 +83,9 @@ This is done using the the parameters named like `UAVCAN_SUB_*` in the parameter
On the ARK CANnode, you may need to configure the following parameters:
| Parameter | Description |
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
| Parameter | Description |
| ----------------------------------------------------------------------------------------------- | ----------------------------- |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
## LED Meanings
+3 -4
View File
@@ -110,10 +110,9 @@ When optical flow is the only source of horizontal position/velocity, then lower
On the ARK Flow, you may need to configure the following parameters:
| Parameter | Description |
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
| Parameter | Description |
| ----------------------------------------------------------------------------------------------- | ----------------------------- |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
## LED Meanings
+3 -4
View File
@@ -105,10 +105,9 @@ Set the following parameters in _QGroundControl_:
You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK Flow MR itself:
| Parameter | Description |
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
| Parameter | Description |
| ----------------------------------------------------------------------------------------------- | ----------------------------- |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
## LED Meanings
+1 -9
View File
@@ -91,17 +91,9 @@ If the sensor is not centred within the vehicle you will also need to define sen
- Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true.
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` if this is that last node on the CAN bus.
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK GPS from the vehicles centre of gravity.
### ARK GPS Configuration
You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK GPS itself:
| Parameter | Description |
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. |
## LED Meanings
You will see green, blue and red LEDs on the ARK GPS when it is being flashed, and a blinking green LED if it is running properly.
+1 -9
View File
@@ -85,15 +85,7 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if
- Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked).
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity.
### ARK RTK GPS Configuration
You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK RTK GPS itself:
| Parameter | Description |
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. |
- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` on the GPS if this it that last node on the CAN bus.
### Setting Up Rover and Fixed Base
-9
View File
@@ -96,10 +96,6 @@ If the DNA is still running and certain devices need to be manually configured,
::: info
The PX4 node ID can be configured using the [UAVCAN_NODE_ID](../advanced_config/parameter_reference.md#UAVCAN_NODE_ID) parameter.
The parameter is set to 1 by default.
Devices running the [PX4 DroneCAN firmware](px4_cannode_fw.md) (such as [ARK CANnode](ark_cannode.md)) can use the
[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter to set a static node ID.
Set it to 0 (default) for dynamic allocation, or to a value between 1-127 to use a specific static node ID.
:::
:::warning
@@ -286,11 +282,6 @@ For example, the screenshot below shows the parameters for a CAN GPS with node i
![QGC Parameter showing selected DroneCAN node](../../assets/can/dronecan/qgc_can_parameters.png)
Common CANNODE parameters that you can configure include:
- [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID): Set a static node ID (1-127) or use 0 for dynamic allocation. See [PX4 DroneCAN Firmware > Static Node ID](px4_cannode_fw.md#static-node-id) for more information.
- [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM): Enable CAN bus termination on the last node in the bus.
## Device Specific Setup
Most DroneCAN nodes require no further setup, unless specifically noted in their device-specific documentation.
-20
View File
@@ -20,26 +20,6 @@ make ark_can-flow_default
This will create an output in **build/ark_can-flow_default** named **XX-X.X.XXXXXXXX.uavcan.bin**. Follow the instructions at [DroneCAN firmware update](index.md#firmware-update) to flash the firmware.
## Configuration
### Static Node ID
By default, DroneCAN devices use [Dynamic Node Allocation (DNA)](index.md#node-id-allocation) to automatically obtain a unique node ID from the flight controller.
However, you can configure a static node ID using the [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter.
To configure a static node ID:
1. Set [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) to a value between 1-127 using [QGroundControl](index.md#qgc-cannode-parameter-configuration)
2. Reboot the device
To return to dynamic allocation, set `CANNODE_NODE_ID` back to 0.
Note that when switching back to dynamic allocation, the flight controller will typically continue to allocate the same node ID that was previously used (this is normal DNA behavior).
:::warning
When using static node IDs, you must ensure that each device on the CAN bus has a unique node ID.
Configuring two devices with the same ID will cause communication conflicts.
:::
## Developer Information
This section has information that is relevant to developers who want to add support for new DroneCAN hardware to the PX4 Autopilot.
+3
View File
@@ -9,6 +9,9 @@ uint16 DEVICE_FLAGS_NEUTRAL = 2
uint16 DEVICE_FLAGS_ROLL_LOCK = 4
uint16 DEVICE_FLAGS_PITCH_LOCK = 8
uint16 DEVICE_FLAGS_YAW_LOCK = 16
uint16 DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32
uint16 DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64
float32[4] q
float32 angular_velocity_x
+22 -140
View File
@@ -59,47 +59,6 @@
#include <drivers/bootloaders/boot_alt_app_shared.h>
#include <drivers/drv_watchdog.h>
#include <lib/crc/crc.h>
#include <stdio.h>
/****************************************************************************
* Bootloader Debug Logging
*
* Bootloader bypasses stdio initialization, so we use arm_lowputc directly
* for debug output. These macros are similar to PX4_INFO/PX4_DEBUG.
*
* Enable by setting OPT_ENABLE_DEBUG=1 in boot_config.h or board config.
****************************************************************************/
extern void arm_lowputc(char ch);
static inline void bl_puts(const char *str)
{
while (*str) { arm_lowputc(*str++); }
}
static inline void bl_putnum(uint32_t val)
{
char buf[12];
snprintf(buf, sizeof(buf), "%lu", val);
bl_puts(buf);
}
#if OPT_ENABLE_DEBUG
# define BL_DEBUG(fmt, ...) \
do { \
bl_puts("[BL] " fmt); \
__VA_ARGS__; \
bl_puts("\r\n"); \
} while (0)
# define BL_DEBUG_NUM(label, val) \
do { \
bl_puts("[BL] " label ": "); \
bl_putnum(val); \
bl_puts("\r\n"); \
} while (0)
#else
# define BL_DEBUG(fmt, ...)
# define BL_DEBUG_NUM(label, val)
#endif
//#define DEBUG_APPLICATION_INPLACE 1 /* Never leave defined */
#define DEBUG_NO_FW_UPDATE 1 /* With DEBUG_APPLICATION_INPLACE
@@ -1152,40 +1111,9 @@ __EXPORT int main(int argc, char *argv[])
*/
common.crc.valid = false;
/*
* Check if Node ID has been previously assigned and skip DNA if so.
* IMPORTANT: Read this BEFORE invalidating!
*/
bootloader_app_shared_t shared_data;
bool has_node_id = false;
if (bootloader_app_shared_read(&shared_data, App) == OK) {
/* We have valid shared_data data from a previous app run */
if (shared_data.node_id > 0 && shared_data.node_id <= 127) {
has_node_id = true;
common.node_id = shared_data.node_id;
BL_DEBUG_NUM("Read persisted node ID", shared_data.node_id);
/* Also restore the bus speed if we have it */
if (shared_data.bus_speed != 0) {
common.bus_speed = shared_data.bus_speed;
BL_DEBUG_NUM("Read persisted bus speed", shared_data.bus_speed);
}
} else {
BL_DEBUG("Shared data has invalid node ID",);
}
} else {
BL_DEBUG("No valid shared data found",);
}
BL_DEBUG_NUM("has_node_id", has_node_id);
/* Now invalidate to prevent deja vu (after we've read the static node ID) */
/* Either way prevent Deja vu by invalidating the struct*/
bootloader_app_shared_invalidate();
/* Set up the Timers */
bl_timer_cb_t p = null_cb;
p.cb = uptime_process;
@@ -1265,78 +1193,34 @@ __EXPORT int main(int argc, char *argv[])
* or the Node allocation runs longer the tBoot
*/
BL_DEBUG("Regular boot - checking for static node ID",);
/* Preferred Node Address */
/* Skip DNA if we already have a node ID from previously */
if (has_node_id) {
BL_DEBUG("Using persisted static node ID - skipping DNA",);
BL_DEBUG_NUM("Static node ID", common.node_id);
common.node_id = OPT_PREFERRED_NODE_ID;
if (CAN_OK != autobaud_and_get_dynamic_node_id(tboot, (can_speed_t *)&bootloader.bus_speed, &common.node_id)) {
/*
* We have a saved node ID.
* Only do autobaud if we don't have the bus speed.
*/
if (common.bus_speed == 0) {
BL_DEBUG("Bus speed unknown - performing autobaud only",);
bootloader.bus_speed = CAN_UNDEFINED;
if (CAN_OK != autobaud_and_get_dynamic_node_id(tboot, (can_speed_t *)&bootloader.bus_speed, &common.node_id)) {
goto boot;
}
common.bus_speed = can_speed2freq(bootloader.bus_speed);
BL_DEBUG_NUM("Autobaud completed - bus speed", common.bus_speed);
} else {
BL_DEBUG("Using both persisted node ID and bus speed",);
BL_DEBUG_NUM("Node ID", common.node_id);
BL_DEBUG_NUM("Bus speed", common.bus_speed);
/* We have both node ID and bus speed from shared data */
bootloader.bus_speed = can_freq2speed(common.bus_speed);
can_init(bootloader.bus_speed, CAN_Mode_Normal);
}
bootloader.uptime = 0;
common.crc.valid = true;
} else {
/* No node ID, do full DNA */
BL_DEBUG("No persisted node ID - performing full DNA",);
/* Preferred Node Address */
common.node_id = OPT_PREFERRED_NODE_ID;
if (CAN_OK != autobaud_and_get_dynamic_node_id(tboot, (can_speed_t *)&bootloader.bus_speed, &common.node_id)) {
/*
* It is OK that node ID is set to the preferred Node ID because
* common.crc.valid is not true yet
*/
BL_DEBUG("DNA failed or timed out",);
goto boot;
}
BL_DEBUG("DNA completed successfully",);
BL_DEBUG_NUM("Allocated node ID", common.node_id);
/* We have autobauded and got a Node ID. So reset uptime
* and save the speed and node_id in both the common and
* and bootloader data sets
* It is OK that node ID is set to the preferred Node ID because
* common.crc.valid is not true yet
*/
bootloader.uptime = 0;
common.bus_speed = can_speed2freq(bootloader.bus_speed);
/*
* Mark CRC to say this is from
* auto baud and Node Allocation
*/
common.crc.valid = true;
goto boot;
}
/* We have autobauded and got a Node ID. So reset uptime
* and save the speed and node_id in both the common and
* and bootloader data sets
*/
bootloader.uptime = 0;
common.bus_speed = can_speed2freq(bootloader.bus_speed);
/*
* Mark CRC to say this is from
* auto baud and Node Allocation
*/
common.crc.valid = true;
/* Auto bauding may have taken a long time, so restart the tboot time*/
if (bootloader.app_valid && !bootloader.wait_for_getnodeinfo) {
@@ -1346,8 +1230,6 @@ __EXPORT int main(int argc, char *argv[])
}
BL_DEBUG_NUM("Configuring UAVCAN with node ID", common.node_id);
/* Now that we have a node Id configure the uavcan library */
g_this_node_id = common.node_id;
-46
View File
@@ -586,30 +586,11 @@ void UavcanNode::Run()
// check for parameter updates
if (_parameter_update_sub.updated()) {
PX4_INFO("params updated");
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);
// update parameters from storage
int32_t cannode_node_id = 0;
param_get(param_find("CANNODE_NODE_ID"), &cannode_node_id);
if (_node.getNodeID().get() != (uint8_t)cannode_node_id) {
if (cannode_node_id > 0 && cannode_node_id <= uavcan::NodeID::Max) {
// Write new static node ID
PX4_INFO("Param changed - writing static node ID %ld to bootloader", cannode_node_id);
bootloader_app_shared_t shared_write = {};
shared_write.node_id = cannode_node_id;
shared_write.bus_speed = 0; // Force autobaud on next boot (distinguishes from FW update request)
bootloader_app_shared_write(&shared_write, App);
} else if (cannode_node_id == 0) {
// User set to 0 to force DNA on next boot
PX4_INFO("CANNODE_NODE_ID set to 0 - invalidating shared memory to force DNA on next boot");
bootloader_app_shared_invalidate();
}
}
}
_node.spinOnce();
@@ -843,33 +824,6 @@ extern "C" int uavcannode_start(int argc, char *argv[])
}
}
// Read the static node ID parameter - this always takes precedence if set
int32_t cannode_node_id = 0;
param_get(param_find("CANNODE_NODE_ID"), &cannode_node_id);
// Check if the static node ID is in range
if (cannode_node_id < 0 || cannode_node_id > uavcan::NodeID::Max) {
PX4_ERR("Invalid static node ID %ld, using dynamic allocation", cannode_node_id);
cannode_node_id = 0;
}
// Always prefer static node ID parameter if set (overrides bootloader's node_id)
if (cannode_node_id > 0 && cannode_node_id <= uavcan::NodeID::Max) {
node_id = cannode_node_id;
PX4_INFO("Using static node ID %ld from parameter", cannode_node_id);
bootloader_app_shared_t shared_write = {};
shared_write.node_id = node_id;
shared_write.bus_speed = 0; // Force autobaud on next boot (distinguishes from FW update request)
PX4_INFO("Writing static node ID %ld to shared memory (bus_speed=0)", (int32_t)shared_write.node_id);
bootloader_app_shared_write(&shared_write, App);
} else {
PX4_INFO("No static node ID set (CANNODE_NODE_ID=%ld)", cannode_node_id);
}
// If no static node ID parameter, use what bootloader provided.
// Shared memory is invalidated above, so bootloader will do DNA on next boot.
if (
#if defined(SUPPORT_ALT_CAN_BOOTLOADER)
board_booted_by_px4() &&
@@ -31,15 +31,6 @@
*
****************************************************************************/
/**
* UAVCAN CAN node ID (0 for dynamic allocation).
*
* @min 0
* @max 127
* @group UAVCAN
*/
PARAM_DEFINE_INT32(CANNODE_NODE_ID, 0);
/**
* UAVCAN CAN bus bitrate.
*
@@ -100,11 +100,15 @@ void GZGimbal::gimbalIMUCallback(const gz::msgs::IMU &IMU_data)
pthread_mutex_lock(&_node_mutex);
static const matrix::Quatf q_FLU_to_FRD = matrix::Quatf(0.0f, 1.0f, 0.0f, 0.0f);
static const matrix::Quatf q_ENU_to_NED = matrix::Quatf(0.0f, cosf(M_PI_4_F), cosf(M_PI_4_F), 0.0f);
// Get the gimbal orientation. Gimbal frame is FLU in Gazebo, reference frame is ENU in Gazebo
const matrix::Quatf q_gimbal_FLU = matrix::Quatf(IMU_data.orientation().w(),
IMU_data.orientation().x(),
IMU_data.orientation().y(),
IMU_data.orientation().z());
_q_gimbal = q_FLU_to_FRD * q_gimbal_FLU * q_FLU_to_FRD.inversed();
_q_gimbal = q_ENU_to_NED * q_gimbal_FLU * q_FLU_to_FRD.inversed();
matrix::Vector3f rate = q_FLU_to_FRD.rotateVector(matrix::Vector3f(IMU_data.angular_velocity().x(),
IMU_data.angular_velocity().y(),
@@ -206,13 +210,11 @@ void GZGimbal::publishDeviceInfo()
void GZGimbal::publishDeviceAttitude()
{
// TODO handle flags
gimbal_device_attitude_status_s gimbal_att{};
gimbal_att.target_system = 0; // Broadcast
gimbal_att.target_component = 0; // Broadcast
gimbal_att.device_flags = 0;
gimbal_att.device_flags = gimbal_device_attitude_status_s::DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME;
_q_gimbal.copyTo(gimbal_att.q);
gimbal_att.angular_velocity_x = _gimbal_rate[0];
gimbal_att.angular_velocity_y = _gimbal_rate[1];
@@ -104,6 +104,10 @@ publications:
type: px4_msgs::msg::Wind
rate_limit: 1.
- topic: /fmu/out/gimbal_device_attitude_status
type: px4_msgs::msg::GimbalDeviceAttitudeStatus
rate_limit: 20.
# Create uORB::Publication
subscriptions:
- topic: /fmu/in/register_ext_component_request