修改时间:2026.1.26
参与者:刘志钰
类的封装与调用
如果你想用一个代码调用一个功能,那么当你面对需要同时调用多个功能的问题时就需要繁复地写各种 .cpp 文件。例如,你不仅需要 /Odometry 的数据,还要 /Pointcloud 的数据,还要其他各种各样的数据。
面对这样的问题,有个简单的办法就是把各种调用的部分进行封装。但是封装也不是一件容易的事,下面仍以 livox-mid360 为例,说明如何封装自己写的类,并且学会写 CMakeLists.txt。这不仅可以帮助你学会如何编写一个功能包,更能让你面对报错时知道该从哪里找问题所在。
1)功能包结构图
此处工作空间命名为 livox_odom_ws,功能包自定义为 livox_odom,后续不再说明。想要封装一个类,需要的结构图如图所示。
livox_odom_ws/
├── src/
│ ├── livox_odom/
│ │ ├── include/livox_odom/odom_processor.hpp # 头文件
│ │ ├── src/odom_processor.cpp # 实现文件
│ │ ├── /main.cpp # 主程序
│ │ └── CMakeLists.txt
│ └── ...
└── ...
可以看到,总共需要新添加三个文件:
include/livox_odom/下的odom_processor.hppsrc/下的odom_processor.cppsrc/下的主程序main.cpp
当然,最重要的还有 CMakeLists.txt 的编写。
对于多个话题的数据处理,大概的架构流程如下所示:
2)头文件的编写
下面是 odom_processor.hpp 的代码,并附以较为详细的解释。
#pragma once
#include "rclcpp/rclcpp.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2/LinearMath/Matrix3x3.h"
namespace livox_odom {
class OdomProcessor : public rclcpp::Node {
public:
// 构造函数显式指定话题名称
OdomProcessor(const std::string& node_name = "odom_processor_node");
// 数据存储结构体
struct OdomData {
double x = 0.0, y = 0.0, z = 0.0; // 位置坐标(米)
double roll = 0.0, pitch = 0.0, yaw = 0.0; // 欧拉角(弧度)
};
// 获取最新数据的线程安全方法
OdomData get_current_data() const;
private:
void odom_callback(const nav_msgs::msg::Odometry::SharedPtr msg);
OdomData current_data_;
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub_;
};
} // namespace livox_odom
代码解析
#pragma once:用于避免重复引用头文件导致报错。详细说明可参考:[可疑链接已删除]namespace livox_odom:命名空间内可以存放变量、函数或类。如果调用命名空间中的函数,要记得添加上作用域livox_odom::。详细说明可参考:详解c++的命名空间namespace
构造函数参数含义表:
| 部分 | 含义 | ROS2 开发中的意义 |
|---|---|---|
const | 表示参数是只读的,函数内部不能修改它的值 | 确保节点名称不会被意外修改 |
std::string& | 字符串的引用(避免拷贝开销) | 高效传递节点名称(ROS2 节点名称通常是字符串) |
node_name | 参数名称,开发者自定义的标识符 | 用于接收外部传入的节点名称 |
node_name:此处默认值为odom_processor_node,在使用这个类的时候可以不用再写入节点名称。OdomData:自己创建的结构体,用于封装从/Odometry中读取到的数据。get_current_data() const:用于获取current_data_的副本。const声明该函数为常量成员函数,函数内部不会修改类的任何成员变量。rclcpp::Subscription<...>::SharedPtr:表示 ROS2 的订阅者对象,后续订阅话题内容需要通过这个变量。
3)实现文件的编写
实现文件即 odom_processor.cpp,下面是具体的代码:
#include "livox_odom/odom_processor.hpp"
namespace livox_odom {
// OdomProcessor是在public中定义的,外部引用需要添加作用域
OdomProcessor::OdomProcessor(const std::string& node_name)
: Node(node_name) {
odom_sub_ = create_subscription<nav_msgs::msg::Odometry>(
"/Odometry",
10,
[this](const nav_msgs::msg::Odometry::SharedPtr msg) {
odom_callback(msg);
});
}
void OdomProcessor::odom_callback(const nav_msgs::msg::Odometry::SharedPtr msg) {
// 存储位置数据
current_data_.x = msg->pose.pose.position.x;
current_data_.y = msg->pose.pose.position.y;
current_data_.z = msg->pose.pose.position.z;
// 四元数转欧拉角
tf2::Quaternion q(
msg->pose.pose.orientation.x,
msg->pose.pose.orientation.y,
msg->pose.pose.orientation.z,
msg->pose.pose.orientation.w);
tf2::Matrix3x3 m(q);
m.getRPY(current_data_.roll, current_data_.pitch, current_data_.yaw);
}
OdomProcessor::OdomData OdomProcessor::get_current_data() const {
return current_data_;
}
} // namespace livox_odom
代码解析
- 构造函数的写法与普通 C++ 编写 ROS2 节点类似,区别在于使用了头文件声明。
- Lambda 表达式:回调函数使用 C++ Lambda 表达式定义。
| 代码部分 | 说明 |
|---|---|
[this] | 捕获列表:指定外部变量的捕获方式,这里捕获 this 指针以便调用成员函数。 |
(参数列表) | 函数参数:与普通函数参数定义相同。 |
{ 函数体 } | 执行逻辑:收到消息时执行的操作。 |
get_current_data():作为一个数据读取接口,用于从类中安全地读取当前存储的里程计数据,为外部代码提供current_data_。
| 代码部分 | 说明 |
|---|---|
OdomProcessor::OdomData | 返回类型(自定义结构体) |
OdomProcessor::get_current_data | 类成员函数限定符 |
() const | 声明为常量成员函数(不可修改成员变量) |
4)主程序的编写
main.cpp 即主程序,一般在这里进行数据的读取和操作。
#include "livox_odom/odom_processor.hpp"
#include <chrono> // 时间库(用于sleep_for)
#include <thread> // 多线程支持
#include <iomanip> // 输出格式化
// 弧度转角度转换函数
constexpr double rad2deg(double radians) {
return radians * 180.0 / M_PI;
}
int main(int argc, char** argv) {
rclcpp::init(argc, argv);
// 创建里程计处理实例
auto odom_processor = std::make_shared<livox_odom::OdomProcessor>();
// 启动ROS2运行线程
std::thread ros_thread([&]() {
rclcpp::spin(odom_processor);
});
// 控制台输出线程
while (rclcpp::ok()) {
// 获取里程计数据
auto data = odom_processor->get_current_data();
// 位置输出(保留3位小数)
std::cout << std::fixed << std::setprecision(3);
std::cout << "位置 (m):\n X: " << data.x
<< "\n Y: " << data.y
<< "\n Z: " << data.z << std::endl;
// 2Hz输出频率
std::this_thread::sleep_for(std::chrono::milliseconds(250));
}
ros_thread.join();
rclcpp::shutdown();
return 0;
}
线程与架构说明
| 代码段 | 说明 |
|---|---|
std::thread ros_thread | 创建一个名为 ros_thread 的线程对象 |
[&]() | Lambda 表达式捕获列表和参数列表 |
rclcpp::spin(odom_processor) | ROS2 核心事件处理函数,保持节点运行 |
多线程扩展:
如果想要创建多个线程同步进行(需要同时读取多个话题数据),则可以采用如下方法:
// 创建多个节点线程
std::thread node1_thread([&](){ rclcpp::spin(node1); });
std::thread node2_thread([&](){ rclcpp::spin(node2); });
多线程工作流程图:
A[主线程 main] --> B[创建 ros_thread]
B --> C[执行 rclcpp::spin]
A --> D[执行数据输出循环]
C --> E[处理ROS2消息]
D --> F[控制台打印]
5) CMakeLists 的编写
CMakeLists.txt 是极其重要的部分,决定了能否成功编译。在生成功能包时会自动生成部分内容,这里展示需要额外添加的关键部分。
# 1. 添加头文件搜索路径
# 让编译器能够找到自定义文件, 确保在编译时能找到 #include "livox_odom/odom_processor.hpp"
target_include_directories(odom_processor PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include>"
)
# 2. 将 src/odom_processor.cpp 编译成静态库 libodom_processor.a
add_library(odom_processor
src/odom_processor.cpp
)
# 3. 使用 ament_target_dependencies 管理依赖
ament_target_dependencies(odom_processor
PUBLIC
rclcpp
nav_msgs
geometry_msgs
tf2
tf2_ros
std_msgs
)
# 4. 可执行文件配置
# 将 src/main.cpp 编译为可执行文件 odom_node
add_executable(odom_node
src/main.cpp
)
# 5. 链接依赖(显式传递所有必要目标)
target_link_libraries(odom_node
odom_processor
${nav_msgs_LIBRARIES} # nav_msgs必须使用这种链接方式,否则可能报错
rclcpp::rclcpp
tf2::tf2
tf2_ros::tf2_ros
)
# 6. 安装配置
# 将生成的库和可执行文件安装到 install/lib/livox_odom
install(TARGETS
odom_processor # 生成的库
odom_node # 生成可执行文件(缺失会报错 No add_executable found)
DESTINATION lib/${PROJECT_NAME}
)
# 7. 关键:导出依赖项
ament_export_dependencies(
rclcpp
nav_msgs
geometry_msgs
tf2
tf2_ros
std_msgs
)
ament_export_include_directories(
include
)
ament_export_libraries(
odom_processor
)
ament_package()
注意事项
- 可执行文件名称:
ros2 run <package_name> <executable_name>命令中的<executable_name>依赖于 CMake 中add_executable的定义(本例中为odom_node)。 - 依赖链接:确保
target_link_libraries中链接了所有用到的库。
CMakeLists 工作流程: