43 std::function<
void()>& sub_changed)
70 sensor_msgs::ImagePtr im = boost::make_shared<sensor_msgs::Image>();
75 im->header.stamp.sec = time / 1000000000ul;
76 im->header.stamp.nsec = time % 1000000000ul;
81 im->width =
static_cast<uint32_t
>(buffer->
getWidth(part));
82 im->height =
static_cast<uint32_t
>(buffer->
getHeight(part));
87 const uint8_t* ps =
static_cast<const uint8_t*
>(buffer->
getBase(part));
93 im->step = im->width *
sizeof(float);
95 im->data.resize(im->step * im->height);
96 float* pt =
reinterpret_cast<float*
>(&im->data[0]);
98 float scale = 1.0f / 255.0f;
100 for (uint32_t k = 0; k < im->height; k++)
102 for (uint32_t i = 0; i < im->width; i++)
104 *pt++ = scale * *ps++;
Interface for all publishers relating to images, point clouds or other stereo-camera data...
std::function< void()> sub_callback
ConfidencePublisher(ros::NodeHandle &nh, const std::string &frame_id, std::function< void()> &sub_changed)
size_t getWidth(std::uint32_t part) const
static const int ComponentConfidence
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)
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
void * getBase(std::uint32_t part) const
uint32_t getNumSubscribers() const
bool used() override
Returns true if there are subscribers to the topic.
size_t getXPadding(std::uint32_t part) const
void requiresComponents(int &components, bool &color) override
Adds components and if color images are required to the given values.