个人项目:基于 ROS2 的激光雷达小车 SLAM 与自主导航系统
- 项目时间:2024.09 – 2024.10
- 技术栈:ROS2 Humble / Navigation2 / Cartographer / slam-toolbox / Micro-ROS / ESP32 / 分布式架构
视频展示:
项目简介
基于 Fishbot 硬件平台,用 ESP32 + Micro-ROS 做底盘控制,搭载激光雷达,用 ROS2 做建图和导航。上位机支持PC(WSL2)和树莓派两种部署方式,通过 UDP 或串口与车体通信。用 Cartographer 和 slam-toolbox 做未知环境建图和定位,接入 Navigation2 实现目标点导航。
项目亮点
- 差速底盘:ESP32 + Micro-ROS,编码器闭环控制与传感器数据上报
- 分布式架构:PC(WSL2 )和树莓派两套部署方案;UDP/串口通信
- SLAM:Cartographer / slam-toolbox 实时建图与定位
- 自主导航:Navigation2 路径规划与目标点导航
- 闭环链路:底盘控制 → SLAM → 规划 → 下发目标点执行
系统架构
两种部署形态:
A. PC 上位机方案(WSL2)
- PC 侧部署 Micro-ROS agent + 雷达驱动(docker)、Rviz2 可视化
- ESP32(Micro-ROS 固件)通过 UDP 接入局域网,上位机侧(Rviz2)控制/可视化
B. 树莓派上车方案(Raspberry Pi 4B)
- 激光雷达串口接入树莓派;树莓派跑 micro-ros-agent 串口连 ESP32;PC 端(Ubuntu 22.04) SSH 进树莓派启动建图,Rviz2 同域读取数据并发送目标点

硬件清单
- 差速底盘小车(Fishbot 平台)
- 激光雷达(ydlidar)
- ESP32(Micro-ROS 固件)
- 可选:树莓派 4B(上车方案)
软件/框架
- ROS2 Humble、Navigation2、Cartographer / slam-toolbox、Micro-ROS
核心模块
- 底盘控制与里程计:编码器闭环、速度控制接口、里程计/传感器数据上报(ESP32 + Micro-ROS)
- 通信链路:UDP(PC 方案)/ 串口(树莓派方案),Micro-ROS agent 桥接 ROS2 网络
- SLAM:Cartographer / slam-toolbox 实时建图定位
- 导航:Navigation2(规划用 hyperA*;跟踪用 MPPI/DWB)
Demo 展示(B站)
- 视频 1:从Navigation2开始的ROS2生活(BV1boxYePEWm)
- 视频 2:未知环境探索——ROS2树莓派小车实时地图构建和导航(BV1Fs2BYPEbU)
仿真


代码展示(部分)
bringup.launch.py
import launch
import launch_ros
from ament_index_python.packages import get_package_share_directory
from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description():
fishbot_bringup_dir = get_package_share_directory(
'fishbot_bringup'
)
ydlidar_ros2_dir = get_package_share_directory(
'ydlidar'
)
urdf2tf = launch.actions.IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[fishbot_bringup_dir,'/launch','/urdf2tf.launch.py']
),
)
odom2tf = launch_ros.actions.Node(
package='fishbot_bringup',
executable='odom2tf',
output='screen'
)
microros_agent = launch_ros.actions.Node(
package='micro_ros_agent',
executable='micro_ros_agent',
arguments=['udp4','--port','8888'],
output='screen'
)
ros_serail2wifi = launch_ros.actions.Node(
package='ros_serail2wifi',
executable='tcp_server',
parameters=[{'serial_port':'/tmp/tty_laser'}],
output = 'screen'
)
ydlidar = launch.actions.IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[ydlidar_ros2_dir,'/launch','/ydlidar_launch.py']
),
)
#使用TimerAction启动后的5s执行ydlidar节点
ydlidar_delay = launch.actions.TimerAction(period=5.0,actions=[ydlidar])
return launch.LaunchDescription([
urdf2tf,
odom2tf,
microros_agent,
ros_serail2wifi,
ydlidar_delay
])
odom2tf.cpp
#include <rclcpp/rclcpp.hpp>
#include <tf2/utils.h>
#include <tf2_ros/transform_broadcaster.h>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
class OdomTopic2TF : public rclcpp::Node {
public:
OdomTopic2TF(std::string name) : Node(name) {
// 创建 odom 话题订阅者,使用传感器数据的 Qos
odom_subscribe_ = this->create_subscription<nav_msgs::msg::Odometry>(
"odom", rclcpp::SensorDataQoS(),
std::bind(&OdomTopic2TF::odom_callback_, this, std::placeholders::_1));
// 创建一个tf2_ros::TransformBroadcaster用于广播坐标变换
tf_broadcaster_ = std::make_unique<tf2_ros::TransformBroadcaster>(this);
}
private:
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_subscribe_;
std::unique_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
// 回调函数,处理接收到的odom消息,并发布tf
void odom_callback_(const nav_msgs::msg::Odometry::SharedPtr msg) {
geometry_msgs::msg::TransformStamped transform;
transform.header = msg->header; // 使用消息的时间戳和框架ID
transform.child_frame_id = msg->child_frame_id;
transform.transform.translation.x = msg->pose.pose.position.x;
transform.transform.translation.y = msg->pose.pose.position.y;
transform.transform.translation.z = msg->pose.pose.position.z;
transform.transform.rotation.x = msg->pose.pose.orientation.x;
transform.transform.rotation.y = msg->pose.pose.orientation.y;
transform.transform.rotation.z = msg->pose.pose.orientation.z;
transform.transform.rotation.w = msg->pose.pose.orientation.w;
// 广播坐标变换信息
tf_broadcaster_->sendTransform(transform);
};
};
int main(int argc, char **argv) {
rclcpp::init(argc, argv);
auto node = std::make_shared<OdomTopic2TF>("odom2tf");
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}