Go to the documentation of this file.00001 #include <stdint.h>
00002 #include <boost/shared_ptr.hpp>
00003 #include <vector>
00004 #include <iostream>
00005
00006 #include <nodelet/nodelet.h>
00007 #include <jsk_topic_tools/log_utils.h>
00008 #include <image_transport/image_transport.h>
00009 #include <pluginlib/class_list_macros.h>
00010 #include <sensor_msgs/image_encodings.h>
00011 #include <jsk_recognition_msgs/SparseImage.h>
00012
00013
00014 namespace enc = sensor_msgs::image_encodings;
00015
00016 namespace jsk_perception {
00017 class SparseImageDecoder: public nodelet::Nodelet
00018 {
00019 image_transport::Publisher _img_pub;
00020 ros::Subscriber _spr_img_sub;
00021
00022 sensor_msgs::ImagePtr _img_ptr;
00023
00024 boost::shared_ptr<image_transport::ImageTransport> _it;
00025 ros::NodeHandle _nh;
00026 int _subscriber_count;
00027
00028 void imageCallback(const jsk_recognition_msgs::SparseImageConstPtr& msg){
00029 do_work(msg, msg->header.frame_id);
00030 }
00031
00032 void do_work(const jsk_recognition_msgs::SparseImageConstPtr& msg, const std::string input_frame_from_msg){
00033 try {
00034
00035 _img_ptr->header.stamp = msg->header.stamp;
00036 _img_ptr->header.frame_id = input_frame_from_msg;
00037 _img_ptr->width = msg->width;
00038 _img_ptr->height = msg->height;
00039 _img_ptr->step = msg->width;
00040 _img_ptr->encoding = enc::MONO8;
00041 if (!_img_ptr->data.empty()) _img_ptr->data.clear();
00042
00043
00044 bool useData32 = false;
00045 int length = msg->data16.size();
00046 if (length <= 0) {
00047 useData32 = true;
00048 length = msg->data32.size();
00049 JSK_NODELET_DEBUG("use data32 array");
00050 }
00051 _img_ptr->data.resize(_img_ptr->width * _img_ptr->height);
00052
00053 for (int i = 0; i < length; ++i){
00054 uint16_t x, y;
00055 if (useData32) {
00056 uint32_t pos = msg->data32[i];
00057 x = (uint16_t)(pos >> 16);
00058 y = (uint16_t)pos;
00059 } else {
00060 uint16_t pos = msg->data16[i];
00061 x = (uint16_t)(pos >> 8);
00062 y = (uint16_t)(pos & (uint8_t)-1);
00063 }
00064 _img_ptr->data[y * _img_ptr->width + x] = 255;
00065 }
00066
00067
00068 _img_pub.publish(*_img_ptr);
00069 }
00070 catch (...) {
00071 JSK_NODELET_ERROR("making sparse image error");
00072 }
00073 }
00074
00075 void subscribe() {
00076 JSK_NODELET_DEBUG("Subscribing to image topic.");
00077 _spr_img_sub = _nh.subscribe("sparse_image", 3, &SparseImageDecoder::imageCallback, this);
00078 }
00079
00080 void unsubscribe() {
00081 JSK_NODELET_DEBUG("Unsubscribing from image topic.");
00082 _spr_img_sub.shutdown();
00083 }
00084
00085 void connectCb(const image_transport::SingleSubscriberPublisher& ssp) {
00086 if (_subscriber_count++ == 0) {
00087 subscribe();
00088 }
00089 }
00090
00091 void disconnectCb(const image_transport::SingleSubscriberPublisher&) {
00092 _subscriber_count--;
00093 if (_subscriber_count == 0) {
00094 unsubscribe();
00095 }
00096 }
00097
00098 public:
00099 void onInit() {
00100 _nh = getNodeHandle();
00101 _img_ptr.reset(new sensor_msgs::Image());
00102 _it.reset(new image_transport::ImageTransport(_nh));
00103 _subscriber_count = 0;
00104 image_transport::SubscriberStatusCallback connect_cb = boost::bind(&SparseImageDecoder::connectCb, this, _1);
00105 image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&SparseImageDecoder::disconnectCb, this, _1);
00106 _img_pub = image_transport::ImageTransport(ros::NodeHandle(_nh, "sparse")).advertise("image_decoded", 1, connect_cb, disconnect_cb);
00107 }
00108 };
00109 }
00110
00111 typedef jsk_perception::SparseImageDecoder SparseImageDecoder;
00112 PLUGINLIB_DECLARE_CLASS (jsk_perception, SparseImageDecoder, SparseImageDecoder, nodelet::Nodelet);