halcon_pointcloud.h
Go to the documentation of this file.
1 
18 #include <sensor_msgs/PointCloud2.h>
19 #include <halconcpp/HalconCpp.h>
20 #include <stdexcept>
21 
22 namespace halcon_bridge {
23 
24 
25 
26 
28 
30 
37  public:
38  std_msgs::Header header;
39  HalconCpp::HTuple curvature;
40  HalconCpp::HObjectModel3D *model;
41 
43 
49  sensor_msgs::PointCloud2Ptr toPointcloudMsg() const;
50 
51 
56  void toPointcloudMsg(sensor_msgs::PointCloud2& ros_pointcloud) const;
57  };
58 
59 
67  HalconPointcloudPtr toHalconCopy(const sensor_msgs::PointCloud2ConstPtr& source);
68 
69 
77  HalconPointcloudPtr toHalconCopy(const sensor_msgs::PointCloud2& source);
78 
79 
80 
81 }
82 
boost::shared_ptr< HalconPointcloud > HalconPointcloudPtr
HalconImagePtr toHalconCopy(const sensor_msgs::ImageConstPtr &source)
Convert a sensor_msgs::Image message to a Halcon-compatible HImage, copying the image data...
sensor_msgs::PointCloud2Ptr toPointcloudMsg() const
Convert this message to a ROS sensor_msgs::PointCloud2 message.
HalconCpp::HObjectModel3D * model
PointCloud message class that is interoperable with sensor_msgs/PointCloud2 but uses a HObjectModel3D...


asr_halcon_bridge
Author(s): Allgeyer Tobias
autogenerated on Fri Jun 19 2020 03:54:32