导语:
视频是机器人感知系统最核心的模块之一。本篇将讲解 Foxglove 如何处理摄像头视频流,包括编码格式、消息封装、bridge 转发、前端渲染机制,并对常见问题(如卡顿、颜色不对)给出解决方案。
本篇依赖前两篇的内容,请读者前往阅读 👀
《机器人实践开发①:Foxglove 开发环境完整搭建指南(含常见坑位)》
《机器人实践开发②:Foxglove 嵌入式移植 + CMake 集成》
第一种方式比较简单,通过 ros2 的方式推送图片流
注意:
这种方式比较耗流量,在网络不好的情况下会导致异常显示
需要结合 opencv2 处理图片
需要在机器人端运行桥接指令 ros2 launch foxglove_bridge foxglove_bridge_launch.xml port:=8765
cpp
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/opencv.hpp>
class CameraPublisher : public rclcpp::Node {
public:
CameraPublisher()
: Node("camera_publisher")
{
publisher_ = this->create_publisher<sensor_msgs::msg::Image>("/camera/image_raw", 10);
cap_.open(0); // 默认摄像头
if (!cap_.isOpened()) {
RCLCPP_ERROR(this->get_logger(), "Cannot open camera");
rclcpp::shutdown();
}
timer_ = this->create_wall_timer(
std::chrono::milliseconds(33), // ~30 FPS
std::bind(&CameraPublisher::publish_frame, this)
);
}
private:
void publish_frame() {
cv::Mat frame;
cap_ >> frame;
if (frame.empty()) {
RCLCPP_WARN(this->get_logger(), "Empty frame captured");
return;
}
auto msg = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", frame).toImageMsg();
publisher_->publish(*msg);
RCLCPP_INFO(this->get_logger(), "Published a frame");
}
rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_;
cv::VideoCapture cap_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<CameraPublisher>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
编写 CmakeList.txt文件
cpp
cmake_minimum_required(VERSION 3.8)
project(camera_publisher)
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(cv_bridge REQUIRED)
find_package(OpenCV REQUIRED)
add_executable(camera_publisher camera_publisher.cpp)
ament_target_dependencies(camera_publisher rclcpp std_msgs visualization_msgs cv_bridge OpenCV)
install(TARGETS
camera_publisher
DESTINATION ${CMAKE_CURRENT_SOURCE_DIR}/lib/${PROJECT_NAME})
ament_package()
第二种方式,使用 foxglove sdk 的方式集成,使用 H264/H265视频流的方式,推荐!!
有效的节省带宽,运动特性更好
视频指令可控,帧率/码流/分辨率
功耗低,运行比第一种方式节省 cpu 资源
定义视频类
cpp
std::unique_ptr<foxglove::schemas::CompressedVideoChannel> visualization_compressed_main_video_channel;
封装视频发送接口
核心接口是visualization_compressed_main_video_channel>log(compressed_video)
注意填充数据 一定要将timestamp 填充对,否则没有看不见视频
cpp
int FoxgloveVisualizationService::startVideoChannelService(int index,uint8_t *video_buffer, uint32_t audio_size) {
auto time_since_epoch = std::chrono::system_clock::now().time_since_epoch();
auto seconds = std::chrono::duration_cast<std::chrono::seconds>(time_since_epoch);
auto nanoseconds =
std::chrono::duration_cast<std::chrono::nanoseconds>(time_since_epoch - seconds);
foxglove::schemas::Timestamp timestamp;
timestamp.sec = static_cast<uint32_t>(seconds.count());
timestamp.nsec = static_cast<uint32_t>(nanoseconds.count());
std::vector<std::byte> data(audio_size * sizeof(uint8_t));
std::memcpy(data.data(), video_buffer, audio_size * sizeof(uint8_t));
foxglove::schemas::CompressedVideo compressed_video;
compressed_video.format = "h264";
compressed_video.timestamp = timestamp;
compressed_video.frame_id = visualization_frame_id;
compressed_video.data = data;
index==0?visualization_compressed_main_video_channel->log(compressed_video):visualization_sub_compressed_video_channel->log(compressed_video);
}
使用工具可视化视频
