CARLA
 
载入中...
搜索中...
未找到
CarlaDepthCameraPublisher.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
7
8#include <memory>// 引入智能指针相关的头文件
9#include <vector>// 引入向量容器相关的头文件
10
11#include "CarlaPublisher.h"// 引入CarlaPublisher类的头文件
12
13namespace carla {
14namespace ros2 {
15 /// @brief CarlaDepthCameraPublisher的内部实现结构体(前向声明)
16 /// 这是一个Pimpl(Pointer to IMPLementation)用法,用于隐藏实现细节。
17 struct CarlaDepthCameraPublisherImpl;
18 /// @brief CarlaCameraInfoPublisher的内部实现结构体(前向声明)
19 /// 这也是一个Pimpl用法,用于隐藏与相机信息相关的实现细节。
20 struct CarlaCameraInfoPublisherImpl;
21 /// @class CarlaDepthCameraPublisher
22 /// @brief 用于在ROS 2中发布CARLA深度相机数据的类。
23 /// 这个类继承自CarlaPublisher,专门用于初始化、设置和发布深度相机数据。
25 public:
26 /// @brief 构造函数,用于创建CarlaDepthCameraPublisher对象。
27 /// @param ros_name ROS节点的名称(可选)。
28 /// @param parent 父节点的名称(可选)。
29 CarlaDepthCameraPublisher(const char* ros_name = "", const char* parent = "");
30 /// @brief 析构函数,用于销毁CarlaDepthCameraPublisher对象。
32 /// @brief 拷贝构造函数。
34 /// @brief 拷贝赋值运算符。
36 /// @brief 移动构造函数。
38 /// @brief 移动赋值运算符。
40 /// @brief 初始化函数,用于设置ROS节点和发布者。
41 /// @return 初始化是否成功。
42 bool Init();
43 void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify);
44 bool Publish();
45
46 bool HasBeenInitialized() const;
47 void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const uint8_t* data);
48 void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds);
49 const char* type() const override { return "depth camera"; }
50
51 private:
52 bool InitImage();
53 bool InitInfo();
54 bool PublishImage();
55 bool PublishInfo();
56
57 void SetInfoRegionOfInterest( uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify);
58 void SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector<uint8_t>&& data);
59
60 private:
61 std::shared_ptr<CarlaDepthCameraPublisherImpl> _impl;
62 std::shared_ptr<CarlaCameraInfoPublisherImpl> _impl_info;
63 };
64}
65}
用于在ROS 2中发布CARLA深度相机数据的类。 这个类继承自CarlaPublisher,专门用于初始化、设置和发布深度相机数据。
bool Publish()
发布深度图像和相机信息。
bool InitInfo()
初始化相机信息发布者的DDS相关组件。
~CarlaDepthCameraPublisher()
析构函数,用于销毁CarlaDepthCameraPublisher对象。
CarlaDepthCameraPublisher & operator=(const CarlaDepthCameraPublisher &)
拷贝赋值运算符。
void SetInfoRegionOfInterest(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify)
设置感兴趣区域(ROI)信息
CarlaDepthCameraPublisher(const char *ros_name="", const char *parent="")
构造函数,用于创建CarlaDepthCameraPublisher对象。
bool InitImage()
初始化深度图像数据。
void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const uint8_t *data)
设置图像数据
bool Init()
初始化函数,用于设置ROS节点和发布者。
void SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector< uint8_t > &&data)
设置图像数据及其元数据
std::shared_ptr< CarlaDepthCameraPublisherImpl > _impl
void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify)
初始化深度相机信息数据。
std::shared_ptr< CarlaCameraInfoPublisherImpl > _impl_info
bool HasBeenInitialized() const
检查深度相机发布者是否已初始化。
void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds)
设置相机信息数据的时间戳
const std::string & parent() const
CARLA模拟器的主命名空间。
Definition Carla.cpp:139