37 #include <rc_genicam_api/config.h> 44 std::function<
void()>& sub_changed)
48 pub = nh.
advertise<stereo_msgs::DisparityImage>(
"disparity", 1,
72 stereo_msgs::DisparityImagePtr p = boost::make_shared<stereo_msgs::DisparityImage>();
77 p->header.stamp.sec = time / 1000000000ul;
78 p->header.stamp.nsec = time % 1000000000ul;
89 mindepth = std::max(mindepth, 2.5*t);
90 int disprange =
static_cast<int>(std::ceil(f*t/mindepth));
94 p->image.header = p->header;
95 p->image.width =
static_cast<uint32_t
>(buffer->
getWidth(part));
96 p->image.height =
static_cast<uint32_t
>(buffer->
getHeight(part));
99 p->image.step = p->image.width *
sizeof(float);
102 const uint8_t* ps =
static_cast<const uint8_t*
>(buffer->
getBase(part));
106 p->image.data.resize(p->image.step * p->image.height);
108 float* pt =
reinterpret_cast<float*
>(&p->image.data[0]);
113 for (uint32_t k = 0; k < p->image.height; k++)
117 for (uint32_t i = 0; i < p->image.width; i++)
119 uint16_t
d = (ps[0] << 8) | ps[1];
126 dmax = std::max(dmax, *pt);
135 for (uint32_t i = 0; i < p->image.width; i++)
137 uint16_t
d = (ps[1] << 8) | ps[0];
144 dmax = std::max(dmax, *pt);
157 p->valid_window.x_offset = 0;
158 p->valid_window.y_offset = 0;
159 p->valid_window.width = p->image.width;
160 p->valid_window.height = p->image.height;
161 p->min_disparity = 0;
162 p->max_disparity = std::max(dmax, static_cast<float>(disprange));
Interface for all publishers relating to images, point clouds or other stereo-camera data...
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
static const int ComponentDisparity
bool used() override
Returns true if there are subscribers to the topic.
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
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)
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 * getBase(std::uint32_t part) const
DisparityPublisher(ros::NodeHandle &nh, const std::string &frame_id, std::function< void()> &sub_changed)
std::shared_ptr< GenApi::CNodeMapRef > nodemap
uint32_t getNumSubscribers() const
size_t getXPadding(std::uint32_t part) const