38 #include <sensor_msgs/PointCloud2.h> 52 pub = nh.
advertise<sensor_msgs::PointCloud2>(
"points2", 1);
59 tolerance_ns =
static_cast<uint64_t
>(0.050 * 1000000000ull);
74 publish(buffer, part, pixelformat,
false);
113 ROS_DEBUG_STREAM(
"Cannot find left image for disparity image. Internal queue size to small.");
117 ROS_DEBUG_STREAM(
"Cannot find left image for disparity image. Left image possibly dropped.");
125 uint32_t lw = left->getWidth();
126 uint32_t lh = left->getHeight();
133 int ds = (lw + disp->getWidth() - 1) / disp->getWidth();
135 if ((lw + ds - 1) / ds == disp->getWidth() && (lh + ds - 1) / ds == disp->getHeight())
139 sensor_msgs::PointCloud2Ptr p = boost::make_shared<sensor_msgs::PointCloud2>();
141 const uint64_t freq = 1000000000ul;
143 p->header.seq =
seq++;
144 p->header.stamp.sec = timestamp / freq;
145 p->header.stamp.nsec = timestamp - freq * p->header.stamp.sec;
157 p->fields[0].name =
"x";
158 p->fields[0].offset = 0;
159 p->fields[0].count = 1;
160 p->fields[0].datatype = sensor_msgs::PointField::FLOAT32;
161 p->fields[1].name =
"y";
162 p->fields[1].offset = 4;
163 p->fields[1].count = 1;
164 p->fields[1].datatype = sensor_msgs::PointField::FLOAT32;
165 p->fields[2].name =
"z";
166 p->fields[2].offset = 8;
167 p->fields[2].count = 1;
168 p->fields[2].datatype = sensor_msgs::PointField::FLOAT32;
169 p->fields[3].name =
"rgb";
170 p->fields[3].offset = 12;
171 p->fields[3].count = 1;
172 p->fields[3].datatype = sensor_msgs::PointField::FLOAT32;
175 p->row_step = p->point_step * p->width;
179 p->data.resize(p->row_step * p->height);
180 float* pd =
reinterpret_cast<float*
>(&p->data[0]);
184 const uint8_t* dps = disp->getPixels();
185 size_t dstep = disp->getWidth() *
sizeof(uint16_t) + disp->getXPadding();
189 float ff =
f * disp->getWidth();
191 bool bigendian = disp->isBigEndian();
193 for (uint32_t k = 0; k < p->height; k++)
195 for (uint32_t i = 0; i < p->width; i++)
205 d =
scale * ((dps[j] << 8) | dps[j + 1]);
209 d =
scale * ((dps[j + 1] << 8) | dps[j]);
218 pd[0] = (i + 0.5 - disp->getWidth() / 2.0) *
t / d;
219 pd[1] = (k + 0.5 - disp->getHeight() / 2.0) *
t / d;
227 uint8_t* bgra =
reinterpret_cast<uint8_t*
>(pd + 3);
236 for (
int i = 0; i < 4; i++)
238 pd[i] = std::numeric_limits<float>::quiet_NaN();
254 ROS_ERROR_STREAM(
"Size of left and disparity image must differ only by an integer factor: " 255 << left->getWidth() <<
"x" << left->getHeight() <<
" != " << disp->getWidth() <<
"x" 256 << disp->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
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
bool used() override
Returns true if there are subscribers to the topic.
void removeOld(uint64_t timestamp)
LOG4CPP_EXPORT CategoryStream & left(CategoryStream &os)
void add(const std::shared_ptr< const Image > &image)
void setOut1Alternate(bool alternate)
uint64_t getOldestTime() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void getColor(uint8_t rgb[3], const std::shared_ptr< const rcg::Image > &img, uint32_t ds, uint32_t i, uint32_t k)
#define ROS_DEBUG_STREAM(args)
Points2Publisher(ros::NodeHandle &nh, const std::string &frame_id_prefix, double f, double t, double scale)
Initialization of publisher for depth errors.
uint64_t getTimestampNS() const
uint32_t getNumSubscribers() const
#define ROS_ERROR_STREAM(args)