README
Data Tamer Tools
Tools for working with DataTamer data in ROS2, providing Foxglove integration and MCAP data storage capabilities.
Overview
This package provides five main tools:
Foxglove Relay: Real-time visualization of DataTamer data through Foxglove Studio
MCAP Sink: Store DataTamer data in MCAP (MessagePack) format for efficient storage and playback
MCAP Converter: Convert DataTamer-encoded MCAP files to Protobuf-encoded MCAP files for Foxglove compatibility
Rosout Logger: Record ROS log messages (
/rosout) to MCAP files with Foxglove Log schemaLog Rotation Coordinator: Synchronize log directory rotation across multiple MCAP loggers
Tools
1. Foxglove Relay (foxglove_relay)
A ROS2 component that bridges DataTamer data to Foxglove Studio for real-time visualization.
Features:
Automatically discovers DataTamer topics (
/data_tamer/schema,/data_tamer/schemas,/data_tamer/snapshot)Automatically discovers
sensor_msgs/msg/NavSatFixtopics and relays each source as its ownfoxglove.LocationFixchannel (Map track)Automatically discovers
geographic_msgs/msg/GeoPathtopics and relays each source asfoxglove.GeoJSON(Map overlay)Optional MCAP recording of selected Foxglove schemas (
foxglove.LocationFix+foxglove.GeoJSON) for offline playback in FoxgloveSupports both JSON and Protocol Buffers encoding for Foxglove visualization
Converts DataTamer schemas to JSON Schema or Protocol Buffers descriptor format
Creates Foxglove WebSocket server for real-time data streaming
Supports soft eviction of idle channels (closes channels but keeps schemas)
Configurable eviction policies and discovery intervals
Optional ROS log relaying to Foxglove
Prerequisites:
Your DataTamer channels must use
DataTamer::ROS2PublisherSinkto publish data to ROS2 topicsThe relay automatically discovers and subscribes to the standard DataTamer ROS2 topics
Usage:
# Launch as ROS2 component
ros2 run data_tamer_tools foxglove_relay
# Or with custom parameters
ros2 run data_tamer_tools foxglove_relay --ros-args \
-p host:=127.0.0.1 \
-p port:=8765 \
-p use_protobuf:=true \
-p eviction_ttl_sec:=900 \
-p eviction_period_sec:=30 \
-p discovery_sec:=5 \
-p enable_rosout:=true
Parameters:
WebSocket Server Configuration:
host(string, default: “127.0.0.1”): WebSocket server host addressport(int, default: 8765): WebSocket server port number
Data Encoding:
use_protobuf(bool, default: true): Use Protocol Buffers encoding instead of JSONtrue: Data is serialized using Protocol Buffers for better performance and smaller payloadsfalse: Data is serialized as JSON strings for human readability
Channel Management:
eviction_ttl_sec(int, default: 900): Time-to-live for idle channels in secondsChannels that haven’t received data for this duration will be soft-evicted (closed but schema kept)
eviction_period_sec(int, default: 30): Interval in seconds for checking stale channelsHow often the relay checks for channels that should be evicted
discovery_sec(int, default: 5): Interval in seconds for topic discoveryHow often the relay scans for new DataTamer topics to subscribe to
navsat_ttl_sec(int, default: 30): Time-to-live for NavSatFix sources; stale sources are pruned from the relay’s discovered LocationFix tracksgeopath_ttl_sec(int, default: 0): Time-to-live for GeoPath sources (0 disables pruning)navsat_qos(string, default: “sensor”): QoS profile for NavSatFix subscriptions. Acceptssensor(orsensor_data),system_default(ordefault),best_effort, orreliable.location_fix_prefix(string, default: “/locations”): Prefix for relayed per-sourcefoxglove.LocationFixtopicsgeojson_prefix(string, default: “/geojson”): Prefix for relayed per-sourcefoxglove.GeoJSONtopics
Map Topic Mapping:
A discovered
sensor_msgs/msg/NavSatFixtopic like/gps/fixis relayed as a per-sourcefoxglove.LocationFixtopic at/locations/gps/fix(prefix is configurable vialocation_fix_prefix)A discovered
geographic_msgs/msg/GeoPathtopic like/planner/pathis relayed asfoxglove.GeoJSONat/geojson/planner/path(prefix is configurable viageojson_prefix)Each GeoPath is rendered as GeoJSON (FeatureCollection) containing a LineString for the path and Point features for start/goal; colors are deterministic per topic
Relay MCAP Recording (Foxglove schemas only):
enable_mcap(bool, default: false): Recordfoxglove.LocationFix+foxglove.GeoJSONto an MCAP filelogdir(string, default: “.”): Directory for the initial relay MCAP filemcap_filename(string, default: “foxglove_relay.mcap”): Relay MCAP filenamemcap_append_timestamp(bool, default: true): Prefix timestamp likeYYYY-MM-DD_HH-MM-SS_to the relay MCAP filenamemcap_profile(string, default: “protobuf”): MCAP profile string passed to the Foxglove SDK writermcap_truncate(bool, default: false): If true, overwrite an existing relay MCAP file on name collisionmcap_use_chunks(bool, default: true): Enable chunking (batch writes) in the relay MCAP outputmcap_chunk_size(int, default: 0): Chunk size in bytes (0 = SDK default)mcap_compression(string, default: “zstd”): Compression type:none,zstd, orlz4rotate_dir_topic(string, default: “”): Rotation topic override (empty = auto-discoverdata_tamer_tools/msg/LogDirby type)
ROS Log Integration:
enable_rosout(bool, default: true): Enable relaying of ROS logs to Foxglovetrue: ROS logs from/rosouttopic are relayed to Foxglove Log channelfalse: Disable ROS log relaying
rosout_topic(string, default: “/rosout”): ROS topic name for log messages
Foxglove Studio Connection (Live):
Open Foxglove Studio
Connect to
ws://localhost:8765(or your configured host:port)Add a Map panel to visualize:
GPS tracks from
foxglove.LocationFixtopics (default prefix:/locations/...)Paths/overlays from
foxglove.GeoJSONtopics (default prefix:/geojson/...)
Add a Raw Messages panel to inspect the relayed DataTamer channels
Foxglove Studio Connection (Offline):
Enable relay MCAP recording (
enable_mcap:=true) or use the bringup launch file optionsIn Foxglove Studio: File → Open local file → select the relay MCAP file
Add a Map panel (GeoJSON overlays + LocationFix tracks) and any other panels you need
Encoding Notes:
Protocol Buffers mode (
use_protobuf:=true): More efficient, smaller payloads, better performanceJSON mode (
use_protobuf:=false): Human-readable data, easier to debug, larger payloadsBoth modes provide the same data visualization capabilities in Foxglove Studio
2. MCAP Sink
Stores DataTamer data in MCAP (MessagePack) format for efficient storage and playback.
Features:
Multiple compression options (None, LZ4, Zstd)
Configurable chunk sizes
Thread-safe operations
Integration with DataTamer sink system
Log rotation support: When initialized with a ROS node, automatically subscribes to rotation topic
Synchronized rotation: Multiple MCAP sinks can rotate to new directories simultaneously
Basic Usage:
#include <data_tamer_tools/sinks/mcap_sink.hpp>
// Create MCAP sink (standalone)
auto mcap_sink = std::make_shared<data_tamer_tools::McapSink>(
"/path/to/file.mcap",
data_tamer_tools::Format::Protobuf,
data_tamer_tools::McapSink::Compression::Zstd,
1024 // chunk size
);
// Add to DataTamer channel
auto channel = DataTamer::ChannelsRegistry::Global().getChannel("my_channel");
channel->addDataSink(mcap_sink);
Log Rotation Usage:
#include <data_tamer_tools/sinks/mcap_sink.hpp>
// Create MCAP sink with ROS node for rotation support
auto node = std::make_shared<rclcpp::Node>("my_node");
auto mcap_sink = std::make_shared<data_tamer_tools::McapSink>(
node,
"/initial/path/data.mcap",
data_tamer_tools::Format::Protobuf,
data_tamer_tools::McapSink::Compression::Zstd
);
// Add to DataTamer channel
auto channel = DataTamer::ChannelsRegistry::Global().getChannel("my_channel");
channel->addDataSink(mcap_sink);
// The sink now listens to the rotation topic (default: /data_tamer/rotate_dir)
// When a LogDir message is received, it will:
// 1. Close the current MCAP file
// 2. Create the new directory if needed
// 3. Open a new MCAP file at <new_dir>/<base_filename>
// 4. Re-register all channels and continue recording
Parameters:
rotate_topic(string, default: “/data_tamer/rotate_dir”): Topic to subscribe for rotation commands
Compression Options:
Compression::None: No compressionCompression::LZ4: Fast compressionCompression::Zstd: High compression ratio
Format Options:
Format::Json: JSON encoding with JSON schemaFormat::Protobuf: Protocol Buffers encoding (recommended for Foxglove compatibility)
3. MCAP Converter (mcap_converter)
Converts DataTamer-encoded MCAP files to Protobuf-encoded MCAP files for Foxglove Studio compatibility.
Features:
Converts DataTamer’s custom message encoding to standard Protobuf encoding
Preserves all message timestamps and metadata
Uses Zstd compression for efficient output files
Maintains channel and schema information
Enables visualization of DataTamer data in Foxglove Studio
Usage:
# Convert a DataTamer MCAP file to Foxglove-compatible format
ros2 run data_tamer_tools mcap_converter input.mcap output.mcap
# With custom compression and chunk size
ros2 run data_tamer_tools mcap_converter input.mcap output.mcap \
--compression lz4 \
--chunk-size 1048576
Command-line Options:
--compression <type>: Compression type (zstd,lz4, ornone). Default:zstd--chunk-size <size>: Chunk size in bytes (positive integer). Default: writer default
What it does:
Reads DataTamer MCAP files: Parses MCAP files created with DataTamer’s custom encoding
Converts schemas: Transforms DataTamer schemas to Protobuf descriptors
Re-encodes messages: Converts DataTamer snapshot data to Protobuf format
Preserves metadata: Maintains timestamps, channel names, and message sequences
Outputs Foxglove-compatible MCAP: Creates MCAP files that can be opened directly in Foxglove Studio
Use Cases:
Post-processing: Convert recorded DataTamer sessions for analysis in Foxglove
Data sharing: Share DataTamer recordings with team members who use Foxglove
Visualization: Enable rich visualization of DataTamer data using Foxglove’s plotting capabilities
Debugging: Inspect DataTamer data using Foxglove’s message inspection tools
Example Workflow:
# 1. Record data with DataTamer (creates data_tamer_encoded.mcap)
ros2 run your_package your_node
# 2. Convert to Foxglove-compatible format
ros2 run data_tamer_tools mcap_converter data_tamer_encoded.mcap foxglove_compatible.mcap
# 3. Open in Foxglove Studio
# - File -> Open Local File -> Select foxglove_compatible.mcap
# - Add panels to visualize your data
Technical Details:
Input: MCAP files with DataTamer’s custom message encoding (JSON Schema + binary snapshots)
Output: MCAP files with Protobuf encoding (Protocol Buffers descriptors + Protobuf messages)
Compression: Output files use Zstd compression for efficiency
Schema conversion: DataTamer schemas are converted to Protobuf FileDescriptorSets
Message conversion: DataTamer snapshots are re-encoded as Protobuf messages
4. Rosout Logger (rosout_logger)
Records ROS log messages (/rosout) to MCAP files using the Foxglove Log schema for seamless playback in Foxglove Studio.
Features:
Subscribes to ROS
/rosouttopic and records all log messagesEncodes logs using Foxglove Log schema (Protobuf format)
Supports log rotation via
LogDirtopicConfigurable compression and chunk size
Thread-safe MCAP writing
Creates timestamped log files on startup
Synchronized rotation with other MCAP loggers
Usage:
# Launch as ROS2 component with defaults
ros2 run data_tamer_tools rosout_logger
# Or with custom parameters
ros2 run data_tamer_tools rosout_logger --ros-args \
-p rosout_topic:=/rosout \
-p output_base:=rosout \
-p output_dir:=/logs \
-p compression:=zstd \
-p chunk_size:=0 \
-p rotate_dir_topic:=''
Parameters:
rosout_topic(string, default: “/rosout”): ROS topic to subscribe for log messagesoutput_base(string, default: “rosout”): Base filename for MCAP filesoutput_dir(string, default: “.”): Directory for initial MCAP filecompression(string, default: “zstd”): Compression type (none, zstd, or lz4)chunk_size(int, default: 0): Chunk size in bytes (0 = no chunking)append_timestamp(bool, default: true): Append a timestamp to the output filenamerotate_dir_topic(string, default: “”): Rotation topic override (empty = auto-discoverdata_tamer_tools/msg/LogDirby type)
How it works:
On startup, creates a timestamped MCAP file:
<output_dir>/<output_base>_YYYYMMDD_HHMMSS.mcapSubscribes to
/rosoutand records all log messages in Foxglove Log formatListens to the rotation topic (latched/transient_local), auto-discovered by type if
rotate_dir_topicis emptyWhen a
LogDirmessage is received with a new directory:Closes the current MCAP file
Creates the new directory if needed
Opens a new file at
<new_dir>/<output_base>_YYYYMMDD_HHMMSS.mcap(or<new_dir>/<output_base>.mcapifappend_timestampis false)Continues recording with monotonic sequence numbers
Foxglove Integration: The recorded MCAP files can be opened directly in Foxglove Studio and will display logs in the Log panel with proper severity levels, timestamps, and message details.
5. Log Rotation Coordinator (log_rotation_coordinator)
Coordinates synchronized log directory rotation across multiple MCAP loggers (data_tamer_tools::McapSink sinks and Rosout logger).
Features:
Provides a ROS service to trigger rotation
Publishes rotation commands on a latched topic
Ensures all loggers rotate simultaneously to the same directory
Simple service-based API for external control
Usage:
# Launch the coordinator
ros2 run data_tamer_tools log_rotation_coordinator
# Or with custom parameters
ros2 run data_tamer_tools log_rotation_coordinator --ros-args \
-p rotate_topic:=/data_tamer/rotate_dir \
-p service_name:=/data_tamer/loggers/rotate
Parameters:
rotate_topic(string, default: “/data_tamer/rotate_dir”): Topic name for publishing rotation commandsservice_name(string, default: “/data_tamer/loggers/rotate”): Service name for rotation requests
Triggering Rotation:
# Rotate all loggers to a new directory
ros2 service call /data_tamer/loggers/rotate data_tamer_tools/srv/Rotate "{directory: '/logs/session_001'}"
How it works:
The coordinator provides a ROS service that accepts a directory path
When the service is called, it creates the new logdir if it doesn’t xist and publishes a
LogDirmessage on the rotation topicThe topic uses transient_local QoS (latched), so:
All current subscribers receive the message immediately
Late-joining subscribers (loggers started after rotation) also receive the last message
All MCAP sinks and Rosout loggers subscribed to this topic will:
Close their current files
Create the new directory if needed
Open new files in the specified directory
Continue recording seamlessly
Synchronized Logging Architecture:
┌─────────────────────────┐
│ Log Rotation │
│ Coordinator │
│ (Service Provider) │
└───────────┬─────────────┘
│ publishes LogDir (latched)
├──────────────┐──────────────┐
↓ ↓ ↓
/data_tamer/rotate_dir topic topic
↓ ↓ ↓
┌───────┴────┐ ┌────┴──────┐ ┌──────────┐
│ McapSink 1 │ │ McapSink 2│ │ Rosout │
│ (DataTamer)│ │(DataTamer)│ │ Logger │
└────────────┘ └───────────┘ └──────────┘
↓ ↓ ↓
data1.mcap data2.mcap rosout.mcap
(all in the same directory)
Use Cases:
Session-based logging: Organize logs by test session or experiment
Time-based rotation: Rotate to hourly/daily directories
Event-triggered rotation: Switch directories on specific events
Multi-robot systems: Coordinate logging across multiple robots
Launch Files
Bringup Launch File
The package provides a comprehensive launch file (bringup.launch.py) that starts all three components (Foxglove Relay, Rosout Logger, and Log Rotation Coordinator) in a single composable node container for efficient execution.
Quick Start:
# Launch with all default settings
ros2 launch data_tamer_tools bringup.launch.py
# Launch with custom log directory
ros2 launch data_tamer_tools bringup.launch.py logdir:=/tmp/my_logs
# Launch with custom Foxglove port
ros2 launch data_tamer_tools bringup.launch.py relay_port:=9000
# Disable specific components
ros2 launch data_tamer_tools bringup.launch.py relay:=False log_rosout:=False
Architecture:
The launch file creates a multi-threaded composable node container (component_container_mt) that hosts all three components, providing:
Efficient inter-component communication
Shared namespace configuration
Coordinated lifecycle management
Lower resource overhead compared to separate nodes
Launch Arguments:
General Configuration:
ns(string, default: “data_tamer_tools”): Namespace for all nodeslogdir(string, default: “.”): Output directory for log files
Component Enable/Disable:
relay(bool, default: True): Enable/disable Foxglove Relay componentlog_rosout(bool, default: True): Enable/disable Rosout Logger componentrotation_coordinator(bool, default: True): Enable/disable Log Rotation Coordinator component
Foxglove Relay Parameters:
relay_host(string, default: “127.0.0.1”): WebSocket server host addressrelay_port(int, default: 8765): WebSocket server port (0-65535)relay_eviction_ttl_sec(int, default: 900): Time-to-live for stale publishers in seconds (15 minutes)relay_eviction_period_sec(int, default: 30): Interval for checking stale publishersrelay_discover_sec(int, default: 5): Period for rediscovering DataTamer snapshot topicsrelay_enable_rosout(bool, default: true): Enable relaying /rosout to Foxgloverelay_use_protobuf(bool, default: true): Use Protobuf encoding instead of JSONrelay_enable_mcap(bool, default: false): Recordfoxglove.LocationFix+foxglove.GeoJSONto an MCAP file from the relayrelay_mcap_filename(string, default: “foxglove_relay.mcap”): Relay MCAP filename (written underlogdir)relay_mcap_append_timestamp(bool, default: true): Prefix timestamp likeYYYY-MM-DD_HH-MM-SS_to the relay MCAP filenamerelay_mcap_truncate(bool, default: false): Overwrite relay MCAP file on collisionrelay_mcap_use_chunks(bool, default: true): Enable chunking in relay MCAP outputrelay_mcap_chunk_size(int, default: 0): Chunk size in bytes (0 = SDK default)relay_mcap_compression(string, default: “zstd”): Compression type:none,zstd, orlz4relay_rotate_dir_topic(string, default: “”): Rotation topic override for relay (empty = auto-discoverdata_tamer_tools/msg/LogDir)
Rosout Logger Parameters:
logger_output_base(string, default: “rosout”): Base filename for MCAP output fileslogger_compression(string, default: “zstd”): Compression type (none, zstd, or lz4)logger_chunk_size(int, default: 0): MCAP chunk size in bytes (0 = no chunking)logger_rotate_dir_topic(string, default: “”): Rotation topic override for rosout logger (empty = auto-discoverdata_tamer_tools/msg/LogDir)
Log Rotation Coordinator Parameters:
coordinator_rotate_topic(string, default: “/data_tamer/rotate_dir”): Topic to publish rotation commandscoordinator_service_name(string, default: “/data_tamer/loggers/rotate”): Service name for rotation requests
Shared Parameters:
rosout_topic(string, default: “/rosout”): ROS topic to subscribe for logs (used by both Foxglove Relay and Rosout Logger)
Common Usage Patterns:
1. Production Deployment with Custom Settings:
ros2 launch data_tamer_tools bringup.launch.py \
ns:=robot_logger \
logdir:=/data/robot_logs \
relay_host:=0.0.0.0 \
relay_port:=8765 \
logger_compression:=lz4 \
relay_use_protobuf:=true
2. Development/Debugging (JSON mode, disable logger):
ros2 launch data_tamer_tools bringup.launch.py \
relay_use_protobuf:=false \
log_rosout:=False \
relay_discover_sec:=2
3. Logging Only (no live visualization):
ros2 launch data_tamer_tools bringup.launch.py \
relay:=False \
logdir:=/logs/experiment_001
4. Remote Foxglove Access:
ros2 launch data_tamer_tools bringup.launch.py \
relay_host:=0.0.0.0 \
relay_port:=8765
# Now accessible from any machine: ws://<robot_ip>:8765
5. High-Frequency Logging (optimized settings):
ros2 launch data_tamer_tools bringup.launch.py \
logger_compression:=lz4 \
logger_chunk_size:=1048576 \
relay_discover_sec:=10 \
relay_eviction_period_sec:=60
Typical Workflow with Launch File:
# 1. Start the complete logging system
ros2 launch data_tamer_tools bringup.launch.py logdir:=/logs/initial
# 2. Connect Foxglove Studio to ws://localhost:8765
# 3. Run your application with DataTamer integration
ros2 run your_package your_node
# 4. Trigger log rotation for organized sessions
ros2 service call /data_tamer/loggers/rotate data_tamer_tools/srv/Rotate \
"{directory: '/logs/test_run_001'}"
# 5. All logs now go to /logs/test_run_001/:
# - rosout.mcap (ROS logs)
# - <your_datatamer_files>.mcap (DataTamer data)
Integration with Your Launch Files:
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.substitutions import FindPackageShare
from launch.substitutions import PathJoinSubstitution
def generate_launch_description():
return LaunchDescription([
# Include data_tamer_tools bringup
IncludeLaunchDescription(
PythonLaunchDescriptionSource([
PathJoinSubstitution([
FindPackageShare('data_tamer_tools'),
'launch',
'bringup.launch.py'
])
]),
launch_arguments={
'ns': 'my_robot/logging',
'logdir': '/data/logs',
'relay_port': '9000',
'logger_compression': 'lz4',
}.items()
),
# Your other nodes...
])
Benefits of Using the Launch File:
Single command: Launch all logging infrastructure at once
Coordinated configuration: Shared parameters ensure consistency
Resource efficiency: Composable nodes reduce overhead
Easy customization: Override any parameter without modifying code
Production ready: Sensible defaults for most use cases
Modular: Disable components you don’t need
Examples
Example: Basic MCAP Recording
// See examples/json_mcap_sink.cpp
#include <data_tamer_tools/sinks/mcap_sink.hpp>
auto mcap_sink = std::make_shared<data_tamer_tools::McapSink>(
"/tmp/example.mcap",
data_tamer_tools::Format::Protobuf,
data_tamer_tools::McapSink::Compression::None,
1024
);
auto channel = DataTamer::ChannelsRegistry::Global().getChannel("sensor_data");
channel->addDataSink(mcap_sink);
// Register and log data
double temperature = 22.5;
channel->registerValue("temperature", &temperature);
channel->takeSnapshot();
Example: Synchronized Log Rotation System
// In your DataTamer-enabled node
#include <data_tamer_tools/sinks/mcap_sink.hpp>
#include <rclcpp/rclcpp.hpp>
class MyRobotNode : public rclcpp::Node {
public:
MyRobotNode() : Node("my_robot") {
// Create MCAP sink with rotation support
auto mcap_sink = std::make_shared<data_tamer_tools::McapSink>(
shared_from_this(), // Pass the node for rotation
"/initial/logs/robot_data.mcap",
data_tamer_tools::Format::Protobuf,
data_tamer_tools::McapSink::Compression::Zstd
);
// Set up DataTamer channel
auto channel = DataTamer::ChannelsRegistry::Global().getChannel("robot_state");
channel->addDataSink(mcap_sink);
// Register values
channel->registerValue("position_x", &position_x_);
channel->registerValue("velocity", &velocity_);
// Timer to take snapshots
timer_ = create_wall_timer(
std::chrono::milliseconds(100),
[channel]() { channel->takeSnapshot(); }
);
}
private:
double position_x_{0.0};
double velocity_{0.0};
rclcpp::TimerBase::SharedPtr timer_;
};
Complete System Launch:
# Terminal 1: Launch the rotation coordinator
ros2 run data_tamer_tools log_rotation_coordinator
# Terminal 2: Launch rosout logger
ros2 run data_tamer_tools rosout_logger --ros-args -p output_dir:=/logs/initial
# Terminal 3: Launch your robot node with DataTamer
ros2 run my_package my_robot_node
# Terminal 4: Trigger rotation to organize logs by session
ros2 service call /data_tamer/loggers/rotate data_tamer_tools/srv/Rotate "{directory: '/logs/test_session_001'}"
# Now all loggers (DataTamer MCAP sinks + Rosout logger) write to /logs/test_session_001/
# - /logs/test_session_001/robot_data.mcap
# - /logs/test_session_001/rosout.mcap
# Rotate again for a new session
ros2 service call /data_tamer/loggers/rotate data_tamer_tools/srv/Rotate "{directory: '/logs/test_session_002'}"
Building
Install dependencies:
rosdep install --from-paths src --ignore-src -r -y
Build with colcon:
cd /path/to/your/workspace
colcon build --packages-select data_tamer_tools
License
MIT License - see LICENSE file for details.
Support
If you find this project useful, consider buying me a coffee! ☕