32 #include <sensor_msgs/Image.h> 34 #include <stereo_msgs/DisparityImage.h> 62 void callback(
const stereo_msgs::DisparityImageConstPtr& disparityMsg)
73 if(publish32f || publish16u)
76 cv::Mat disparity(disparityMsg->image.height, disparityMsg->image.width, CV_32FC1, const_cast<uchar*>(disparityMsg->image.data.data()));
82 depth32f = cv::Mat::zeros(disparity.rows, disparity.cols, CV_32F);
86 depth16u = cv::Mat::zeros(disparity.rows, disparity.cols, CV_16U);
88 for (
int i = 0; i < disparity.rows; i++)
90 for (
int j = 0; j < disparity.cols; j++)
92 float disparity_value = disparity.at<
float>(i,j);
93 if (disparity_value > disparityMsg->min_disparity && disparity_value < disparityMsg->max_disparity)
96 float depth = disparityMsg->T * disparityMsg->f / disparity_value;
99 depth32f.at<
float>(i,j) = depth;
103 depth16u.at<
unsigned short>(i,j) = (
unsigned short)(depth*1000.0f);
void callback(const stereo_msgs::DisparityImageConstPtr &disparityMsg)
#define NODELET_ERROR(...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
virtual ~DisparityToDepth()
image_transport::Publisher pub32f_
uint32_t getNumSubscribers() const
ros::NodeHandle & getPrivateNodeHandle() const
void publish(const sensor_msgs::Image &message) const
const std::string TYPE_32FC1
const std::string TYPE_16UC1
image_transport::Publisher pub16u_
ros::NodeHandle & getNodeHandle() const
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
sensor_msgs::ImagePtr toImageMsg() const