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> 94 pnh.
param(
"queue_size", queueSize, queueSize);
101 pnh.
param(
"approx", approx, approx);
105 ROS_FATAL(
"fixed_frame_id should be set when using approximate " 106 "time synchronization (approx=true)! If the robot " 107 "is moving, it could be \"odom\". If not moving, it " 108 "could be \"base_link\".");
112 ROS_INFO(
" approx=%s", approx?
"true":
"false");
113 ROS_INFO(
" queue_size=%d", queueSize);
116 ROS_INFO(
" fill_holes_size=%d pixels (0=disabled)",
fillHolesSize_);
142 const sensor_msgs::PointCloud2ConstPtr & pointCloud2Msg,
143 const sensor_msgs::CameraInfoConstPtr & cameraInfoMsg)
152 pointCloud2Msg->header.frame_id,
154 pointCloud2Msg->header.stamp,
155 cameraInfoMsg->header.stamp,
160 if(cloudDisplacement.
isNull())
166 pointCloud2Msg->header.frame_id,
167 cameraInfoMsg->header.frame_id,
168 cameraInfoMsg->header.stamp,
172 if(cloudToCamera.
isNull())
189 ROS_ERROR(
"decimation (%d) not valid for image size %dx%d",
196 pcl::PCLPointCloud2::Ptr cloud(
new pcl::PCLPointCloud2);
210 depthImage.
header = cameraInfoMsg->header;
void callback(const sensor_msgs::PointCloud2ConstPtr &pointCloud2Msg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg)
const cv::Size & imageSize() const
image_transport::Publisher depthImage32Pub_
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
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)
uint32_t getNumSubscribers() const
ros::NodeHandle & getPrivateNodeHandle() const
void publish(const sensor_msgs::Image &message) const
image_transport::Publisher depthImage16Pub_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
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
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
ros::NodeHandle & getNodeHandle() 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)
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > MyExactSyncPolicy
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()
sensor_msgs::ImagePtr toImageMsg() const
CameraModel scaled(double scale) const
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > MyApproxSyncPolicy
const Transform & localTransform() const
std::string fixedFrameId_