5#define _GLIBCXX_USE_CXX11_ABI 0
12 struct CarlaNormalsCameraPublisherImpl;
13 struct CarlaCameraInfoPublisherImpl;
29 void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width,
float fov,
bool do_rectify);
35 void SetImageData(int32_t seconds, uint32_t nanoseconds,
size_t height,
size_t width,
const uint8_t* data);
39 const char*
type()
const override {
return "normals camera"; }
48 void SetInfoRegionOfInterest( uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width,
bool do_rectify);
50 void SetData(int32_t seconds, uint32_t nanoseconds,
size_t height,
size_t width, std::vector<uint8_t>&& data);
53 std::shared_ptr<CarlaNormalsCameraPublisherImpl>
_impl;
54 std::shared_ptr<CarlaCameraInfoPublisherImpl>
_impl_info;
bool PublishImage()
发布图像数据
const char * type() const override
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。
bool InitImage()
初始化图像发布者。
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