37 #include <rc_genicam_api/config.h> 44 std::function<
void()>& sub_changed)
92 else if (pixelformat ==
Error8)
101 std::shared_ptr<const rcg::Image> disp =
disp_list.
find(timestamp);
102 std::shared_ptr<const rcg::Image> err =
err_list.
find(timestamp);
106 if (disp->getWidth() == err->getWidth() && disp->getHeight() == err->getHeight())
110 sensor_msgs::ImagePtr im = boost::make_shared<sensor_msgs::Image>();
113 im->header.stamp.sec = timestamp / 1000000000ul;
114 im->header.stamp.nsec = timestamp % 1000000000ul;
119 im->width =
static_cast<uint32_t
>(disp->getWidth());
120 im->height =
static_cast<uint32_t
>(disp->getHeight());
124 size_t dpx = disp->getXPadding();
125 const uint8_t* dps = disp->getPixels();
127 size_t epx = err->getXPadding();
128 const uint8_t* eps = err->getPixels();
134 im->step = im->width *
sizeof(float);
136 im->data.resize(im->step * im->height);
137 float* pt =
reinterpret_cast<float*
>(&im->data[0]);
141 bool bigendian = disp->isBigEndian();
143 for (uint32_t k = 0; k < im->height; k++)
145 for (uint32_t i = 0; i < im->width; i++)
151 d =
scale * ((dps[0] << 8) | dps[1]);
155 d =
scale * ((dps[1] << 8) | dps[0]);
162 *pt++ = *eps * s / (d * d);
166 *pt++ = std::numeric_limits<float>::infinity();
182 ROS_ERROR_STREAM(
"Size of disparity and error images differ: " << disp->getWidth() <<
"x" << disp->getHeight()
183 <<
" != " << err->getWidth() <<
"x" 184 << err->getHeight());
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
void requiresComponents(int &components, bool &color) override
Adds components and if color images are required to the given values.
std::function< void()> sub_callback
bool used() override
Returns true if there are subscribers to the topic.
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
static const int ComponentError
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 removeOld(uint64_t timestamp)
void publish(const boost::shared_ptr< M > &message) const
const std::string TYPE_32FC1
uint64_t getTimestampNS() const
void add(const std::shared_ptr< const Image > &image)
ErrorDepthPublisher(ros::NodeHandle &nh, const std::string &frame_id, std::function< void()> &sub_changed)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double getFloat(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, double *vmin=0, double *vmax=0, bool exception=false, bool igncache=false)
std::shared_ptr< const Image > find(uint64_t timestamp) const
#define ROS_ERROR_STREAM(args)
std::shared_ptr< GenApi::CNodeMapRef > nodemap
uint32_t getNumSubscribers() const