CARLA
 
载入中...
搜索中...
未找到
CarlaOpticalFlowCameraPublisher.h
浏览该文件的文档.
1// 版权 (c) 2022 巴萨大学计算机视觉中心 (CVC)。
2// 本作品根据MIT许可证条款授权。
3// 许可证副本见 <https://opensource.org/licenses/MIT>。
4
5#pragma once
6#define _GLIBCXX_USE_CXX11_ABI 0
7
8#include <memory>
9#include <vector>
10
11#include "CarlaPublisher.h"
12
13namespace carla {
14namespace ros2 {
15
16// 前向声明
17struct CarlaOpticalFlowCameraPublisherImpl;
18struct CarlaCameraInfoPublisherImpl;
19
20// Carla光流相机发布器类
22public:
23 // 构造函数,默认ROS名称和父节点
24 CarlaOpticalFlowCameraPublisher(const char* ros_name = "", const char* parent = "");
25 // 析构函数
27
28 // 拷贝构造函数
30 // 拷贝赋值运算符
32
33 // 移动构造函数
35 // 移动赋值运算符
37
38 // 初始化函数
39 bool Init();
40 // 初始化相机信息数据
41 void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify);
42 // 发布函数
43 bool Publish();
44
45 // 检查是否已初始化
46 bool HasBeenInitialized() const;
47 // 设置图像数据
48 void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const float* data);
49 // 设置相机信息数据
50 void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds);
51 // 重写类型函数
52 const char* type() const override { return "optical flow camera"; }
53
54private:
55 // 初始化图像的私有方法
56 bool InitImage();
57 // 初始化信息的私有方法
58 bool InitInfo();
59 // 发布图像的私有方法
60 bool PublishImage();
61 // 发布信息的私有方法
62 bool PublishInfo();
63
64 // 设置感兴趣区域的私有方法
65 void SetInfoRegionOfInterest(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify);
66 // 设置数据的私有方法
67 void SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector<uint8_t>&& data);
68
69private:
70 // 实现指针
71 std::shared_ptr<CarlaOpticalFlowCameraPublisherImpl> _impl;
72 // 相机信息实现指针
73 std::shared_ptr<CarlaCameraInfoPublisherImpl> _impl_info;
74};
75}
76}
void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify)
初始化摄像头信息数据。
CarlaOpticalFlowCameraPublisher & operator=(const CarlaOpticalFlowCameraPublisher &)
赋值运算符重载
void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const float *data)
设置图像数据,将光学流数据转换为RGBA图像数据
void SetInfoRegionOfInterest(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify)
设置感兴趣区域(ROI)信息
bool HasBeenInitialized() const
检查类是否已经被初始化。
void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds)
设置相机信息数据的时间戳
bool InitInfo()
初始化信息并设置CarlaOpticalFlowCameraPublisher的相关参数。
CarlaOpticalFlowCameraPublisher(const char *ros_name="", const char *parent="")
CarlaOpticalFlowCameraPublisher类的构造函数
void SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector< uint8_t > &&data)
设置图像数据
std::shared_ptr< CarlaOpticalFlowCameraPublisherImpl > _impl
~CarlaOpticalFlowCameraPublisher()
CarlaOpticalFlowCameraPublisher类的析构函数
std::shared_ptr< CarlaCameraInfoPublisherImpl > _impl_info
const std::string & parent() const
CARLA模拟器的主命名空间。
Definition Carla.cpp:139