CARLA
 
载入中...
搜索中...
未找到
CarlaNormalsCameraPublisher.h
浏览该文件的文档.
1// 版权所有 (c) 2022 巴塞罗那自治大学 (UAB) 计算机视觉中心 (CVC)。
2// 本作品根据 MIT 许可证进行许可。
3// 许可证副本请参见 <https://opensource.org/licenses/MIT>。
4#pragma once
5#define _GLIBCXX_USE_CXX11_ABI 0
6#include <memory>
7#include <vector>
8#include "CarlaPublisher.h"
9namespace carla {
10namespace ros2 {
11// 前向声明实现类,隐藏实现细节
12 struct CarlaNormalsCameraPublisherImpl;
13 struct CarlaCameraInfoPublisherImpl;
14// CarlaOpticalFlowCameraPublisher 类继承自 CarlaPublisher,用于发布光流相机数据
16 public:
17// 构造函数,接受 ROS 名称和父节点名称,默认值为空
18 CarlaNormalsCameraPublisher(const char* ros_name = "", const char* parent = "");
19// 析构函数
21// 拷贝和移动构造函数及赋值运算符,支持资源管理
26 // 初始化方法
27 bool Init();
28// 初始化相机信息数据
29 void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify);
30// 发布数据
31 bool Publish();
32// 查询对象是否已初始化
33 bool HasBeenInitialized() const;
34// 设置图像数据
35 void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const uint8_t* data);
36// 设置相机信息数据
37 void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds);
38// 返回光流相机类型
39 const char* type() const override { return "normals camera"; }
40 private:
41 // 初始化图像和信息的私有方法
42 bool InitImage();
43 bool InitInfo();
44// 发布图像和信息的私有方法
45 bool PublishImage();
46 bool PublishInfo();
47// 设置区域相关信息
48 void SetInfoRegionOfInterest( uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify);
49 // 设置数据
50 void SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector<uint8_t>&& data);
51 private:
52// 使用智能指针管理实现类的实例
53 std::shared_ptr<CarlaNormalsCameraPublisherImpl> _impl;
54 std::shared_ptr<CarlaCameraInfoPublisherImpl> _impl_info;
55 };
56}
57}
void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify)
初始化CameraInfo数据。
void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const uint8_t *data)
设置图像数据
CarlaNormalsCameraPublisher(const char *ros_name="", const char *parent="")
CarlaNormalsCameraPublisher的构造函数
void SetInfoRegionOfInterest(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify)
设置感兴趣区域(Region of Interest, ROI)
bool HasBeenInitialized() const
检查CarlaNormalsCameraPublisher是否已初始化。
CarlaNormalsCameraPublisher & operator=(const CarlaNormalsCameraPublisher &)
赋值运算符重载
bool Init()
初始化CarlaNormalsCameraPublisher。
void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds)
设置相机信息数据的时间戳
bool InitInfo()
初始化CameraInfo发布者。
void SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector< uint8_t > &&data)
设置图像数据
std::shared_ptr< CarlaNormalsCameraPublisherImpl > _impl
~CarlaNormalsCameraPublisher()
CarlaNormalsCameraPublisher的析构函数
std::shared_ptr< CarlaCameraInfoPublisherImpl > _impl_info
const std::string & parent() const
CARLA模拟器的主命名空间。
Definition Carla.cpp:139