Hardware Familiarization
Hardware Familiarization
Understanding your Beetlebot's architecture and components
Tutorial Overview
🎯 Learning Objectives
By the end of this tutorial, you will:
✅ Understand Beetlebot's hardware architecture
✅ Know what the Lyra controller does vs. Raspberry Pi
✅ Identify all major components and their functions
✅ Understand the sensor suite and capabilities
✅ Navigate the ROS2 software architecture
✅ Use ROS2 command-line tools to explore your robot
✅ Understand data flow from sensors to actuators
⏱️ Time Required
Reading: 20 minutes
Hands-on exercises: 30 minutes
Total: ~50 minutes
📚 Prerequisites
✅ Completed Getting Started (robot powered on and responding)
✅ Robot connected to controller (can drive with joystick)
⚠️ System Setup NOT required yet! (WiFi, SSH can wait)
⚠️ This tutorial uses ONLY the joystick - no laptop needed
🛠️ What You'll Need
✅ Beetlebot robot (powered and ready)
✅ Wireless controller (connected)
✅ Clear space to observe robot
⏸️ Laptop (optional for this tutorial)
Part 1: Physical Hardware Tour
Component Overview
Let's identify every major component on your robot.
[PLACEHOLDER: Top-down labeled diagram of Beetlebot showing all components]
🔝 Top Plate Components
Walk around your robot and locate:
1. RPLidar C1 (Front Center)
[PLACEHOLDER: Close-up photo of LiDAR]
What it is: 360° laser range finder What it does: Scans environment, detects obstacles, builds maps Specifications:
Range: 12 meters maximum, 8-10m practical indoors
Scan rate: 10 Hz (10 complete rotations per second)
Resolution: ~0.5° angular resolution
Height: 20.6cm from ground
Key features:
Spinning motor visible (rotates continuously when active)
Transparent dome protects laser assembly
Connected via USB to Raspberry Pi
What you'll use it for:
SLAM mapping (Tutorial 8)
Obstacle detection during navigation
Localization (knowing where you are)
Path planning around obstacles
2. Metal Top Plate
What it is: 2mm metal platform What it does: Mounting surface for sensors and accessories Features:
Rear-hinged articulated plate with a back-mounted rod acting as a pivot
Allows the front of the plate to rotate upward and lock into a vertical or angled position
Multiple mounting holes for accessories
Protects internal components
What you can add:
Additional sensors (GPS, ultrasonic, etc. on optional mounting plate upgrade)
Compute modules (Jetson, cameras)
Your custom hardware
3. Depth Camera Mount (Optional)
[PLACEHOLDER: Photo of rear camera mount bracket]
Location: Rear of top plate What it is: Metal U-bracket for mounting depth cameras Compatible with: Intel RealSense, Orbbec Astra, etc. (not included) Features:
Cable routing hole through top plate
Sturdy metal construction
Status: Empty (mount included, camera optional upgrade)
🔷 Front Components
4. Raspberry Pi Camera V1.3
[PLACEHOLDER: Close-up of camera on front panel]
What it is: 5MP camera module What it does: Visual perception, image processing Specifications:
Resolution: 5MP (2592×1944 max), typically use 1080p/720p
Sensor: OmniVision OV5647
Connection: CSI ribbon cable to Pi
Height: 8.8cm from ground
Field of view: ~54° horizontal
Mounting:
Fixed forward-facing (horizontal, no tilt)
Behind front metal protective plate
Cable routed internally
What you'll use it for:
Object detection
Line following (advanced projects)
Visual servoing (follow objects)
Environment recognition
⚙️ Back Panel Components
[PLACEHOLDER: Back panel photo with numbered labels]
Walk to the back of your robot and locate:
5. RJ45 Ethernet Port
What it is: Direct Ethernet connection to Raspberry Pi What it does: High-speed wired network (alternative to WiFi) Speed: Gigabit (1000 Mbps) Usage:
Backup if WiFi fails
Lower latency for real-time control
Large data transfers (rosbag recordings)
Development in crowded WiFi environments
Note: Not configured by default - requires setup
6. Power Switch
What it is: Main power ON/OFF button Appearance: Flat button with red LED ring Function: Controls MOSFET that gates battery power
LED Indicator:
Red glowing: Robot powered ON
Off: Robot powered OFF
How it works:
Press switch → triggers low-current signal
MOSFET opens → allows high-current battery power to flow
Power reaches Pi, STM32, motors
Why MOSFET? Switch only handles 2A - battery can supply 50A+. MOSFET handles high current safely.
7. Reset Button
What it is: Tactile button (raised knob, unlabeled) What it does: Reboots Raspberry Pi (and indirectly, STM32)
When to use:
System frozen/unresponsive
After software changes
Network configuration issues
How it works:
Triggers GPIO on Raspberry Pi
Pi initiates graceful shutdown → reboot
STM32 powered via Pi USB → also reboots
Note: NOT an emergency stop! Use power switch for that.
8. Charging Port
What it is: 2.1mm center-positive power jack Input: 12V 2A from included smart charger Function: Charges 3S Li-Ion battery pack
Charging:
Can charge while powered ON or OFF
Smart charger prevents overcharging
LED on charger: Red = charging, Green = full
9. OLED Display (Optional Feature)
[PLACEHOLDER: Photo showing OLED location OR empty mounting area]
Size: 0.91" (wide aspect ratio) Type: I2C OLED (if present) Display info:
Battery voltage
IP address
System status
Current operation mode
Note: May not be present on all units. All information also available via ROS2 topics.
🔄 Side Components
10. USB Port (RF Dongle)
[PLACEHOLDER: Side panel photo showing USB slot]
Location: Right side panel Function: Houses RF dongle for wireless controller Features:
Dongle is removable (can use on laptop for Gazebo)
Direct USB connection to Raspberry Pi
LED indicators visible on dongle
LED Meanings:
Green: Power (always on when robot powered)
Red ON: Raspberry Pi still booting
Red OFF: Pi booted and ready
11. USB/HDMI Placeholder (Optional Access)
Location: Left side panel Function: Access point for additional connectors Status: Hole in chassis, no connectors populated
Potential uses:
External HDMI for monitor
Additional USB ports
Debug interfaces
🚗 Wheels & Motors
12. Wheels (4×)
[PLACEHOLDER: Close-up of wheel showing tread pattern]
Specifications:
Diameter: 130mm
Width: ~40mm
Material: Rubber with aggressive tread
Color: Blue hubs, black tread
Type: All-terrain (indoor/outdoor)
Features:
Deep tread for traction
Suitable for carpet, tile, concrete, pavement
Metal wheel hubs (durable)
Configuration:
Front left (FL)
Front right (FR)
Back left (BL)
Back right (BR)
All wheels independently driven (4WD).
13. Motors (4×)
Hidden inside chassis - you can't see them, but here's what's there:
Model: JGB37-3530 Type: DC metal gear motors Rated voltage: 12V DC Internal gearing: 1:90 (motor to output shaft) Output gearing: 1:1 (shaft directly drives wheel) Max RPM: 178 RPM (limited to 150 RPM in software for safety)
Why metal gears?
Durability - won't strip under load
Continuous operation rated
Consistent torque delivery
14. Encoders (4×)
Also hidden - one per motor:
Type: Quadrature incremental encoders Resolution: 450 CPR (counts per revolution) Mode: X4 decoding = 1800 ticks per wheel revolution Function: Measure wheel rotation for odometry
How it works:
Magnetic disk on motor shaft
Hall effect sensors detect rotation
A/B phase signals → direction + speed
STM32 reads encoder ticks → calculates wheel RPM
Why so precise?
1800 ticks/rev = 0.2° resolution
Essential for accurate odometry
Enables closed-loop PID speed control
Hardware Timer-Based Encoders
Critical distinction: Beetlebot uses hardware timer-based encoder counting, not software interrupts.
What this means:
Hardware Timers (STM32 TIM1, TIM2, TIM4, TIM8):
Dedicated hardware peripherals count encoder pulses
Zero CPU overhead - happens in silicon, not software
Counts continuously at full 168 MHz speed (MCU clock)
Cannot miss pulses even under heavy CPU load
32-bit hardware counters with overflow handling
vs. Software Interrupts (common in Arduino, ESP32):
Each encoder pulse triggers interrupt
CPU must stop current task and handle pulse
Can miss pulses if interrupts disabled or CPU busy
Significant CPU overhead at high speeds
Typically 16-bit counters (limited range)
Why hardware encoders matter:
✅ Accuracy: Never misses a pulse, even at max 150 RPM ✅ Reliability: Works perfectly even when motor control loop is running ✅ CPU efficiency: Zero interrupt overhead = more CPU for control algorithms ✅ High resolution: 1800 ticks/rev with no performance penalty ✅ Overflow protection: 32-bit counters + firmware overflow detection
Technical implementation:
TIM1 (Channel A/B): Motor 1 encoder (PA8, PA9)
TIM2 (Channel A/B): Motor 2 encoder (PA0, PA1)
TIM4 (Channel A/B): Motor 3 encoder (PB6, PB7)
TIM8 (Channel A/B): Motor 4 encoder (PC6, PC7)
Each timer configured in X4 quadrature mode (4× resolution)
Direction detection handled by hardware (up/down counting)
Reading encoders:
Result: Professional-grade encoder performance typically found in industrial servo systems, not hobby robots.
Part 2: Internal Architecture
What's Inside? (Don't Open really - Here's What's There)
[PLACEHOLDER: Internal wiring diagram OR transparent view render]
Computing Stack:
Raspberry Pi 5 (8GB)
Location: Center of chassis
Function: Main ROS2 brain
Runs: Ubuntu 24.04, ROS2 Jazzy, all high-level software
Cooling: Active fan with temperature-based PWM control
Power: 5V 5A from buck converter
Lyra Controller (STM32F405)
Location: Mounted near motors
Function: Real-time motor control, sensor interface
Runs: FreeRTOS + Lyra firmware v2.6
Cooling: Not required. Motor drivers never get hot to damage
Power: 5V from buck converter (via Pi USB during normal operation)
Power Distribution:
Key points:
Motors powered directly from battery (12V)
Logic (Pi, STM32) powered from 5V buck converter
STM32 gets 5V from Pi USB (simple, clean)
MOSFET prevents inrush current damage to switch
Communication Paths:
Part 3: The Lyra Controller Deep Dive
What is Lyra?
Lyra is the name of the STM32-based motor controller inside Beetlebot.
[PLACEHOLDER: Photo of Lyra board OR block diagram]
Think of Beetlebot as having TWO computers:
Raspberry Pi - The "smart" brain (planning, navigation, vision)
Lyra (STM32) - The "reflex" brain (motors, sensors, safety)
Why Two Computers?
Question: Why not just use the Raspberry Pi for everything?
Answer: Linux is NOT real-time.
What does this mean?
Linux can be interrupted at any time:
WiFi packet arrives → interrupt
Disk write completes → interrupt
Screen updates → interrupt
Process scheduler → switches tasks
Result: Your motor control code might run every 50ms... or 53ms... or 47ms... unpredictable!
Motors need: Exactly 50ms update rate (20 Hz), not "approximately 50ms"
Solution: Lyra runs FreeRTOS (real-time OS) → guaranteed 50.000ms control loop
Lyra's Responsibilities
Real-Time Motor Control:
20 Hz PID loop per motor (50ms period, exact)
Encoder reading (1800 ticks/rev resolution)
PWM generation (20 kHz frequency)
Stall detection and recovery
Safety timeouts
Sensor Interface:
IMU (LSM6DSRTR) via I2C @ 100 Hz
Battery voltage via ADC
Motor fault detection (DRV8874 fault pins)
Safety Systems:
Independent watchdog timer (16.4s)
Command timeout (500ms → auto-stop)
Motor fault response (immediate all-stop)
Emergency stop handling
Communication:
Binary protocol over UART3 @ 115200 baud
10 Hz telemetry to Raspberry Pi
CRC16 validation on all packets
Raspberry Pi's Responsibilities
High-Level Intelligence:
ROS2 Jazzy navigation stack
SLAM mapping (SLAM Toolbox)
Path planning (Nav2)
Localization (AMCL)
Sensor fusion (EKF)
Sensor Processing:
LiDAR data (RPLidar driver)
Camera images (V4L2)
Point cloud processing
Image processing
User Interface:
Joystick control (teleop_twist_joy)
RViz visualization (when connected)
Launch file management
Network communication
Coordination:
Receives sensor data from Lyra
Sends motor commands to Lyra
Manages overall robot behavior
Division of Labor Example
User presses joystick forward:
Raspberry Pi (takes ~20-30ms):
Reads joystick USB HID device
joy_nodepublishes/joymessageteleop_nodeconverts to/cmd_vel(geometry_msgs/Twist)lyra_bridgeconverts Twist → wheel velocities (rad/s)Packages into binary protocol packet
Sends via UART3 to Lyra
Lyra STM32 (every 50ms, exactly):
Receives packet, validates CRC
Extracts target wheel velocities
Updates
target_rpm[4]arrayPID Control Loop (runs regardless of new commands):
Read 4 encoders → current RPM
Calculate error (target - actual)
PID math → PWM output
Apply PWM to motors
Send telemetry back to Pi (10 Hz)
Key insight: Even if Pi stops sending commands, Lyra continues controlling motors smoothly for up to 500ms (timeout), then safe-stops.
Part 4: ROS2 Software Architecture
Node Graph Overview
[PLACEHOLDER: ROS2 node graph diagram]
When your Beetlebot boots, these ROS2 nodes start automatically:
Understanding Topics
Topics are like radio stations - nodes "broadcast" on topics, other nodes "listen"
Key topics on your robot:
/cmd_vel (geometry_msgs/Twist)
Published by: teleop, nav2, your code
Contains: Linear velocity (m/s), Angular velocity (rad/s)
Purpose: "Go this fast, turn this fast"
/lyra/cmd_vel_safe (geometry_msgs/Twist)
Published by: cmd_vel_gate (after safety checks)
Contains: Clamped velocities
Purpose: Safe version of cmd_vel
/lyra/wheel_states (custom message)
Published by: lyra_node
Contains: RPM, encoder ticks per wheel
Purpose: Raw motor feedback
/odom (nav_msgs/Odometry)
Published by: lyra_odometry_node
Contains: Robot position (x, y, θ), velocity
Purpose: "Where am I?" (relative to start)
/scan (sensor_msgs/LaserScan)
Published by: rplidar_composition
Contains: 360° distance measurements
Purpose: "What's around me?"
/lyra/imu (sensor_msgs/Imu)
Published by: lyra_node (from STM32)
Contains: Acceleration, angular velocity
Purpose: Motion sensing
Understanding Services
Services are like phone calls - you call, wait for answer
Key services:
/lyra/arm (std_srvs/Trigger)
What it does: Enables motor control
Called by: teleop (when LB pressed)
Response: Success/failure
/lyra/disarm (std_srvs/Trigger)
What it does: Disables motors (safety)
Called by: teleop (when LB released), timeout
Response: Success/failure
/lyra/emergency_stop (std_srvs/Trigger)
What it does: Immediate stop + disarm
Called by: Emergency situations
Response: Success/failure
Part 5: Hands-On Exploration
Exercise 1: Node Discovery (Optional - Requires Laptop)
If you have laptop connected via SSH:
What this tells you: These 7-8 nodes make your robot work!
Exercise 2: Topic Discovery (Optional)
Try echoing different topics:
/cmd_vel- See your joystick commands/odom- See odometry updating/lyra/battery- Check battery voltage
Exercise 3: Physical Inspection While Running
With robot powered and responding:
Observe LiDAR spinning
Should rotate continuously and smoothly
~10 rotations per second (hard to see - it's fast!)
Drive forward slowly (hold LB + push left stick)
Watch all 4 wheels turn in same direction
Listen for motor noise (should be quiet, smooth)
Observe smooth acceleration (not jerky)
Turn in place (hold LB + push right stick)
Left wheels turn one direction
Right wheels turn opposite direction
Robot rotates smoothly
Release LB button
Robot stops immediately
Wheels don't coast (active braking)
Exercise 4: Understanding the TF Tree (Optional - Advanced)
TF = Transform Tree - how robot parts relate in 3D space
Key concept: ROS2 needs to know where each sensor is relative to robot center!
Example:
Camera is 15cm forward, 8.8cm high
LiDAR is 8.5cm forward, 20.6cm high
This info is in URDF (robot description file)
Part 6: Understanding the Startup Sequence
What Happens When You Power On?
Detailed boot sequence (90 seconds):
T+0s: Press power switch
MOSFET opens
Power flows to buck converter
Pi receives 5V, begins boot
T+5s: Raspberry Pi bootloader
Loads from microSD card
Shows rainbow screen (if display connected)
Starts Ubuntu kernel
T+30s: Ubuntu boots
System services start
Network stack initializes
Systemd launches
T+35s: Lyra service starts (auto-launch script)
Runs:
ros2 launch lyra_bringup base.launch.pyThis starts all core nodes
T+40s: Lyra node initializes
Opens UART3 to STM32
STM32 already running (powered via USB)
Binary protocol handshake
T+45s: STM32 Lyra firmware ready
Motors initialized
Encoders zeroed
IMU calibrated
Safety systems armed
T+50s: Odometry node starts
Subscribes to wheel_states
Begins position integration
T+55s: EKF node starts
Fuses wheel odom + IMU
Publishes filtered odometry
T+60s: Teleop node starts
Subscribes to /joy (joystick)
Publishes /cmd_vel
Robot ready for joystick control!
T+90s: System fully booted
All nodes running
RF dongle red LED turns OFF
Ready to drive!
Part 7: Safety Systems Explained
Multi-Layer Protection
Beetlebot has 5 independent safety layers:
Layer 1: Hardware (DRV8874 Motor Drivers)
Overcurrent protection (>3.5A per motor)
Thermal shutdown (>150°C)
Under-voltage lockout (<7V)
Over-voltage protection (>16V)
Response time: Microseconds
Layer 2: STM32 Firmware
Watchdog timer (16.4s - resets if software hangs)
Command timeout (500ms - stops if no new commands)
Stall detection (10 cycles @ 5 RPM threshold)
Fault monitoring (checks fault pins every cycle)
Response time: 50ms (one control cycle)
Layer 3: ROS2 Bridge (lyra_node)
UART connection monitoring
CRC validation (discards corrupted packets)
Sequence number checking (detects packet loss)
Response time: 100ms (one telemetry cycle)
Layer 4: Safety Gate (cmd_vel_gate)
Velocity clamping (max 1.0 m/s linear, 2.0 rad/s angular)
ARM status checking (blocks commands if DISARMED)
Emergency stop handling
Response time: ~10ms (ROS2 callback)
Layer 5: Mechanical
Ground clearance (16.3cm - avoids getting stuck)
Wheel traction (rubber treads prevent uncontrolled sliding)
Battery BMS (prevents over-discharge, short circuit)
All layers work independently - if one fails, others still protect!
Part 8: Key Specifications Summary
Quick Reference Table
Compute
Raspberry Pi 5 (8GB)
Ubuntu 24.04, ROS2 Jazzy
Motor Controller
STM32F405 (Lyra)
FreeRTOS, 168 MHz
Motors
4× JGB37-3530
12V DC metal gear
Encoders
4× Quadrature
1800 ticks/rev
LiDAR
RPLidar C1
12m range, 10 Hz scan
Camera
Pi Camera V1.3
5MP, 1080p @ 30fps
IMU
LSM6DSRTR
6-axis (accel + gyro)
Battery
3S Li-Ion 10Ah
11.1V nominal
Max Speed
1.0 m/s
3.6 km/h
Runtime
5-6 hours
Typical mixed use
Weight
2.2 kg
With battery
Dimensions
375×360×245mm
L×W×H
Control Loop
20 Hz
50ms period (exact)
Telemetry
10 Hz
Binary protocol
Communication
UART3 @ 115200
Pi ↔ STM32
Part 9: Knowledge Check
Self-Assessment Quiz
Answer these to verify understanding:
What are the two computers in Beetlebot?
Why can't Raspberry Pi control motors directly?
What does the deadman switch (LB button) do?
How many safety layers does Beetlebot have?
What's the resolution of the encoders?
What protocol does Lyra use to communicate with Pi?
Name 3 sensors on Beetlebot.
What happens if controller disconnects while driving?
Part 10: What You've Learned
✅ Congratulations!
You now understand:
Hardware:
✅ All physical components and their locations
✅ What's inside the chassis (without opening it)
✅ How power flows from battery to motors
✅ Where sensors are mounted and what they do
Software:
✅ Why two computers are needed (real-time vs. high-level)
✅ What Lyra (STM32) does vs. Raspberry Pi
✅ ROS2 node architecture (8 key nodes)
✅ How joystick commands become motor motion
Safety:
✅ 5 independent safety layers
✅ Deadman switch operation
✅ Timeout protection
✅ Emergency stop capability
Communication:
✅ Binary protocol (Pi ↔ STM32)
✅ ROS2 topics (inter-node communication)
✅ Services (request/response actions)
✅ TF tree (spatial relationships)
Next Steps
🎯 Ready for More?
Recommended progression:
Option A: Continue Learning Path → Next tutorial: ROS2 Communication & Tools → Learn to use ROS2 command-line tools → Understand topics, services, parameters → Debug robot behavior
Option B: Configure Your System → Go to System Setup Guide → Configure WiFi and SSH → Set up laptop development environment → Then return to tutorials
Option C: Just Keep Driving! → Practice more with joystick → Get comfortable with controls → Learn robot's handling characteristics → Setup can wait!
Troubleshooting
Common Questions
Q: Can I open the chassis to see inside? A: Yes, but not necessary and not recommended during warranty. All internals are documented here. If you must open it, power OFF first and disconnect battery!
Q: What if I want to add more sensors? A: Top plate has mounting holes. USB and GPIO available on Pi. Advanced tutorial covers sensor integration.
Q: How do I know battery voltage?
A: If OLED present, it shows on screen. Otherwise, use ROS2: ros2 topic echo /lyra/battery
Q: Robot sometimes stops moving mid-drive? A: This is command timeout (500ms safety). Keep sending commands (hold joystick stick) or increase timeout in parameters.
Q: Can I update the Lyra (STM32) firmware?
A: Yes, but firmware is proprietary:
Firmware distribution:
Lyra STM32 firmware is proprietary/closed source
Source code not available to customers
VEEROBOT® provides firmware updates as compiled
.hexfiles when availableUpdates include bug fixes, new features, performance improvements
Update process:
Obtain firmware file from VEEROBOT® support ([email protected])
Provided as
.hexor.binfileIncludes version number and changelog
Purchase ST-Link V2 programmer (not included with robot)
Available on Amazon, AliExpress, Digi-Key
Cost: ~$10-30 USD
USB interface for firmware flashing
Connect ST-Link to Lyra board
Requires opening robot chassis
Connect SWD pins: SWDIO, SWCLK, GND, 3.3V
Contact support for exact pin locations
Flash firmware using STM32CubeProgrammer (free from ST)
Download: https://www.st.com/stm32cubeprog
Load
.hexfileClick "Program"
Verify successful flash
Test robot operation after flashing
⚠️ Warnings:
Incorrect firmware can brick controller (recoverable but requires support)
Warranty void if damaged during customer flashing attempt
Power off robot before connecting ST-Link
Never disconnect ST-Link during programming
When to update:
VEEROBOT® notifies of critical bug fixes
New features announced
Experiencing known issue with firmware fix available
Q: What about updating ROS2 code in Raspberry pi? A: ROS code is available on GitHub. Users can always refer to our GitHub page and update the code from there
The Universal Fix: Power Cycle
Most common solution to various issues:
When to power cycle:
ROS2 nodes not appearing
Topics not updating
RViz shows stale data
SLAM map looks corrupted
Navigation behaving strangely
General "weirdness"
How to properly power cycle:
Stop robot motion (release LB, ensure stationary)
Press power button on back panel (red LED turns off)
Wait 10 seconds (allows capacitors to discharge, Pi to fully shutdown)
Press power button again (red LED turns on)
Wait 90 seconds for full boot
Verify operation (drive with joystick, check RViz)
⚠️ Important: Use Power Button, NOT Reset Button
Power button:
✅ Proper shutdown sequence
✅ Clears all software state
✅ Re-initializes all hardware
✅ Fixes 90% of issues
Reset button:
⏸️ Only restarts Raspberry Pi
⏸️ STM32 may stay in weird state
⏸️ Doesn't clear all hardware buffers
⏸️ Use only when Pi frozen (rare)
Why power cycling works:
Software bugs can leave system in inconsistent states:
DDS discovery cache corrupted
ROS2 daemon stuck
Hardware buffers full
Timing issues accumulated
Network state confused
Full power cycle clears everything and starts fresh.
Pro tip: When in doubt, power cycle! It's quick (2 minutes) and solves most issues.
Resources
Related Documentation:
System Setup Guide - Configure WiFi, SSH
ROS2 Communication & Tools - Next tutorial
Technical Reference Manual - Deep dive into every detail
External Resources:
Completed Hardware Familiarization?
→ Continue to ROS2 Communication & Tools → Or return to Tutorial Index
Last Updated: January 2026 Tutorial 1 of 11 - Beginner Level Estimated completion time: 50 minutes
Last updated