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> 97 pnh.
param(
"queue_size", queueSize, queueSize);
104 pnh.
param(
"approx", approx, approx);
110 ROS_FATAL(
"fixed_frame_id should be set when using approximate " 111 "time synchronization (approx=true)! If the robot " 112 "is moving, it could be \"odom\". If not moving, it " 113 "could be \"base_link\".");
117 ROS_INFO(
" approx=%s", approx?
"true":
"false");
118 ROS_INFO(
" queue_size=%d", queueSize);
121 ROS_INFO(
" fill_holes_size=%d pixels (0=disabled)",
fillHolesSize_);
151 const sensor_msgs::PointCloud2ConstPtr & pointCloud2Msg,
152 const sensor_msgs::CameraInfoConstPtr & cameraInfoMsg)
156 double cloudStamp = pointCloud2Msg->header.stamp.toSec();
157 double infoStamp = cameraInfoMsg->header.stamp.toSec();
164 pointCloud2Msg->header.frame_id,
166 cameraInfoMsg->header.stamp,
167 pointCloud2Msg->header.stamp,
172 if(cloudDisplacement.
isNull())
178 pointCloud2Msg->header.frame_id,
179 cameraInfoMsg->header.frame_id,
180 cameraInfoMsg->header.stamp,
184 if(cloudToCamera.
isNull())
192 sensor_msgs::CameraInfo cameraInfoMsgOut = *cameraInfoMsg;
198 model = model.
scaled(scale);
204 ROS_ERROR(
"decimation (%d) not valid for image size %dx%d",
211 UASSERT_MSG(pointCloud2Msg->data.size() == pointCloud2Msg->row_step*pointCloud2Msg->height,
212 uFormat(
"data=%d row_step=%d height=%d", pointCloud2Msg->data.size(), pointCloud2Msg->row_step, pointCloud2Msg->height).c_str());
214 pcl::PCLPointCloud2::Ptr cloud(
new pcl::PCLPointCloud2);
219 if(cloud->data.empty())
238 sensor_msgs::PointCloud2 pointCloud2Out;
240 pointCloud2Out.header = cameraInfoMsg->header;
245 depthImage.
header = cameraInfoMsg->header;
273 if( cloudStamp != pointCloud2Msg->header.stamp.toSec() ||
274 infoStamp != cameraInfoMsg->header.stamp.toSec())
276 NODELET_ERROR(
"Input stamps changed between the beginning and the end of the callback! Make " 277 "sure the node publishing the topics doesn't override the same data after publishing them. A " 278 "solution is to use this node within another nodelet manager. Stamps: " 279 "cloud=%f->%f info=%f->%f",
280 cloudStamp, pointCloud2Msg->header.stamp.toSec(),
281 infoStamp, cameraInfoMsg->header.stamp.toSec());
void callback(const sensor_msgs::PointCloud2ConstPtr &pointCloud2Msg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg)
const cv::Size & imageSize() const
std::string uFormat(const char *fmt,...)
#define NODELET_ERROR(...)
CameraModel scaled(double scale) const
std::string getTopic() const
uint32_t getNumSubscribers() const
image_transport::Publisher depthImage32Pub_
ros::NodeHandle & getNodeHandle() const
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ros::Publisher cameraInfo32Pub_
ros::Publisher pointCloudTransformedPub_
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
ros::NodeHandle & getPrivateNodeHandle() const
double upscaleDepthErrorRatio_
message_filters::Subscriber< sensor_msgs::PointCloud2 > pointCloudSub_
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
cv::Mat RTABMAP_EXP interpolate(const cv::Mat &image, int factor, float depthErrorRatio=0.02f)
sensor_msgs::ImagePtr toImageMsg() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
#define UASSERT_MSG(condition, msg_str)
image_transport::Publisher depthImage16Pub_
tf::TransformListener * listener_
const std::string TYPE_32FC1
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
const std::string TYPE_16UC1
const Transform & localTransform() const
std::string resolveName(const std::string &name, bool remap=true) const
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
void toPCL(const ros::Time &stamp, std::uint64_t &pcl_stamp)
void cameraModelToROS(const rtabmap::CameraModel &model, sensor_msgs::CameraInfo &camInfo)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void publish(const sensor_msgs::Image &message) const
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)
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > MyExactSyncPolicy
ros::Publisher cameraInfo16Pub_
cv::Mat RTABMAP_EXP fillDepthHoles(const cv::Mat &depth, int maximumHoleSize=1, float errorRatio=0.02f)
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
cv::Mat RTABMAP_EXP projectCloudToCamera(const cv::Size &imageSize, const cv::Mat &cameraMatrixK, const cv::Mat &laserScan, const rtabmap::Transform &cameraTransform)
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
cv::Mat RTABMAP_EXP cvtDepthFromFloat(const cv::Mat &depth32F)
virtual ~PointCloudToDepthImage()
uint32_t getNumSubscribers() const
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > MyApproxSyncPolicy
std::string fixedFrameId_