sparse_image_encoder.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  jsk_recognition_msgs::SparseImagePtr _spr_img_ptr;
23 
28  double _rate;
30 
31  void imageCallback(const sensor_msgs::ImageConstPtr& msg){
32  do_work(msg, msg->header.frame_id);
33  }
34 
35  void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg){
36  try {
37  int channel = enc::numChannels(msg->encoding);
38 
39  // check if uint16 array needed
40  bool useData32 = false;
41  if (std::max(msg->width, msg->height) > 256){
42  useData32 = true;
43  NODELET_DEBUG("use data32 array");
44  }
45 
46  _spr_img_ptr->header.stamp = msg->header.stamp;
47  _spr_img_ptr->header.frame_id = input_frame_from_msg;
48  _spr_img_ptr->width = msg->width;
49  _spr_img_ptr->height = msg->height;
50  if (!_spr_img_ptr->data16.empty()) _spr_img_ptr->data16.clear();
51  if (!_spr_img_ptr->data32.empty()) _spr_img_ptr->data32.clear();
52 
53  // make sparse image
54  for (uint32_t y = 0; y < msg->height; ++y){
55  for (uint32_t x = 0; x < msg->width; ++x){
56  if(msg->data[x*channel+y*msg->step] > 125){
57  if (useData32) _spr_img_ptr->data32.push_back( (x << 16) | y );
58  else _spr_img_ptr->data16.push_back( (x << 8) | y );
59  }
60  }
61  }
62 
63  // print number of point if enabled
64  if (_print_point_num) {
65  int size = 0;
66  if (useData32) size = _spr_img_ptr->data32.size();
67  else size = _spr_img_ptr->data16.size();
68  NODELET_INFO("%d point encoded. encoded area per is %lf%%.", size, (100 * ((double) size)/(msg->height* msg->width)));
69  }
70 
71  // publish sparse image message
73  } // end of try
74  catch (...) {
75  NODELET_ERROR("making sparse image error");
76  }
77 
78  ros::Rate pubRate(_rate); // hz
79  pubRate.sleep();
80  } // end of do_work function
81 
82  void subscribe() {
83  NODELET_DEBUG("Subscribing to image topic.");
84  _img_sub = _it->subscribe("image", 3, &SparseImageEncoder::imageCallback, this);
85  ros::V_string names = boost::assign::list_of("image");
86  jsk_topic_tools::warnNoRemap(names);
87  }
88 
89  void unsubscribe() {
90  NODELET_DEBUG("Unsubscribing from image topic.");
92  }
93 
95  if (_subscriber_count++ == 0) {
96  subscribe();
97  }
98  }
99 
102  if (_subscriber_count == 0) {
103  unsubscribe();
104  }
105  }
106 
107 public:
108  void onInit() {
109  _nh = getNodeHandle();
110  _ln = ros::NodeHandle("~");
112  _subscriber_count = 0;
113  ros::SubscriberStatusCallback connect_cb = boost::bind(&SparseImageEncoder::connectCb, this, _1);
114  ros::SubscriberStatusCallback disconnect_cb = boost::bind(&SparseImageEncoder::disconnectCb, this, _1);
115  _spr_img_pub = _nh.advertise<jsk_recognition_msgs::SparseImage>("sparse_image", 10, connect_cb, disconnect_cb);
116  _spr_img_ptr = boost::make_shared<jsk_recognition_msgs::SparseImage>();
117  _ln.param("rate", _rate, 3.0);
118  _ln.param("print_point_num", _print_point_num, false);
119  } // end of onInit function
120 }; // end of SparseImageEncoder class definition
121 } // end of jsk_perception namespace
122 
sensor_msgs::image_encodings
x
x
jsk_perception::SparseImageEncoder::do_work
void do_work(const sensor_msgs::ImageConstPtr &msg, const std::string input_frame_from_msg)
Definition: sparse_image_encoder.cpp:35
jsk_perception::SparseImageEncoder::_print_point_num
bool _print_point_num
Definition: sparse_image_encoder.cpp:29
jsk_perception::SparseImageEncoder::connectCb
void connectCb(const ros::SingleSubscriberPublisher &ssp)
Definition: sparse_image_encoder.cpp:94
NODELET_ERROR
#define NODELET_ERROR(...)
msg
msg
ros::Publisher
jsk_perception::SparseImageEncoder::_rate
double _rate
Definition: sparse_image_encoder.cpp:28
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
image_encodings.h
image_transport::ImageTransport
boost::shared_ptr< image_transport::ImageTransport >
jsk_perception::SparseImageEncoder::unsubscribe
void unsubscribe()
Definition: sparse_image_encoder.cpp:89
jsk_perception::SparseImageEncoder::onInit
void onInit()
Definition: sparse_image_encoder.cpp:108
_1
boost::arg< 1 > _1
jsk_perception::SparseImageEncoder::_img_sub
image_transport::Subscriber _img_sub
Definition: sparse_image_encoder.cpp:20
ros::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
image_transport::Subscriber
class_list_macros.h
ros::SingleSubscriberPublisher
jsk_perception
Definition: add_mask_image.h:48
jsk_perception::SparseImageEncoder::_spr_img_pub
ros::Publisher _spr_img_pub
Definition: sparse_image_encoder.cpp:19
jsk_perception::SparseImageEncoder::_subscriber_count
int _subscriber_count
Definition: sparse_image_encoder.cpp:27
ros::Rate::sleep
bool sleep()
jsk_perception::SparseImageEncoder::_spr_img_ptr
jsk_recognition_msgs::SparseImagePtr _spr_img_ptr
Definition: sparse_image_encoder.cpp:22
image_transport.h
jsk_perception::SparseImageEncoder::_nh
ros::NodeHandle _nh
Definition: sparse_image_encoder.cpp:25
NODELET_INFO
#define NODELET_INFO(...)
nodelet::Nodelet
jsk_perception::SparseImageEncoder::_it
boost::shared_ptr< image_transport::ImageTransport > _it
Definition: sparse_image_encoder.cpp:24
jsk_perception::SparseImageEncoder
Definition: sparse_image_encoder.cpp:17
nodelet.h
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
jsk_perception::SparseImageEncoder::_ln
ros::NodeHandle _ln
Definition: sparse_image_encoder.cpp:26
ros::Rate
jsk_perception::SparseImageEncoder::disconnectCb
void disconnectCb(const ros::SingleSubscriberPublisher &)
Definition: sparse_image_encoder.cpp:100
ros::V_string
std::vector< std::string > V_string
jsk_perception::SparseImageEncoder::subscribe
void subscribe()
Definition: sparse_image_encoder.cpp:82
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_perception::SparseImageEncoder, nodelet::Nodelet)
jsk_perception::SparseImageEncoder::imageCallback
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: sparse_image_encoder.cpp:31
ros::NodeHandle
NODELET_DEBUG
#define NODELET_DEBUG(...)
image_transport::Subscriber::shutdown
void shutdown()


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