50 pub = nh.
advertise<sensor_msgs::Image>(
"error_depth", 1);
68 else if (pixelformat ==
Error8)
77 std::shared_ptr<const rcg::Image> disp =
disp_list.
find(timestamp);
78 std::shared_ptr<const rcg::Image> err =
err_list.
find(timestamp);
82 if (disp->getWidth() == err->getWidth() && disp->getHeight() == err->getHeight())
86 sensor_msgs::ImagePtr im = boost::make_shared<sensor_msgs::Image>();
88 const uint64_t freq = 1000000000ul;
90 im->header.seq =
seq++;
91 im->header.stamp.sec = timestamp / freq;
92 im->header.stamp.nsec = timestamp - freq * im->header.stamp.sec;
97 im->width =
static_cast<uint32_t
>(disp->getWidth());
98 im->height =
static_cast<uint32_t
>(disp->getHeight());
102 size_t dpx = disp->getXPadding();
103 const uint8_t* dps = disp->getPixels();
105 size_t epx = err->getXPadding();
106 const uint8_t* eps = err->getPixels();
112 im->step = im->width *
sizeof(float);
114 im->data.resize(im->step * im->height);
115 float* pt =
reinterpret_cast<float*
>(&im->data[0]);
117 float s =
scale *
f * im->width *
t;
119 bool bigendian = disp->isBigEndian();
121 for (uint32_t k = 0; k < im->height; k++)
123 for (uint32_t i = 0; i < im->width; i++)
129 d =
scale * ((dps[0] << 8) | dps[1]);
133 d =
scale * ((dps[1] << 8) | dps[0]);
140 *pt++ = *eps * s / (d * d);
144 *pt++ = std::numeric_limits<float>::infinity();
160 ROS_ERROR_STREAM(
"Size of disparity and error images differ: " << disp->getWidth() <<
"x" << disp->getHeight()
161 <<
" != " << err->getWidth() <<
"x" 162 << err->getHeight());
Interface for all publishers relating to images, point clouds or other stereo-camera data...
void publish(const boost::shared_ptr< M > &message) const
std::shared_ptr< const Image > find(uint64_t timestamp) const
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.
void removeOld(uint64_t timestamp)
const std::string TYPE_32FC1
void add(const std::shared_ptr< const Image > &image)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint64_t getTimestampNS() const
uint32_t getNumSubscribers() const
#define ROS_ERROR_STREAM(args)
ErrorDepthPublisher(ros::NodeHandle &nh, const std::string &frame_id_prefix, double f, double t, double scale)
Initialization of publisher for depth errors.