32 #include <pcl/point_cloud.h> 33 #include <pcl/point_types.h> 35 #include <pcl/io/pcd_io.h> 36 #include <pcl/filters/voxel_grid.h> 37 #include <pcl/filters/radius_outlier_removal.h> 43 #include <nav_msgs/Odometry.h> 44 #include <sensor_msgs/PointCloud2.h> 50 #include <rtabmap_ros/OdomInfo.h> 108 bool subscribeOdomInfo =
false;
110 pnh.
param(
"queue_size", queueSize, queueSize);
123 pnh.
param(
"subscribe_odom_info", subscribeOdomInfo, subscribeOdomInfo);
142 std::string subscribedTopicsMsg;
146 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to %s",
150 else if(subscribeOdomInfo)
157 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (exact sync):\n %s,\n %s",
159 syncCloudSub_.getTopic().c_str(),
160 syncOdomSub_.getTopic().c_str(),
171 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (exact sync):\n %s,\n %s",
173 syncCloudSub_.getTopic().c_str(),
185 const sensor_msgs::PointCloud2ConstPtr & cloudMsg,
186 const nav_msgs::OdometryConstPtr & odomMsg)
197 NODELET_WARN(
"Reseting point cloud assembler as null odometry has been received.");
203 const sensor_msgs::PointCloud2ConstPtr & cloudMsg,
204 const nav_msgs::OdometryConstPtr & odomMsg,
205 const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg)
211 if(odomInfoMsg->keyFrameAdded)
223 NODELET_WARN(
"Reseting point cloud assembler as null odometry has been received.");
232 if(skipClouds_<=0 || cloudsSkipped_ >=
skipClouds_)
238 cloudMsg->header.frame_id,
239 cloudMsg->header.stamp,
245 ROS_ERROR(
"Cloud not transform all clouds! Resetting...");
250 pcl::PCLPointCloud2::Ptr newCloud(
new pcl::PCLPointCloud2);
256 #if PCL_VERSION_COMPARE(>=, 1, 10, 0) 262 newCloud->header.stamp =
stamp;
266 sensor_msgs::PointCloud2 output;
273 #if PCL_VERSION_COMPARE(>=, 1, 10, 0) 274 bool reachedMaxSize =
279 bool reachedMaxSize =
287 pcl::PCLPointCloud2Ptr assembled(
new pcl::PCLPointCloud2);
288 for(std::list<pcl::PCLPointCloud2::Ptr>::iterator iter=
clouds_.begin(); iter!=
clouds_.end(); ++iter)
290 if(assembled->data.empty())
292 *assembled = *(*iter);
296 pcl::PCLPointCloud2Ptr assembledTmp(
new pcl::PCLPointCloud2);
297 #if PCL_VERSION_COMPARE(>=, 1, 10, 0) 298 pcl::concatenate(*assembled, *(*iter), *assembledTmp);
302 assembled = assembledTmp;
306 sensor_msgs::PointCloud2 rosCloud;
309 pcl::VoxelGrid<pcl::PCLPointCloud2> filter;
311 filter.setInputCloud(assembled);
312 pcl::PCLPointCloud2Ptr output(
new pcl::PCLPointCloud2);
313 filter.filter(*output);
318 pcl::RadiusOutlierRemoval<pcl::PCLPointCloud2> filter;
321 filter.setInputCloud(assembled);
322 pcl::PCLPointCloud2Ptr output(
new pcl::PCLPointCloud2);
323 filter.filter(*output);
334 cloudMsg->header.stamp,
339 ROS_ERROR(
"Cloud not transform back assembled clouds in target frame \"%s\"! Resetting...",
frameId_.c_str());
346 rosCloud.header = cloudMsg->header;
349 rosCloud.header.frame_id =
frameId_;
380 ROS_WARN(
"%s: Did not receive data since 5 seconds! Make sure the input topics are " 381 "published (\"$ rostopic hz my_topic\") and the timestamps in their " 382 "header are set. %s",
384 subscribedTopicsMsg.c_str());
message_filters::Synchronizer< syncInfoPolicy > * exactInfoSync_
tf::TransformListener tfListener_
std::string getTopic() const
std::string uFormat(const char *fmt,...)
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
message_filters::Subscriber< nav_msgs::Odometry > syncOdomSub_
void callbackCloud(const sensor_msgs::PointCloud2ConstPtr &cloudMsg)
pcl::PCLPointCloud2::Ptr RTABMAP_EXP laserScanToPointCloud2(const LaserScan &laserScan, const Transform &transform=Transform())
const std::string & getName() const
double waitForTransformDuration_
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg, bool ignoreRotationIfNotSet=false)
boost::thread * warningThread_
geometry_msgs::TransformStamped t
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
ros::NodeHandle & getPrivateNodeHandle() const
std::list< pcl::PCLPointCloud2::Ptr > clouds_
void callbackCloudOdom(const sensor_msgs::PointCloud2ConstPtr &cloudMsg, const nav_msgs::OdometryConstPtr &odomMsg)
LaserScan RTABMAP_EXP commonFiltering(const LaserScan &scan, int downsamplingStep, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalK=0, float normalRadius=0.0f, float groundNormalsUp=0.0f)
void warningLoop(const std::string &subscribedTopicsMsg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::string getTopic() const
message_filters::Subscriber< sensor_msgs::PointCloud2 > syncCloudSub_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, nav_msgs::Odometry, rtabmap_ros::OdomInfo > syncInfoPolicy
virtual ~PointCloudAssembler()
ros::NodeHandle & getNodeHandle() const
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, nav_msgs::Odometry > syncPolicy
bool concatenatePointCloud(const sensor_msgs::PointCloud2 &cloud1, const sensor_msgs::PointCloud2 &cloud2, sensor_msgs::PointCloud2 &cloud_out)
message_filters::Subscriber< rtabmap_ros::OdomInfo > syncOdomInfoSub_
#define NODELET_INFO(...)
uint32_t getNumSubscribers() 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)
ros::Subscriber cloudSub_
void callbackCloudOdomInfo(const sensor_msgs::PointCloud2ConstPtr &cloudMsg, const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)
message_filters::Synchronizer< syncPolicy > * exactSync_
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)
std::string fixedFrameId_
LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PCLPointCloud2 &cloud, bool filterNaNs=true, bool is2D=false, const Transform &transform=Transform())