由于turtlebot3官方没有找到ROS2 Foxy分支,因此修改源码使turtlebot3能在Ubuntu 20.04 + ROS2 Foxy+Gazebo 11.15.1 环境下编译运行。
为了避免大家再次采坑,特开源项目,项目地址为
https://download.csdn.net/download/ktigerhero3/92766623
TurtleBot3 ROS2 Foxy 编译修复总结
项目概述
本工程基于TurtleBot3官方源码,针对Ubuntu 20.04 + ROS2 Foxy环境进行了编译修复和功能增强。主要解决了ROS2 Foxy API变更导致的编译错误,并添加了新的仿真启动文件。
环境配置
- 操作系统: Ubuntu 20.04 LTS
- ROS2版本: Foxy Fitzroy
- Gazebo版本: 11.15.1
- 工作空间 :
/home/qian/turtlebot3_ws_ros2
主要修改内容
1. 编译错误修复
问题分析
ROS2 Foxy中declare_parameter函数API变更,需要至少两个参数(参数名和默认值),而原始代码只提供了一个参数。
修复文件
(1) src/turtlebot3/turtlebot3_node/src/turtlebot3.cpp
cpp
// 修复前
this->declare_parameter<uint8_t>("opencr.id");
this->declare_parameter<int>("opencr.baud_rate");
this->declare_parameter<float>("opencr.protocol_version");
this->declare_parameter<std::string>("namespace");
// 修复后
this->declare_parameter<uint8_t>("opencr.id", 200);
this->declare_parameter<int>("opencr.baud_rate", 1000000);
this->declare_parameter<float>("opencr.protocol_version", 2.0f);
this->declare_parameter<std::string>("namespace", "");
(2) src/turtlebot3/turtlebot3_node/src/odometry.cpp
cpp
// 修复前
nh_->declare_parameter<std::string>("odometry.frame_id");
nh_->declare_parameter<std::string>("odometry.child_frame_id");
nh_->declare_parameter<std::string>("namespace");
nh_->declare_parameter<bool>("odometry.use_imu");
nh_->declare_parameter<bool>("odometry.publish_tf");
// 修复后
nh_->declare_parameter<std::string>("odometry.frame_id", "odom");
nh_->declare_parameter<std::string>("odometry.child_frame_id", "base_footprint");
nh_->declare_parameter<std::string>("namespace", "");
nh_->declare_parameter<bool>("odometry.use_imu", false);
nh_->declare_parameter<bool>("odometry.publish_tf", false);
修复的参数列表
| 参数类别 | 参数名 | 默认值 | 说明 |
|---|---|---|---|
| OpenCR | opencr.id |
200 | OpenCR设备ID |
| OpenCR | opencr.baud_rate |
1000000 | 波特率 |
| OpenCR | opencr.protocol_version |
2.0 | 协议版本 |
| 命名空间 | namespace |
"" | 节点命名空间 |
| 电机 | motors.profile_acceleration_constant |
214.577 | 加速度常数 |
| 电机 | motors.profile_acceleration |
0.0 | 加速度 |
| 轮子 | wheels.separation |
0.160 | 轮间距(m) |
| 轮子 | wheels.radius |
0.033 | 轮半径(m) |
| 传感器 | sensors.bumper_1 |
0 | 前碰撞传感器 |
| 传感器 | sensors.bumper_2 |
0 | 后碰撞传感器 |
| 传感器 | sensors.illumination |
0 | 光照传感器 |
| 传感器 | sensors.ir |
0 | 红外传感器 |
| 传感器 | sensors.sonar |
0 | 声纳传感器 |
| 里程计 | odometry.frame_id |
"odom" | 坐标系ID |
| 里程计 | odometry.child_frame_id |
"base_footprint" | 子坐标系ID |
| 里程计 | odometry.use_imu |
false | 是否使用IMU |
| 里程计 | odometry.publish_tf |
false | 是否发布TF |
2. 新增仿真启动文件
(1) spawn_turtlebot3_classic.launch.py
- 用途: 使用SDF 1.7版本模型文件生成机器人
- 特点 : 加载
model_v1.7.sdf模型文件,支持更新的SDF格式 - 路径 :
src/turtlebot3_simulations/turtlebot3_gazebo/launch/spawn_turtlebot3_classic.launch.py
(2) turtlebot3_classic_all.launch.py
- 用途: 一键启动Gazebo仿真环境并生成机器人
- 特点: 合并了两个终端的操作,简化启动流程
- 功能 :
- 自动设置
GAZEBO_MODEL_PATH环境变量 - 自动设置
TURTLEBOT3_MODEL环境变量 - 启动Gazebo服务器(使用系统默认empty.world)
- 生成TurtleBot3机器人模型
- 自动设置
- 路径 :
src/turtlebot3_simulations/turtlebot3_gazebo/launch/turtlebot3_empty_world_classic.launch.py
3. 模型文件分析
模型文件对比
| 文件 | SDF版本 | 特点 | 状态 |
|---|---|---|---|
model-1_4.sdf |
1.4 | 传统Gazebo ROS插件 | 原始文件 |
model_v1.7.sdf |
1.7 | 更新的SDF格式,有材质定义 | 新增支持 |
model.sdf |
1.7 | 与model_v1.7.sdf相同 | 原始文件 |
材质问题修复
model_v1.7.sdf中包含完整的材质定义,解决了机器人显示为灰色的问题:
xml
<material>
<ambient>0.3 0.3 0.3 1.0</ambient>
<diffuse>0.3 0.3 0.3 1.0</diffuse>
</material>
编译验证
编译命令
bash
cd /home/qian/turtlebot3_ws_ros2
source /opt/ros/foxy/setup.bash
colcon build
编译结果
- ✅
turtlebot3_node: 编译成功(修复后) - ✅
turtlebot3_gazebo: 编译成功 - ✅
turtlebot3_msgs: 编译成功 - ✅ 所有包编译通过
测试运行
1. 完整仿真启动
bash
# 设置环境
export TURTLEBOT3_MODEL=waffle
# 一键启动
cd /home/qian/turtlebot3_ws_ros2
source /opt/ros/foxy/setup.bash
source install/setup.bash
ros2 launch turtlebot3_gazebo turtlebot3_classic_all.launch.py
2. 使用SDF 1.7模型
bash
# 使用新版模型文件
ros2 launch turtlebot3_gazebo spawn_turtlebot3_classic7.launch.py
3. 自定义参数启动
bash
ros2 launch turtlebot3_gazebo turtlebot3_classic_all.launch.py \
turtlebot3_model:=waffle \
x_pose:=1.0 \
y_pose:=2.0 \
gui:=true \
verbose:=true
解决的问题
1. 编译错误
- 问题 :
declare_parameter函数调用缺少默认值参数 - 原因: ROS2 Foxy API变更
- 解决 : 为所有
declare_parameter调用添加合理的默认值
2. 仿真启动复杂
- 问题: 需要两个终端分别启动Gazebo和生成机器人
- 解决 : 创建集成启动文件
turtlebot3_classic_all.launch.py
3. 模型显示问题
- 问题: Gazebo中机器人显示为灰色
- 原因 :
model-1_4.sdf缺少材质定义 - 解决 : 支持
model_v1.7.sdf(包含完整材质定义)
文件结构修改
新增文件
src/turtlebot3_simulations/turtlebot3_gazebo/launch/
├── spawn_turtlebot3_classic7.launch.py # SDF 1.7模型生成
└── turtlebot3_classic_all.launch.py # 集成启动文件
修改文件
src/turtlebot3/turtlebot3_node/
├── src/turtlebot3.cpp # 修复参数声明
└── src/odometry.cpp # 修复参数声明
使用建议
开发环境
- 确保ROS2 Foxy环境正确配置
- 设置
GAZEBO_MODEL_PATH环境变量 - 使用
colcon build进行编译
仿真测试
- 优先使用
turtlebot3_classic_all.launch.py进行集成测试 - 根据需要选择机器人模型(waffle/burger/waffle_pi)
- 使用
model_v1.7.sdf以获得更好的视觉效果
问题排查
- 编译错误:检查
declare_parameter调用是否都有默认值 - 仿真启动失败:检查Gazebo模型路径和环境变量
- 机器人显示异常:尝试使用不同SDF版本的模型文件
总结
本工程成功解决了TurtleBot3在ROS2 Foxy环境下的编译问题,并增强了仿真功能。主要贡献包括:
- 修复了ROS2 Foxy API变更导致的编译错误
- 提供了更便捷的仿真启动方式
- 支持了更新的SDF模型格式
- 改善了Gazebo中的机器人视觉效果
所有修改都保持了向后兼容性,不影响原有功能的使用。