38 #include <rc_genicam_api/config.h> 45 bool _color,
bool out1_filter, std::function<
void()>& sub_changed)
55 name =
"left/image_rect";
59 name =
"right/image_rect";
64 name = name +
"_color";
124 sensor_msgs::ImagePtr im = boost::make_shared<sensor_msgs::Image>();
129 im->header.stamp.sec = time / 1000000000ul;
130 im->header.stamp.nsec = time % 1000000000ul;
135 im->width =
static_cast<uint32_t
>(buffer->
getWidth(part));
136 im->height =
static_cast<uint32_t
>(buffer->
getHeight(part));
137 im->is_bigendian =
false;
139 bool stacked =
false;
141 if (im->height > im->width)
149 const uint8_t* ps =
static_cast<const uint8_t*
>(buffer->
getBase(part));
150 size_t pstep = im->width + buffer->
getXPadding(part);
154 pstep = (im->width >> 2) * 6 + buffer->
getXPadding(part);
156 else if (pixelformat ==
RGB8)
165 ps += pstep * im->height;
178 im->step = 3 * im->width *
sizeof(uint8_t);
180 im->data.resize(im->step * im->height);
181 uint8_t* pt =
reinterpret_cast<uint8_t*
>(&im->data[0]);
183 if (pixelformat ==
Mono8)
189 for (uint32_t k = 0; k < im->height; k++)
191 for (uint32_t i = 0; i < im->width; i += 4)
200 else if (pixelformat ==
RGB8)
202 for (uint32_t k = 0; k < im->height; k++)
204 for (uint32_t i = 0; i < im->width; i++)
218 im->step = im->width *
sizeof(uint8_t);
220 im->data.resize(im->step * im->height);
221 uint8_t* pt =
reinterpret_cast<uint8_t*
>(&im->data[0]);
223 if (pixelformat ==
Mono8)
225 for (uint32_t k = 0; k < im->height; k++)
227 for (uint32_t i = 0; i < im->width; i++)
237 for (uint32_t k = 0; k < im->height; k++)
241 for (uint32_t i = 0; i < im->width; i += 4)
253 else if (pixelformat ==
RGB8)
255 for (uint32_t k = 0; k < im->height; k++)
257 for (uint32_t i = 0; i < im->width; i++)
259 *pt++ =
static_cast<uint8_t
>((9798*ps[0]+19234*ps[1]+3736*ps[2]+16384)>>15);
Interface for all publishers relating to images, point clouds or other stereo-camera data...
bool used() override
Returns true if there are subscribers to the topic.
uint32_t getNumSubscribers() const
std::function< void()> sub_callback
image_transport::Publisher pub_out1_low
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
int64_t getInteger(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, int64_t *vmin=0, int64_t *vmax=0, bool exception=false, bool igncache=false)
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
size_t getWidth(std::uint32_t part) const
void requiresComponents(int &components, bool &color) override
Adds components and if color images are required to the given values.
bool setEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, const char *value, bool exception=false)
image_transport::Publisher pub
void convYCbCr411toQuadRGB(uint8_t rgb[12], const uint8_t *row, int i)
static const int ComponentIntensity
ImagePublisher(image_transport::ImageTransport &it, const std::string &frame_id, bool left, bool color, bool out1_filter, std::function< void()> &sub_changed)
size_t getHeight(std::uint32_t part) const
std::string getEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false)
uint64_t getTimestampNS() const
void publish(const sensor_msgs::Image &message) const
void * getBase(std::uint32_t part) const
void subChangedIt(const image_transport::SingleSubscriberPublisher &pub)
Called by publisher if subscription changed.
std::shared_ptr< GenApi::CNodeMapRef > nodemap
image_transport::Publisher pub_out1_high
size_t getXPadding(std::uint32_t part) const
static const int ComponentIntensityCombined