37 #include <rc_genicam_api/config.h> 70 sensor_msgs::ImagePtr im = boost::make_shared<sensor_msgs::Image>();
75 im->header.stamp.sec = time / 1000000000ul;
76 im->header.stamp.nsec = time % 1000000000ul;
81 im->width =
static_cast<uint32_t
>(buffer->
getWidth(part));
82 im->height =
static_cast<uint32_t
>(buffer->
getHeight(part));
87 const uint8_t* ps =
static_cast<const uint8_t*
>(buffer->
getBase(part));
93 im->step = im->width *
sizeof(float);
95 im->data.resize(im->step * im->height);
96 float* pt =
reinterpret_cast<float*
>(&im->data[0]);
112 float s = f * t / scale;
114 for (uint32_t k = 0; k < im->height; k++)
116 for (uint32_t i = 0; i < im->width; i++)
122 d = (ps[0] << 8) | ps[1];
126 d = (ps[1] << 8) | ps[0];
131 if (d != 0 && d != invalid)
137 *pt++ = std::numeric_limits<float>::quiet_NaN();
Interface for all publishers relating to images, point clouds or other stereo-camera data...
bool getBoolean(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false, bool igncache=false)
static const int ComponentDisparity
std::function< void()> sub_callback
void requiresComponents(int &components, bool &color) override
Adds components and if color images are required to the given values.
size_t getWidth(std::uint32_t part) const
bool setEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, const char *value, bool exception=false)
void subChanged(const ros::SingleSubscriberPublisher &pub)
Called by publisher if subscription changed.
void publish(const boost::shared_ptr< M > &message) const
bool used() override
Returns true if there are subscribers to the topic.
size_t getHeight(std::uint32_t part) const
const std::string TYPE_32FC1
uint64_t getTimestampNS() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
DepthPublisher(ros::NodeHandle &nh, const std::string &frame_id, std::function< void()> &sub_changed)
double getFloat(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, double *vmin=0, double *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.
void * getBase(std::uint32_t part) const
std::shared_ptr< GenApi::CNodeMapRef > nodemap
uint32_t getNumSubscribers() const
size_t getXPadding(std::uint32_t part) const