ROS2 Jazzy driver for QMC5883L 3-axis digital compass / magnetometer over I2C.
The QMC5883L is a popular drop-in replacement for the HMC5883L, with a different register set and I2C address (0x0D). It provides ±2G or ±8G full scale range with configurable output data rate and over-sampling ratio.
- Publishes
sensor_msgs/MagneticFieldonmag/data fake_modefor testing without hardware (random Gaussian data)- Hard-iron bias calibration via service call
- Configurable gain (±2G / ±8G), ODR (10–200 Hz), OSR (64–512)
- Runtime
publish_ratechange viaros2 param set
- ROS 2 Jazzy
- Python 3
smbus2(pip install smbus2) — only needed for real hardware
cd ~/ros2_ws
colcon build --packages-select qmc5883l_compass --symlink-install
source install/setup.bashros2 launch qmc5883l_compass qmc5883l_launch.pyros2 run qmc5883l_compass qmc5883l_node.py --ros-args -p fake_mode:=trueros2 launch qmc5883l_compass qmc5883l_launch.py params_file:=my_params.yamlqmc5883l_compass_node:
ros__parameters:
fake_mode: false
i2c_bus: 1
device_address: 0x0D
full_scale_range: "8G"
output_data_rate: "200Hz"ros2 topic echo /mag/data| Parameter | Type | Default | Description |
|---|---|---|---|
fake_mode |
bool | true |
Use fake driver (no hardware) |
i2c_bus |
int | 1 |
I2C bus number |
device_address |
int | 0x0D |
I2C address |
publish_rate |
double | 10.0 |
Publishing rate (Hz) |
frame_id |
string | mag_link |
TF frame ID |
output_data_rate |
string | 100Hz |
ODR: 10Hz, 50Hz, 100Hz, 200Hz |
full_scale_range |
string | 2G |
Range: 2G (±2 Gauss), 8G (±8 Gauss) |
over_sampling_ratio |
string | 512 |
OSR: 512, 256, 128, 64 |
magnetic_field_covariance |
double | 0.0 |
Diagonal covariance (T²) |
| Service | Type | Description |
|---|---|---|
mag/calibrate |
std_srvs/srv/Trigger |
Collect samples for 2s, compute hard-iron bias |
mag/reset |
std_srvs/srv/Trigger |
Clear bias, reinitialise sensor |
qmc5883l_compass/
├── CMakeLists.txt
├── CONTRIBUTING.md
├── LICENSE
├── README.md
├── .gitignore
├── package.xml
├── config/
│ └── qmc5883l_params.yaml
├── launch/
│ └── qmc5883l_launch.py
├── nodes/
│ └── qmc5883l_node.py
├── qmc5883l_compass/
│ ├── __init__.py
│ └── qmc5883l_driver.py
└── test/
└── test_qmc5883l_node.py
Tested on Ubuntu 24.04 (WSL2) with fake_mode: true.
| Test Category | Test | Result |
|---|---|---|
| Topics | mag/data publishes sensor_msgs/MagneticField |
PASS |
| Services | mag/calibrate returns success=True |
PASS |
| Services | mag/reset returns success=True |
PASS |
| Parameters | publish_rate runtime change |
PASS |
| Shutdown | Clean exit | PASS |
| Linting | pep257, flake8, copyright, xmllint | PASS |
MIT