CARLA
 
载入中...
搜索中...
未找到
CarlaDVSCameraPublisher.h
浏览该文件的文档.
1// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB).
2// This work is licensed under the terms of the MIT license.
3// For a copy, see <https://opensource.org/licenses/MIT>.
4
5#pragma once // 保证此头文件只被包含一次
6#define _GLIBCXX_USE_CXX11_ABI 0 // 定义宏以控制C++11 ABI兼容性
7
8#include <memory> // 引入智能指针库
9#include <vector> // 引入向量库
10
11#include "CarlaPublisher.h" // 引入CarlaPublisher类的头文件
12
13namespace carla { // 定义carla命名空间
14namespace ros2 { // 定义ros2命名空间
15
16 struct CarlaDVSCameraPublisherImpl; // 前向声明CarlaDVSCameraPublisherImpl结构体
17 struct CarlaCameraInfoPublisherImpl; // 前向声明CarlaCameraInfoPublisherImpl结构体
18 struct CarlaPointCloudPublisherImpl; // 前向声明CarlaPointCloudPublisherImpl结构体
19
20 class CarlaDVSCameraPublisher : public CarlaPublisher { // 定义CarlaDVSCameraPublisher类,继承自CarlaPublisher
21 public:
22 CarlaDVSCameraPublisher(const char* ros_name = "", const char* parent = ""); // 构造函数,带ROS名称和父对象名称参数
23 ~CarlaDVSCameraPublisher(); // 析构函数
24 CarlaDVSCameraPublisher(const CarlaDVSCameraPublisher&); // 拷贝构造函数
25 CarlaDVSCameraPublisher& operator=(const CarlaDVSCameraPublisher&); // 拷贝赋值运算符
26 CarlaDVSCameraPublisher(CarlaDVSCameraPublisher&&); // 移动构造函数
28
29 bool Init(); // 初始化函数
30 void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify); // 初始化信息数据
31 bool Publish(); // 发布函数
32
33 bool HasBeenInitialized() const; // 检查是否已经初始化
34 void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t elements, size_t height, size_t width, const uint8_t* data); // 设置图像数据
35 void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds); // 设置相机信息数据
36 void SetPointCloudData(size_t height, size_t width, size_t elements, const uint8_t* data); // 设置点云数据
37 const char* type() const override { return "dvs camera"; } // 重写类型函数,返回"dvs camera"
38
39 private:
40 bool InitImage(); // 初始化图像函数
41 bool InitInfo(); // 初始化信息函数
42 bool InitPointCloud(); // 初始化点云函数
43
44 void SetInfoRegionOfInterest(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify); // 设置感兴趣区域信息
45 void SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector<uint8_t>&& data); // 设置数据
46 void SetPointCloudData(size_t height, size_t width, std::vector<uint8_t>&& data); // 设置点云数据
47 bool PublishImage(); // 发布图像函数
48 bool PublishInfo(); // 发布信息函数
49 bool PublishPointCloud(); // 发布点云函数
50
51 private:
52 std::shared_ptr<CarlaDVSCameraPublisherImpl> _impl; // 智能指针,指向CarlaDVSCameraPublisherImpl的实现
53 std::shared_ptr<CarlaCameraInfoPublisherImpl> _info; // 智能指针,指向CarlaCameraInfoPublisherImpl的实现
54 std::shared_ptr<CarlaPointCloudPublisherImpl> _point_cloud; // 智能指针,指向CarlaPointCloudPublisherImpl的实现
55 };
56}
57}
void SetPointCloudData(size_t height, size_t width, size_t elements, const uint8_t *data)
设置点云数据。
CarlaDVSCameraPublisher & operator=(const CarlaDVSCameraPublisher &)
赋值运算符重载。
CarlaDVSCameraPublisher(const char *ros_name="", const char *parent="")
CarlaDVSCameraPublisher的构造函数。
std::shared_ptr< CarlaCameraInfoPublisherImpl > _info
std::shared_ptr< CarlaDVSCameraPublisherImpl > _impl
bool Publish()
发布图像、信息和点云数据。
void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t elements, size_t height, size_t width, const uint8_t *data)
设置图像数据,用于DVS(动态视觉传感器)相机发布者。
void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify)
初始化相机信息数据
bool InitPointCloud()
初始化点云发布相关资源
void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds)
设置相机信息数据的时间戳和帧ID。
bool InitInfo()
初始化相机信息发布相关资源
bool InitImage()
初始化图像发布相关资源
void SetPointCloudData(size_t height, size_t width, std::vector< uint8_t > &&data)
bool HasBeenInitialized() const
检查是否已初始化
void SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector< uint8_t > &&data)
设置图像数据,包括时间戳、图像尺寸和图像数据。
void SetInfoRegionOfInterest(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify)
设置相机信息中的感兴趣区域(Region Of Interest, ROI)。
bool Init()
初始化CarlaDVSCameraPublisher
std::shared_ptr< CarlaPointCloudPublisherImpl > _point_cloud
~CarlaDVSCameraPublisher()
CarlaDVSCameraPublisher的析构函数。
const std::string & parent() const
CARLA模拟器的主命名空间。
Definition Carla.cpp:139