sparse_image_decoder.cpp
Go to the documentation of this file.
1 #include <stdint.h>
2 #include <boost/shared_ptr.hpp>
3 #include <boost/assign.hpp>
4 #include <vector>
5 #include <iostream>
6 
7 #include <nodelet/nodelet.h>
8 #include <jsk_topic_tools/log_utils.h>
11 #include <jsk_recognition_msgs/SparseImage.h>
12 
13 
15 
16 namespace jsk_perception {
18 {
21 
22  sensor_msgs::ImagePtr _img_ptr;
23 
27 
28  void imageCallback(const jsk_recognition_msgs::SparseImageConstPtr& msg){
29  do_work(msg, msg->header.frame_id);
30  }
31 
32  void do_work(const jsk_recognition_msgs::SparseImageConstPtr& msg, const std::string input_frame_from_msg){
33  try {
34 
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();
42 
43  // check if uint16 array needed
44  bool useData32 = false;
45  int length = msg->data16.size();
46  if (length <= 0) {
47  useData32 = true;
48  length = msg->data32.size();
49  NODELET_DEBUG("use data32 array");
50  }
51  _img_ptr->data.resize(_img_ptr->width * _img_ptr->height);
52  // decode sparse image -> image
53  for (int i = 0; i < length; ++i){
54  uint16_t x, y;
55  if (useData32) {
56  uint32_t pos = msg->data32[i];
57  x = (uint16_t)(pos >> 16);
58  y = (uint16_t)pos;
59  } else {
60  uint16_t pos = msg->data16[i];
61  x = (uint16_t)(pos >> 8);
62  y = (uint16_t)(pos & (uint8_t)-1);
63  }
64  _img_ptr->data[y * _img_ptr->width + x] = 255;
65  }
66 
67  // publish image message
69  } // end of try
70  catch (...) {
71  NODELET_ERROR("making sparse image error");
72  }
73  } // end of do_work function
74 
75  void subscribe() {
76  NODELET_DEBUG("Subscribing to image topic.");
77  _spr_img_sub = _nh.subscribe("sparse_image", 3, &SparseImageDecoder::imageCallback, this);
78  ros::V_string names = boost::assign::list_of("sparse_image");
79  jsk_topic_tools::warnNoRemap(names);
80  }
81 
82  void unsubscribe() {
83  NODELET_DEBUG("Unsubscribing from image topic.");
85  }
86 
88  if (_subscriber_count++ == 0) {
89  subscribe();
90  }
91  }
92 
95  if (_subscriber_count == 0) {
96  unsubscribe();
97  }
98  }
99 
100 public:
101  void onInit() {
102  _nh = getNodeHandle();
103  _img_ptr.reset(new sensor_msgs::Image());
105  _subscriber_count = 0;
108  _img_pub = image_transport::ImageTransport(ros::NodeHandle(_nh, "sparse")).advertise("image_decoded", 1, connect_cb, disconnect_cb);
109  } // end of onInit function
110 }; // end of SparseImageDecoder class definition
111 } // end of jsk_perception namespace
112 
sensor_msgs::image_encodings
x
x
NODELET_ERROR
#define NODELET_ERROR(...)
msg
msg
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
image_encodings.h
image_transport::ImageTransport
boost::shared_ptr< image_transport::ImageTransport >
i
int i
_1
boost::arg< 1 > _1
ros::Subscriber::shutdown
void shutdown()
jsk_perception::SparseImageDecoder::disconnectCb
void disconnectCb(const image_transport::SingleSubscriberPublisher &)
Definition: sparse_image_decoder.cpp:93
image_transport::ImageTransport::advertise
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
jsk_perception::SparseImageDecoder::_img_pub
image_transport::Publisher _img_pub
Definition: sparse_image_decoder.cpp:19
class_list_macros.h
jsk_perception
Definition: add_mask_image.h:48
jsk_perception::SparseImageDecoder::imageCallback
void imageCallback(const jsk_recognition_msgs::SparseImageConstPtr &msg)
Definition: sparse_image_decoder.cpp:28
jsk_perception::SparseImageDecoder
Definition: sparse_image_decoder.cpp:17
jsk_perception::SparseImageDecoder::_subscriber_count
int _subscriber_count
Definition: sparse_image_decoder.cpp:26
jsk_perception::SparseImageDecoder::connectCb
void connectCb(const image_transport::SingleSubscriberPublisher &ssp)
Definition: sparse_image_decoder.cpp:87
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_perception::SparseImageDecoder, nodelet::Nodelet)
jsk_perception::SparseImageDecoder::subscribe
void subscribe()
Definition: sparse_image_decoder.cpp:75
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
jsk_perception::SparseImageDecoder::_spr_img_sub
ros::Subscriber _spr_img_sub
Definition: sparse_image_decoder.cpp:20
image_transport::SingleSubscriberPublisher
image_transport.h
jsk_perception::SparseImageDecoder::_it
boost::shared_ptr< image_transport::ImageTransport > _it
Definition: sparse_image_decoder.cpp:24
nodelet::Nodelet
nodelet.h
image_transport::Publisher
jsk_perception::SparseImageDecoder::onInit
void onInit()
Definition: sparse_image_decoder.cpp:101
length
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
jsk_perception::SparseImageDecoder::do_work
void do_work(const jsk_recognition_msgs::SparseImageConstPtr &msg, const std::string input_frame_from_msg)
Definition: sparse_image_decoder.cpp:32
image_transport::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ros::V_string
std::vector< std::string > V_string
jsk_perception::SparseImageDecoder::_nh
ros::NodeHandle _nh
Definition: sparse_image_decoder.cpp:25
jsk_perception::SparseImageDecoder::_img_ptr
sensor_msgs::ImagePtr _img_ptr
Definition: sparse_image_decoder.cpp:22
jsk_perception::SparseImageDecoder::unsubscribe
void unsubscribe()
Definition: sparse_image_decoder.cpp:82
ros::NodeHandle
ros::Subscriber
NODELET_DEBUG
#define NODELET_DEBUG(...)


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17