halcon_pointcloud.h
Go to the documentation of this file.
00001 
00018 #include <sensor_msgs/PointCloud2.h>
00019 #include <HalconCpp.h>
00020 #include <stdexcept>
00021 
00022 namespace halcon_bridge {
00023 
00024 
00025 
00026 
00027     class HalconPointcloud;
00028 
00029     typedef boost::shared_ptr<HalconPointcloud> HalconPointcloudPtr;
00030 
00036     class HalconPointcloud {
00037         public:
00038             std_msgs::Header header;
00039             HalconCpp::HTuple curvature;
00040             HalconCpp::HObjectModel3D *model;
00041 
00042             ~HalconPointcloud();
00043 
00049             sensor_msgs::PointCloud2Ptr toPointcloudMsg() const;
00050 
00051 
00056             void toPointcloudMsg(sensor_msgs::PointCloud2& ros_pointcloud) const;
00057     };
00058 
00059 
00067     HalconPointcloudPtr toHalconCopy(const sensor_msgs::PointCloud2ConstPtr& source);
00068 
00069 
00077     HalconPointcloudPtr toHalconCopy(const sensor_msgs::PointCloud2& source);
00078 
00079 
00080 
00081 }
00082 


asr_halcon_bridge
Author(s): Allgeyer Tobias
autogenerated on Thu Jun 6 2019 18:32:11