ROS2 Jazzy driver for LIS3MDL 3-axis digital magnetometer over I2C (STMicroelectronics).
The LIS3MDL features ±4/8/12/16 gauss full scale range, configurable output data rate up to 80 Hz, and four performance modes (low-power to ultra-high). It includes a temperature sensor and block data update (BDU) for consistent readings.
- Publishes
sensor_msgs/MagneticFieldonmag/data fake_modefor testing without hardware (random Gaussian data)- Hard-iron bias calibration via service call
- Configurable range (±4/8/12/16G), ODR (0.625–80 Hz), performance mode
- WHO_AM_I chip ID verification (0x3D)
- 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 lis3mdl_compass --symlink-install
source install/setup.bashros2 launch lis3mdl_compass lis3mdl_launch.pyros2 run lis3mdl_compass lis3mdl_node.py --ros-args -p fake_mode:=trueros2 launch lis3mdl_compass lis3mdl_launch.py params_file:=my_params.yamllis3mdl_compass_node:
ros__parameters:
fake_mode: false
i2c_bus: 1
device_address: 0x1C
full_scale_range: "8G"
output_data_rate: "80Hz"
performance_mode: "ultra-high"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 | 0x1C |
I2C address (0x1C or 0x1E) |
publish_rate |
double | 10.0 |
Publishing rate (Hz) |
frame_id |
string | mag_link |
TF frame ID |
output_data_rate |
string | 10Hz |
ODR: 0.625Hz–80Hz |
full_scale_range |
string | 4G |
Range: 4G, 8G, 12G, 16G |
performance_mode |
string | ultra-high |
low, medium, high, ultra-high |
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 |
lis3mdl_compass/
├── CMakeLists.txt
├── CONTRIBUTING.md
├── LICENSE
├── README.md
├── .gitignore
├── package.xml
├── config/
│ └── lis3mdl_params.yaml
├── launch/
│ └── lis3mdl_launch.py
├── nodes/
│ └── lis3mdl_node.py
├── lis3mdl_compass/
│ ├── __init__.py
│ └── lis3mdl_driver.py
└── test/
└── test_lis3mdl_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