Image message class that is interoperable with sensor_msgs/Image but uses a HImage representation for the image data. More...
#include <halcon_image.h>
| Public Member Functions | |
| sensor_msgs::ImagePtr | toImageMsg () const | 
| Convert this message to a ROS sensor_msgs::Image message.  More... | |
| void | toImageMsg (sensor_msgs::Image &ros_image) const | 
| Copy the message data to a ROS sensor_msgs::Image message.  More... | |
| ~HalconImage () | |
| Public Attributes | |
| std::string | encoding | 
| std_msgs::Header | header | 
| HalconCpp::HImage * | image | 
Image message class that is interoperable with sensor_msgs/Image but uses a HImage representation for the image data.
Definition at line 41 of file halcon_image.h.
| halcon_bridge::HalconImage::~HalconImage | ( | ) | 
Definition at line 87 of file halcon_image.cpp.
| sensor_msgs::ImagePtr halcon_bridge::HalconImage::toImageMsg | ( | ) | const | 
Convert this message to a ROS sensor_msgs::Image message.
The returned sensor_msgs::Image message contains a copy of the image data.
Definition at line 91 of file halcon_image.cpp.
| void halcon_bridge::HalconImage::toImageMsg | ( | sensor_msgs::Image & | ros_image | ) | const | 
Copy the message data to a ROS sensor_msgs::Image message.
This overload is intended mainly for aggregate messages such as stereo_msgs::DisparityImage, which contains a sensor_msgs::Image as a data member.
Definition at line 99 of file halcon_image.cpp.
| std::string halcon_bridge::HalconImage::encoding | 
Definition at line 44 of file halcon_image.h.
| std_msgs::Header halcon_bridge::HalconImage::header | 
Definition at line 43 of file halcon_image.h.
| HalconCpp::HImage* halcon_bridge::HalconImage::image | 
Definition at line 45 of file halcon_image.h.