00001 #include <ros/ros.h>
00002 #include <nodelet/nodelet.h>
00003 #include <image_transport/image_transport.h>
00004 #include <sensor_msgs/image_encodings.h>
00005 #include <stereo_msgs/DisparityImage.h>
00006
00007 namespace openni_camera {
00008
00009 namespace enc = sensor_msgs::image_encodings;
00010
00011 class DisparityNodelet : public nodelet::Nodelet
00012 {
00013
00014 boost::shared_ptr<image_transport::ImageTransport> it_;
00015 image_transport::CameraSubscriber sub_depth_;
00016 bool subscribed_;
00017
00018
00019 ros::Publisher pub_disparity_;
00020
00021 virtual void onInit();
00022
00023 void connectCb();
00024
00025 void depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00026 const sensor_msgs::CameraInfoConstPtr& info_msg);
00027 };
00028
00029 void DisparityNodelet::onInit()
00030 {
00031 ros::NodeHandle& nh = getNodeHandle();
00032 it_.reset(new image_transport::ImageTransport(nh));
00033
00034
00035 subscribed_ = false;
00036 ros::SubscriberStatusCallback connect_cb = boost::bind(&DisparityNodelet::connectCb, this);
00037 pub_disparity_ = nh.advertise<stereo_msgs::DisparityImage>("disparity", 1, connect_cb, connect_cb);
00038 }
00039
00040
00041 void DisparityNodelet::connectCb()
00042 {
00043
00044 if (pub_disparity_.getNumSubscribers() == 0)
00045 {
00046
00047 sub_depth_.shutdown();
00048 subscribed_ = false;
00049 }
00050 else if (!subscribed_)
00051 {
00052
00053 image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00054 sub_depth_ = it_->subscribeCamera("image_rect_raw", 1, &DisparityNodelet::depthCb, this, hints);
00055 subscribed_ = true;
00056 }
00057 }
00058
00059 void DisparityNodelet::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00060 const sensor_msgs::CameraInfoConstPtr& info_msg)
00061 {
00063 if (depth_msg->encoding != enc::TYPE_16UC1)
00064 {
00065 NODELET_ERROR("Expected data of type [%s], got [%s]", enc::TYPE_16UC1.c_str(),
00066 depth_msg->encoding.c_str());
00067 return;
00068 }
00069
00070
00071 stereo_msgs::DisparityImagePtr disp_msg( new stereo_msgs::DisparityImage );
00072 disp_msg->header = depth_msg->header;
00073 disp_msg->image.header = disp_msg->header;
00074 disp_msg->image.encoding = enc::TYPE_32FC1;
00075 disp_msg->image.height = depth_msg->height;
00076 disp_msg->image.width = depth_msg->width;
00077 disp_msg->image.step = disp_msg->image.width * sizeof (float);
00078 disp_msg->image.data.resize( disp_msg->image.height * disp_msg->image.step, 0.0f );
00079 disp_msg->T = 0.075;
00080 disp_msg->f = info_msg->P[0];
00082 disp_msg->min_disparity = disp_msg->f * disp_msg->T / 4.0;
00083 disp_msg->max_disparity = disp_msg->f * disp_msg->T / 0.5;
00084 disp_msg->delta_d = 0.125;
00085
00086
00087 float constant = disp_msg->f * disp_msg->T * 1000.0;
00088
00089 const uint16_t* depth_data = reinterpret_cast<const uint16_t*>(&depth_msg->data[0]);
00090 float* disp_data = reinterpret_cast<float*>(&disp_msg->image.data[0]);
00091 for (unsigned index = 0; index < depth_msg->height * depth_msg->width; ++index)
00092 {
00094 uint16_t depth = depth_data[index];
00095 if (depth != 0)
00096 disp_data[index] = constant / depth;
00097 }
00098
00099 pub_disparity_.publish(disp_msg);
00100 }
00101
00102 }
00103
00104
00105 #include <pluginlib/class_list_macros.h>
00106 PLUGINLIB_DECLARE_CLASS (openni_camera, disparity, openni_camera::DisparityNodelet, nodelet::Nodelet);