37 #include <rc_genicam_api/config.h> 39 #include <sensor_msgs/PointCloud2.h> 77 uint64_t tolerance_ns;
79 if (out1_mode ==
"ExposureAlternateActive")
81 tolerance_ns =
static_cast<uint64_t
>(1.0 * 1000000000ull);
97 if (tolerance_ns > 0 && out1)
125 std::shared_ptr<const rcg::Image>
left =
left_list.
find(timestamp, tolerance_ns);
126 std::shared_ptr<const rcg::Image> disp =
disp_list.
find(timestamp, tolerance_ns);
139 uint32_t lw = left->getWidth();
140 uint32_t lh = left->getHeight();
147 int ds = (lw + disp->getWidth() - 1) / disp->getWidth();
149 if ((lw + ds - 1) / ds == disp->getWidth() && (lh + ds - 1) / ds == disp->getHeight())
153 sensor_msgs::PointCloud2Ptr p = boost::make_shared<sensor_msgs::PointCloud2>();
156 p->header.stamp.sec = timestamp / 1000000000ul;
157 p->header.stamp.nsec = timestamp % 1000000000ul;
169 p->fields[0].name =
"x";
170 p->fields[0].offset = 0;
171 p->fields[0].count = 1;
172 p->fields[0].datatype = sensor_msgs::PointField::FLOAT32;
173 p->fields[1].name =
"y";
174 p->fields[1].offset = 4;
175 p->fields[1].count = 1;
176 p->fields[1].datatype = sensor_msgs::PointField::FLOAT32;
177 p->fields[2].name =
"z";
178 p->fields[2].offset = 8;
179 p->fields[2].count = 1;
180 p->fields[2].datatype = sensor_msgs::PointField::FLOAT32;
181 p->fields[3].name =
"rgb";
182 p->fields[3].offset = 12;
183 p->fields[3].count = 1;
184 p->fields[3].datatype = sensor_msgs::PointField::FLOAT32;
187 p->row_step = p->point_step * p->width;
191 p->data.resize(p->row_step * p->height);
192 float* pd =
reinterpret_cast<float*
>(&p->data[0]);
196 const uint8_t* dps = disp->getPixels();
197 size_t dstep = disp->getWidth() *
sizeof(uint16_t) + disp->getXPadding();
201 bool bigendian = disp->isBigEndian();
203 for (uint32_t k = 0; k < p->height; k++)
205 for (uint32_t i = 0; i < p->width; i++)
215 d =
scale * ((dps[j] << 8) | dps[j + 1]);
219 d =
scale * ((dps[j + 1] << 8) | dps[j]);
228 pd[0] = (i + 0.5 - disp->getWidth() / 2.0) *
t / d;
229 pd[1] = (k + 0.5 - disp->getHeight() / 2.0) *
t / d;
237 uint8_t* bgra =
reinterpret_cast<uint8_t*
>(pd + 3);
246 for (
int i = 0; i < 4; i++)
248 pd[i] = std::numeric_limits<float>::quiet_NaN();
264 ROS_ERROR_STREAM(
"Size of left and disparity image must differ only by an integer factor: " 265 << left->getWidth() <<
"x" << left->getHeight() <<
" != " << disp->getWidth() <<
"x" 266 << disp->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)
Points2Publisher(ros::NodeHandle &nh, const std::string &frame_id, std::function< void()> &sub_changed)
static const int ComponentDisparity
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
std::function< void()> sub_callback
bool used() override
Returns true if there are subscribers to the topic.
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)
bool setEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, const char *value, bool exception=false)
static const int ComponentIntensity
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
LOG4CPP_EXPORT CategoryStream & left(CategoryStream &os)
std::string getEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false)
uint64_t getTimestampNS() const
void add(const std::shared_ptr< const Image > &image)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
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
void getColor(uint8_t rgb[3], const std::shared_ptr< const Image > &img, uint32_t ds, uint32_t i, uint32_t k)
void requiresComponents(int &components, bool &color) override
Adds components and if color images are required to the given values.