ROS2下编写orbbec相机C++ package并Rviz显示
视频讲解:
https://www.bilibili.com/video/BV1HUwSe3E6o/?vd_source=5ba34935b7845cd15c65ef62c64ba82f
ROS2下编写orbbec相机C++ package并Rviz显示
开发环境:Ubuntu22.04 WSL
ROS2版本:humble
创建工作空间
mkdir ws_ros2
cd ws_ros2
mkdir src
cd src
创建ros2 package模板,依赖cv_bridge,OpenCV,sensor_msgs
ros2 pkg create --build-type ament_cmake orbbec_cam_pkg --dependencies rclcpp sensor_msgs cv_bridge OpenCV
创建include和lib,include和lib的文件为orrbec sdk提取
cd orrbec_cam_pkg
mkdir include lib
修改CMakeLists.txt,增加如下内容
file依赖的动态库
target链接
将动态库安装到工作空间的install的lib下
file(GLOB ORBBEC_LIBS "lib/x86_64/*")
target_link_libraries(image_publisher
${ORBBEC_LIBS}
)
install(DIRECTORY
lib/x86_64/
DESTINATION lib/)
src下的image_publisher.cpp
发布消息类型为Image,设置发布定时器30ms,使用封装好的orbbec相机类获取cv图像,通过cv_bridge转换成msg
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/opencv.hpp>
#include <thread>
#include "orbbec.h"
class ImagePublisher : public rclcpp::Node
{
public:
ImagePublisher() : Node("image_publisher")
{
publisher_ = this->create_publisher<sensor_msgs::msg::Image>("rgb_image", 10);
timer_ = this->create_wall_timer(std::chrono::milliseconds(30), std::bind(&ImagePublisher::timer_callback, this));
}
void camInit()
{
cam_.wait4Device();
cam_.init();
std::thread t = std::thread([&]() {
cam_.run();
});
t.detach();
}
private:
void timer_callback()
{
// 创建一个简单的RGB图像(这里创建一个红色方块图像)
// cv::Mat image(480, 640, CV_8UC3, cv::Scalar(0, 0, 255));
cv::Mat image = cam_.getImg();
// 将OpenCV图像转换为ROS 2图像消息
sensor_msgs::msg::Image::SharedPtr msg = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", image).toImageMsg();
// 发布图像消息
publisher_->publish(*msg);
RCLCPP_INFO(this->get_logger(), "Publishing an RGB image");
}
rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_;
OrbbecCam cam_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<ImagePublisher>();
node->camInit();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
运行Rvi2,并添加Image显示
运行orbbec_cam_pkg程序,这里需要注意,需要sudo权限获取设备,所以先切到root,再source当前的ros2工作空间,不然会直接报错退出
sudo su
source install/setup.bash
ros2 run orbbec_cam_pkg image_publisher
可以看到已经获取到相机信息和发布出了数据,图像大小为480*640
切回到Rviz,将Image中的Topic选择为rgb_image,将History Policy选为System Default既可显示