2 #include <boost/shared_ptr.hpp> 3 #include <boost/assign.hpp> 11 #include <jsk_recognition_msgs/SparseImage.h> 28 void imageCallback(
const jsk_recognition_msgs::SparseImageConstPtr& msg){
29 do_work(msg, msg->header.frame_id);
32 void do_work(
const jsk_recognition_msgs::SparseImageConstPtr& msg,
const std::string input_frame_from_msg){
35 _img_ptr->header.stamp = msg->header.stamp;
36 _img_ptr->header.frame_id = input_frame_from_msg;
37 _img_ptr->width = msg->width;
38 _img_ptr->height = msg->height;
39 _img_ptr->step = msg->width;
40 _img_ptr->encoding = enc::MONO8;
41 if (!_img_ptr->data.empty()) _img_ptr->data.clear();
44 bool useData32 =
false;
45 int length = msg->data16.size();
48 length = msg->data32.size();
51 _img_ptr->data.resize(_img_ptr->width * _img_ptr->height);
53 for (
int i = 0; i < length; ++i){
56 uint32_t
pos = msg->data32[i];
57 x = (uint16_t)(pos >> 16);
60 uint16_t
pos = msg->data16[i];
61 x = (uint16_t)(pos >> 8);
62 y = (uint16_t)(pos & (uint8_t)-1);
64 _img_ptr->data[y * _img_ptr->width + x] = 255;
88 if (_subscriber_count++ == 0) {
95 if (_subscriber_count == 0) {
103 _img_ptr.reset(
new sensor_msgs::Image());
105 _subscriber_count = 0;
#define NODELET_ERROR(...)
ros::Subscriber _spr_img_sub
void do_work(const jsk_recognition_msgs::SparseImageConstPtr &msg, const std::string input_frame_from_msg)
sensor_msgs::ImagePtr _img_ptr
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
boost::shared_ptr< image_transport::ImageTransport > _it
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void imageCallback(const jsk_recognition_msgs::SparseImageConstPtr &msg)
std::vector< std::string > V_string
void disconnectCb(const image_transport::SingleSubscriberPublisher &)
void publish(const sensor_msgs::Image &message) const
ros::NodeHandle & getNodeHandle() const
void connectCb(const image_transport::SingleSubscriberPublisher &ssp)
PLUGINLIB_EXPORT_CLASS(jsk_perception::SparseImageDecoder, nodelet::Nodelet)
image_transport::Publisher _img_pub
#define NODELET_DEBUG(...)