Go to the documentation of this file.
   62     sensor_msgs::ImagePtr im = boost::make_shared<sensor_msgs::Image>();
 
   64     const uint64_t freq = 1000000000ul;
 
   67     im->header.seq = 
seq++;
 
   68     im->header.stamp.sec = time / freq;
 
   69     im->header.stamp.nsec = time - freq * im->header.stamp.sec;
 
   74     im->width = 
static_cast<uint32_t
>(buffer->
getWidth(part));
 
   75     im->height = 
static_cast<uint32_t
>(buffer->
getHeight(part));
 
   80     const uint8_t* ps = 
static_cast<const uint8_t*
>(buffer->
getBase(part));
 
   86     im->step = im->width * 
sizeof(float);
 
   88     im->data.resize(im->step * im->height);
 
   89     float* pt = 
reinterpret_cast<float*
>(&im->data[0]);
 
   93     float s = 
scale * im->width;
 
   95     for (uint32_t k = 0; k < im->height; k++)
 
   97       for (uint32_t i = 0; i < im->width; i++)
 
  103           d = (ps[0] << 8) | ps[1];
 
  107           d = (ps[1] << 8) | ps[0];
 
  118           *pt++ = std::numeric_limits<float>::quiet_NaN();
 
  
size_t getXPadding(std::uint32_t part) const
bool used() override
Returns true if there are subscribers to the topic.
uint64_t getTimestampNS() const
void * getBase(std::uint32_t part) const
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
size_t getHeight(std::uint32_t part) const
Interface for all publishers relating to images, point clouds or other stereo-camera data.
const std::string TYPE_32FC1
size_t getWidth(std::uint32_t part) const
uint32_t getNumSubscribers() const
DepthPublisher(ros::NodeHandle &nh, const std::string &frame_id_prefix, double f, double t, double scale)
Initialization of publisher.
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
rc_visard_driver
Author(s): Heiko Hirschmueller 
, Christian Emmerich , Felix Ruess 
autogenerated on Sun May 15 2022 02:25:43