34 #include <boost/version.hpp> 35 #if ((BOOST_VERSION / 100) % 1000) >= 53 36 #include <boost/thread/lock_guard.hpp> 46 #include <stereo_msgs/DisparityImage.h> 72 void depthCb(
const sensor_msgs::ImageConstPtr& depth_msg,
73 const sensor_msgs::CameraInfoConstPtr& info_msg);
76 void convert(
const sensor_msgs::ImageConstPtr& depth_msg,
77 stereo_msgs::DisparityImagePtr& disp_msg);
90 private_nh.
param(
"queue_size", queue_size, 5);
92 private_nh.
param(
"max_range",
max_range_, std::numeric_limits<double>::infinity());
124 const sensor_msgs::CameraInfoConstPtr& info_msg)
127 stereo_msgs::DisparityImagePtr disp_msg(
new stereo_msgs::DisparityImage );
128 disp_msg->header = depth_msg->header;
129 disp_msg->image.header = disp_msg->header;
130 disp_msg->image.encoding = enc::TYPE_32FC1;
131 disp_msg->image.height = depth_msg->height;
132 disp_msg->image.width = depth_msg->width;
133 disp_msg->image.step = disp_msg->image.width *
sizeof (float);
134 disp_msg->image.data.resize( disp_msg->image.height * disp_msg->image.step, 0.0f );
135 double fx = info_msg->P[0];
136 disp_msg->T = -info_msg->P[3] / fx;
139 disp_msg->min_disparity = disp_msg->f * disp_msg->T /
max_range_;
140 disp_msg->max_disparity = disp_msg->f * disp_msg->T /
min_range_;
143 if (depth_msg->encoding == enc::TYPE_16UC1)
145 convert<uint16_t>(depth_msg, disp_msg);
147 else if (depth_msg->encoding == enc::TYPE_32FC1)
149 convert<float>(depth_msg, disp_msg);
162 stereo_msgs::DisparityImagePtr& disp_msg)
166 float constant = disp_msg->f * disp_msg->T / unit_scaling;
168 const T* depth_row =
reinterpret_cast<const T*
>(&depth_msg->data[0]);
169 int row_step = depth_msg->step /
sizeof(T);
170 float* disp_data =
reinterpret_cast<float*
>(&disp_msg->image.data[0]);
171 for (
int v = 0; v < (int)depth_msg->height; ++v)
173 for (
int u = 0; u < (int)depth_msg->width; ++u)
175 T depth = depth_row[u];
177 *disp_data = constant / depth;
181 depth_row += row_step;
ros::Publisher pub_disparity_
boost::mutex connect_mutex_
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ros::NodeHandle & getNodeHandle() const
#define NODELET_ERROR_THROTTLE(rate,...)
const Subscriber & getSubscriber() const
boost::shared_ptr< image_transport::ImageTransport > left_it_
ros::NodeHandle & getPrivateNodeHandle() const
image_transport::SubscriberFilter sub_depth_image_
boost::shared_ptr< Sync > sync_
void depthCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
message_filters::TimeSynchronizer< sensor_msgs::Image, sensor_msgs::CameraInfo > Sync
ros::NodeHandlePtr right_nh_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void convert(const sensor_msgs::ImageConstPtr &depth_msg, stereo_msgs::DisparityImagePtr &disp_msg)
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
PLUGINLIB_EXPORT_CLASS(depth_image_proc::DisparityNodelet, nodelet::Nodelet)
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
uint32_t getNumSubscribers() const