Go to the documentation of this file.
31 #include <ros/publisher.h>
39 #include <sensor_msgs/PointCloud2.h>
40 #include <sensor_msgs/Image.h>
42 #include <sensor_msgs/CameraInfo.h>
46 #include <pcl/point_cloud.h>
47 #include <pcl/point_types.h>
96 int syncQueueSize = 10;
98 pnh.
param(
"topic_queue_size", queueSize, queueSize);
101 pnh.
param(
"queue_size", syncQueueSize, syncQueueSize);
102 ROS_WARN(
"Parameter \"queue_size\" has been renamed "
103 "to \"sync_queue_size\" and will be removed "
104 "in future versions! The value (%d) is copied to "
105 "\"sync_queue_size\".", syncQueueSize);
109 pnh.
param(
"sync_queue_size", syncQueueSize, syncQueueSize);
117 pnh.
param(
"approx", approx, approx);
123 ROS_FATAL(
"fixed_frame_id should be set when using approximate "
124 "time synchronization (approx=true)! If the robot "
125 "is moving, it could be \"odom\". If not moving, it "
126 "could be \"base_link\".");
130 ROS_INFO(
" approx=%s", approx?
"true":
"false");
131 ROS_INFO(
" topic_queue_size=%d", queueSize);
132 ROS_INFO(
" sync_queue_size=%d", syncQueueSize);
165 const sensor_msgs::PointCloud2ConstPtr & pointCloud2Msg,
166 const sensor_msgs::CameraInfoConstPtr & cameraInfoMsg)
170 double cloudStamp = pointCloud2Msg->header.stamp.toSec();
171 double infoStamp = cameraInfoMsg->header.stamp.toSec();
178 pointCloud2Msg->header.frame_id,
180 pointCloud2Msg->header.stamp,
181 cameraInfoMsg->header.stamp,
186 if(cloudDisplacement.
isNull())
192 pointCloud2Msg->header.frame_id,
193 cameraInfoMsg->header.frame_id,
194 cameraInfoMsg->header.stamp,
198 if(cloudToCamera.
isNull())
206 sensor_msgs::CameraInfo cameraInfoMsgOut = *cameraInfoMsg;
218 ROS_ERROR(
"decimation (%d) not valid for image size %dx%d",
221 model.imageHeight());
225 UASSERT_MSG(pointCloud2Msg->data.size() == pointCloud2Msg->row_step*pointCloud2Msg->height,
226 uFormat(
"data=%d row_step=%d height=%d", pointCloud2Msg->data.size(), pointCloud2Msg->row_step, pointCloud2Msg->height).c_str());
228 pcl::PCLPointCloud2::Ptr cloud(
new pcl::PCLPointCloud2);
233 if(cloud->data.empty())
236 depthImage.
image = cv::Mat::zeros(
model.imageSize(), CV_32FC1);
252 sensor_msgs::PointCloud2 pointCloud2Out;
254 pointCloud2Out.header = cameraInfoMsg->header;
259 depthImage.
header = cameraInfoMsg->header;
287 if( cloudStamp != pointCloud2Msg->header.stamp.toSec() ||
288 infoStamp != cameraInfoMsg->header.stamp.toSec())
290 NODELET_ERROR(
"Input stamps changed between the beginning and the end of the callback! Make "
291 "sure the node publishing the topics doesn't override the same data after publishing them. A "
292 "solution is to use this node within another nodelet manager. Stamps: "
293 "cloud=%f->%f info=%f->%f",
294 cloudStamp, pointCloud2Msg->header.stamp.toSec(),
295 infoStamp, cameraInfoMsg->header.stamp.toSec());
virtual ~PointCloudToDepthImage()
#define NODELET_ERROR(...)
ros::NodeHandle & getNodeHandle() const
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
cv::Mat RTABMAP_CORE_EXPORT interpolate(const cv::Mat &image, int factor, float depthErrorRatio=0.02f)
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
sensor_msgs::ImagePtr toImageMsg() const
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > MyExactSyncPolicy
image_transport::Publisher depthImage16Pub_
std::string uFormat(const char *fmt,...)
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
uint32_t getNumSubscribers() const
image_transport::Publisher depthImage32Pub_
void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
void cameraModelToROS(const rtabmap::CameraModel &model, sensor_msgs::CameraInfo &camInfo)
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
ros::Publisher cameraInfo32Pub_
std::string fixedFrameId_
ros::NodeHandle & getPrivateNodeHandle() const
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
const std::string TYPE_16UC1
std::string getTopic() const
cv::Mat RTABMAP_CORE_EXPORT fillDepthHoles(const cv::Mat &depth, int maximumHoleSize=1, float errorRatio=0.02f)
void callback(const sensor_msgs::PointCloud2ConstPtr &pointCloud2Msg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg)
std::string resolveName(const std::string &name, bool remap=true) const
cv::Mat RTABMAP_CORE_EXPORT projectCloudToCamera(const cv::Size &imageSize, const cv::Mat &cameraMatrixK, const cv::Mat &laserScan, const rtabmap::Transform &cameraTransform)
tf::TransformListener * listener_
bool hasParam(const std::string &key) const
void publish(const sensor_msgs::Image &message) const
ros::Publisher pointCloudTransformedPub_
noiseModel::Diagonal::shared_ptr model
#define UASSERT_MSG(condition, msg_str)
double upscaleDepthErrorRatio_
message_filters::Subscriber< sensor_msgs::PointCloud2 > pointCloudSub_
cv::Mat RTABMAP_CORE_EXPORT cvtDepthFromFloat(const cv::Mat &depth32F)
void transformPointCloud(const Eigen::Matrix4f &transform, const sensor_msgs::PointCloud2 &in, sensor_msgs::PointCloud2 &out)
rtabmap::Transform getMovingTransform(const std::string &movingFrame, const std::string &fixedFrame, const ros::Time &stampFrom, const ros::Time &stampTo, tf::TransformListener &listener, double waitForTransform)
PLUGINLIB_EXPORT_CLASS(rtabmap_util::DisparityToDepth, nodelet::Nodelet)
const std::string TYPE_32FC1
T param(const std::string ¶m_name, const T &default_val) const
ros::Publisher cameraInfo16Pub_
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > MyApproxSyncPolicy
uint32_t getNumSubscribers() const
rtabmap_util
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:40:50