CARLA
 
载入中...
搜索中...
未找到
CarlaSSCameraPublisher.h
浏览该文件的文档.
1// This work is licensed under the terms of the MIT license.
2// For a copy, see <https://opensource.org/licenses/MIT>.
3
4// ָʾͷļֻһ
5#pragma once
6// GLIBCXX ʹ C++11 ABI ĺ
7#define _GLIBCXX_USE_CXX11_ABI 0
8
9// ڴ
10#include <memory>
11#include <vector>
12
13// CarlaPublisher Ķ
14#include "CarlaPublisher.h"
15
16namespace carla {
17namespace ros2 {
18
19 // ǰṹ CarlaSSCameraPublisherImpl CarlaCameraInfoPublisherImpl
20 struct CarlaSSCameraPublisherImpl;
21 struct CarlaCameraInfoPublisherImpl;
22
23 // CarlaSSCameraPublisher ̳࣬ CarlaPublisher
25 public:
26 // 캯 ROS ƺ͸ΪĬΪַ
27 CarlaSSCameraPublisher(const char* ros_name = "", const char* parent = "");
28 //
30 // 캯
32 // ֵ
34 // ƶ캯
36 // ƶֵ
38
39 // ʼزֵָʾǷɹ
40 bool Init();
41 // ʼϢݣƫͼߴӳǵȲ
42 void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify);
43 // ݵĺزֵָʾǷɹ
44 bool Publish();
45
46 // Ƿѳʼ
47 bool HasBeenInitialized() const;
48 // ͼݵĺʱͼ
49 void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const uint8_t* data);
50 // Ϣݵĺʱ
51 void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds);
52 // ǻ type() ش
53 const char* type() const override { return "semantic segmentation"; }
54
55 private:
56 // ʼͼݵ˽кزֵָʾǷɹ
57 bool InitImage();
58 // ʼϢ˽кزֵָʾǷɹ
59 bool InitInfo();
60 // ͼ˽кزֵָʾǷɹ
61 bool PublishImage();
62 // Ϣ˽кزֵָʾǷɹ
63 bool PublishInfo();
64
65 // øȤϢƫߴǷУ
66 void SetInfoRegionOfInterest( uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify);
67 // ڲúʹֵ÷ʽ
68 void SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector<uint8_t>&& data);
69
70 private:
71 // ʹָ CarlaSSCameraPublisherImpl CarlaCameraInfoPublisherImpl ʵ
72 std::shared_ptr<CarlaSSCameraPublisherImpl> _impl;
73 std::shared_ptr<CarlaCameraInfoPublisherImpl> _impl_info;
74 };
75}// namespace ros2
76}// namespace carla
const std::string & parent() const
bool HasBeenInitialized() const
检查CarlaSSCameraPublisher是否已初始化。
std::shared_ptr< CarlaSSCameraPublisherImpl > _impl
CarlaSSCameraPublisher & operator=(const CarlaSSCameraPublisher &)
赋值运算符重载
CarlaSSCameraPublisher(const char *ros_name="", const char *parent="")
CarlaSSCameraPublisher类的构造函数
void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds)
设置相机信息数据的时间戳
void SetInfoRegionOfInterest(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify)
设置感兴趣区域的信息
void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const uint8_t *data)
设置图像数据
std::shared_ptr< CarlaCameraInfoPublisherImpl > _impl_info
bool InitInfo()
初始化CarlaSSCameraPublisher的信息
void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify)
初始化相机信息数据
void SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector< uint8_t > &&data)
设置图像数据
~CarlaSSCameraPublisher()
CarlaSSCameraPublisher类的析构函数
CARLA模拟器的主命名空间。
Definition Carla.cpp:139