NatNet ROS 2 Wrapper¶
OptiTrack NatNet ROS 2 wrapper for motion capture integration in AirStack (optional). Receives rigid body pose data from an external Motive PC via NatNet UDP protocol and publishes into the AirStack perception layer.
Note: This module is only required if you intend to use OptiTrack Motive motion capture systems. If you do not plan to use OptiTrack, you can skip the NatNet SDK setup with airstack setup --no-natnet.
OptiTrack room calibration¶
If rigid bodies are jumping around or not tracking well, consider re-calibrating the capture volume in Motive. See the OptiTrack Motive calibration guide.
Overview¶
This module provides a bridge between OptiTrack Motive motion capture systems and the AirStack autonomy stack. It:
- Receives NatNet UDP packets from an external Motive PC (configurable IP/port)
- Decodes motion capture frames containing rigid body positions and orientations
- Publishes pose data to the AirStack perception layer in standard ROS 2 formats
- Supports multi-robot via ROBOT_NAME namespacing
- Optionally bridges to MAVROS for PX4 external pose feedback
- Respects OptiTrack licensing by keeping the NatNet SDK external (host-side download with explicit consent)
Architecture¶
Motive (External PC)
↓ NatNet UDP (port 1511)
↓
NatNet ROS 2 Node
├→ /robot_1/perception/optitrack/{body_name} (PoseStamped, optional)
├→ /robot_1/perception/optitrack/{body_name}/pose_cov (PoseWithCovarianceStamped, always)
└→ (Optional, publish_to_mavros: true)
vision_pose_converter_node
├→ /robot_1/mavros/vision_pose/pose
└→ /robot_1/mavros/vision_pose/pose_cov
Interfaces¶
Inputs¶
- Network: NatNet UDP stream from Motive PC (external network)
- Configuration:
natnet_config.yamlwith server IP, ports,body_name, and covariance
Outputs¶
For each tracked rigid body {body_name} from Motive:
Direct OptiTrack pose (optional)¶
- Topic:
/{ROBOT_NAME}/perception/optitrack/{body_name} - Type:
geometry_msgs/PoseStamped - Description: Position and orientation only (no covariance)
- Enabled by:
publish_direct_optitrack: truein config (default:true)
Pose with covariance (always)¶
- Topic:
/{ROBOT_NAME}/perception/optitrack/{body_name}/pose_cov - Type:
geometry_msgs/PoseWithCovarianceStamped - Description: Same pose as above plus a 6×6 covariance matrix (
position_covarianceandorientation_covariancefrom config). Published whenever the rigid body is tracked — independent ofpublish_direct_optitrackandpublish_to_mavros.
MAVROS vision pose bridge (optional)¶
When publish_to_mavros: true, vision_pose_converter_node subscribes to pose_cov and republishes for PX4:
- Topic:
/{ROBOT_NAME}/mavros/vision_pose/pose—geometry_msgs/PoseStamped(pose extracted from the covariance message) - Topic:
/{ROBOT_NAME}/mavros/vision_pose/pose_cov—geometry_msgs/PoseWithCovarianceStamped(full message, quaternion optionally canonicalized) - Enabled by:
publish_to_mavros: truein config
Configuration¶
Edit config/natnet_config.yaml:
/**:
ros__parameters:
server_ip: "192.168.1.100" # IP of the Motive PC
client_ip: "0.0.0.0"
command_port: 1510
data_port: 1511
connection_type: "unicast" # or "multicast"
body_name: "Drone" # rigid body name in Motive (case-sensitive)
body_id: -1 # -1 = publish all bodies in the frame
publish_direct_optitrack: true # PoseStamped on …/optitrack/{body_name}
publish_to_mavros: false # include vision_pose_converter → MAVROS
frame_id: "world"
position_covariance: [0.1, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.1]
orientation_covariance: [0.01, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.01]
Launch¶
Basic launch¶
Parameters come from config/natnet_config.yaml (network, body, covariance). Optional overrides:
ros2 launch natnet_ros2 natnet_ros2.launch.py \
config_file:=/path/to/custom_natnet.yaml \
vision_pose_config_file:=/path/to/custom_vision_pose.yaml \
use_sim_time:=true
MAVROS bridge¶
Set publish_to_mavros: true in natnet_config.yaml. The launch file reads publish_to_mavros and body_name from that YAML to decide whether to include vision_pose_converter.launch.xml.
From perception bringup¶
With LAUNCH_NATNET=true in .env, perception.launch.xml includes natnet_ros2.launch.py.
Dependencies¶
Runtime¶
rclpy— ROS 2 Python clientgeometry_msgs— Standard pose message typestf_transformations— Quaternion and rotation utilitiesmavros_msgs— Optional, for MAVROS bridge
Required¶
- OptiTrack NatNet SDK (Linux SDK) — REQUIRED, downloaded via
airstack setup
Installation¶
To install the NatNet SDK and accept the license:
The SDK will be installed intorobot/ros_ws/src/perception/natnet_ros2/lib/ and robot/ros_ws/src/perception/natnet_ros2/include/natnet/ after accepting the OptiTrack License Agreement.
Implementation Details¶
Protocol Support¶
- NatNet Version: 4.4+ (SDK handles protocol negotiation)
- Packet Type: Frame of Data with rigid bodies and markers
- Transport: UDP (configurable port, default 1511)
- SDK: OptiTrack NatNet SDK handles all protocol parsing
Multi-Robot Support¶
Each container instance gets its own ROBOT_NAME and ROS_DOMAIN_ID:
- Topics: /{ROBOT_NAME}/perception/optitrack/{body_name} and /{ROBOT_NAME}/perception/optitrack/{body_name}/pose_cov
- Supported via launch file argument forwarding
Error Handling¶
- Invalid/malformed packets are skipped with debug logging
- Lost connectivity logs warnings; gracefully recovers when stream resumes
- Covariance in config allows tuning uncertainty per deployment
Testing¶
With Real Motive¶
- Ensure Motive PC and robot are on same network
- Configure server IP in
natnet_config.yaml - Launch the node:
- Verify topics:
Without Real Hardware (Mock)¶
TODO: Implement Motive simulator in Isaac Sim to generate fake NatNet packets
Known Limitations¶
- When
body_id: -1, all rigid bodies in the Motive frame get publishers; filter by subscribing to the{body_name}you care about - MAVROS bridge applies frame_id override and quaternion canonicalization; full PX4 frame alignment may still need tuning per airframe
- No support for skeleton tracking or labeled markers yet (future enhancement)
References¶
Troubleshooting¶
No data being received¶
- Check Motive PC IP address in config
- Verify UDP port is not blocked by firewall
- Use
ros2 topic hzto check if data is arriving
Topics not published¶
- Check
ros2 node list— should seenatnet_ros2_node - Check
ros2 topic list | grep optitrack— should see published topics - Look at logs:
ros2 node info natnet_ros2_node
Low frame rate or dropped frames¶
- Reduce other network traffic
- Check NatNet streaming rate in Motive (default 120 Hz)
- Monitor CPU usage:
docker stats
License¶
Note on NatNet SDK Licensing: The OptiTrack NatNet SDK is proprietary software governed by the OptiTrack Software License Agreement. Users download and install the SDK locally under their own license compliance. AirStack does not redistribute the SDK and remains fully open-source.