6#define _GLIBCXX_USE_CXX11_ABI 0
17struct CarlaOpticalFlowCameraPublisherImpl;
18struct CarlaCameraInfoPublisherImpl;
41 void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width,
float fov,
bool do_rectify);
48 void SetImageData(int32_t seconds, uint32_t nanoseconds,
size_t height,
size_t width,
const float* data);
52 const char*
type()
const override {
return "optical flow camera"; }
65 void SetInfoRegionOfInterest(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width,
bool do_rectify);
67 void SetData(int32_t seconds, uint32_t nanoseconds,
size_t height,
size_t width, std::vector<uint8_t>&& data);
71 std::shared_ptr<CarlaOpticalFlowCameraPublisherImpl>
_impl;
73 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)
初始化摄像头信息数据。
CarlaOpticalFlowCameraPublisher & operator=(const CarlaOpticalFlowCameraPublisher &)
赋值运算符重载
void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const float *data)
设置图像数据,将光学流数据转换为RGBA图像数据
void SetInfoRegionOfInterest(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify)
设置感兴趣区域(ROI)信息
bool InitImage()
初始化图像相关的资源。
bool HasBeenInitialized() const
检查类是否已经被初始化。
void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds)
设置相机信息数据的时间戳
const char * type() const override
bool InitInfo()
初始化信息并设置CarlaOpticalFlowCameraPublisher的相关参数。
bool PublishImage()
发布图像数据。
CarlaOpticalFlowCameraPublisher(const char *ros_name="", const char *parent="")
CarlaOpticalFlowCameraPublisher类的构造函数
void SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector< uint8_t > &&data)
设置图像数据
std::shared_ptr< CarlaOpticalFlowCameraPublisherImpl > _impl
~CarlaOpticalFlowCameraPublisher()
CarlaOpticalFlowCameraPublisher类的析构函数
std::shared_ptr< CarlaCameraInfoPublisherImpl > _impl_info
const std::string & parent() const