CARLA
 
载入中...
搜索中...
未找到
CarlaISCameraPublisher.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"
12
13namespace carla {
14namespace ros2 { //定义了代码所属的命名空间
15
16 struct CarlaISCameraPublisherImpl;
17 struct CarlaCameraInfoPublisherImpl; //是内部实现的结构体声明,具体实现可能在对应的源文件中。
18
20 public:
21 CarlaISCameraPublisher(const char* ros_name = "", const char* parent = ""); //带默认参数的构造函数,用于创建CarlaISCameraPublisher对象,可以指定 ROS 名称和父节点名称。
22 ~CarlaISCameraPublisher(); //析构函数,释放资源
27
28 bool Init(); //初始化发布者
29 void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify); //初始化相机信息数据。
30 bool Publish(); //发布相机数据和相机信息数据
31 bool HasBeenInitialized() const; //检查发布者是否已被初始化。
32 void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const uint8_t* data); //设置图像数据。
33
34 void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds); //设置相机信息数据。
35 const char* type() const override { return "instance segmentation"; } //返回发布的数据类型为 “instance segmentation”。
36
37 private:
38 bool InitImage(); //用于初始化图像
39 bool InitInfo(); //用相机信息的发布。
40 bool PublishImage(); // 用于发布图像信息。
41 bool PublishInfo(); // 用于发布相机信息。
42
43 void SetInfoRegionOfInterest( uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify); //设置相机信息的感兴趣区域。
44 void SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector<uint8_t>&& data); //设置数据,包括时间戳、高度、宽度和图像数据
45
46 private:
47 std::shared_ptr<CarlaISCameraPublisherImpl> _impl; //指向内部实现的智能指针,用于管理实例分割相机数据的发布。
48 std::shared_ptr<CarlaCameraInfoPublisherImpl> _impl_info; //指向内部实现的智能指针,用于管理相机信息的发布。
49 };
50}
51}
CarlaISCameraPublisher & operator=(const CarlaISCameraPublisher &)
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)
std::shared_ptr< CarlaCameraInfoPublisherImpl > _impl_info
void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify)
std::shared_ptr< CarlaISCameraPublisherImpl > _impl
void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const uint8_t *data)
CarlaISCameraPublisher(const char *ros_name="", const char *parent="")
void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds)
const std::string & parent() const
CARLA模拟器的主命名空间。
Definition Carla.cpp:139