39 #include <sensor_msgs/PointCloud2.h> 41 #include <pcl/point_cloud.h> 53 void callback(
const sensor_msgs::PointCloud2::ConstPtr& pc)
55 PointCloudT::Ptr cloud = boost::make_shared<PointCloudT>();
58 if (!cloud->isOrganized())
66 ROS_INFO(
"Dimensions of input cloud different from stored background, resetting background.");
77 invalid.x = invalid.y = invalid.z = std::numeric_limits<float>::quiet_NaN();
81 for (
size_t i = 0; i < cloud->size(); i++)
83 const PointT &p_in = cloud->points[i];
87 if (!pcl::isFinite<PointT>(p_in))
93 if (!pcl::isFinite<PointT>(p_bg))
95 (*cloud_bg_)[i] = p_in;
100 float dist_in = p_in.getVector3fMap().norm();
101 float dist_bg = p_bg.getVector3fMap().norm();
102 float diff = dist_bg - dist_in;
107 (*cloud_bg_)[i] = p_in;
108 (*cloud)[i] = invalid;
113 (*cloud)[i] = invalid;
119 sensor_msgs::PointCloud2::Ptr
msg = boost::make_shared<sensor_msgs::PointCloud2>();
121 msg->header = pc->header;
124 sensor_msgs::PointCloud2::Ptr msg_bg = boost::make_shared<sensor_msgs::PointCloud2>();
126 msg_bg->header = pc->header;
130 int main(
int argc,
char **argv)
132 ros::init(argc, argv,
"sick_ldmrs_remove_background");
142 pub = nh.
advertise<sensor_msgs::PointCloud2>(
"foreground", 10);
143 pub_bg = nh.
advertise<sensor_msgs::PointCloud2>(
"background", 10);
void publish(const boost::shared_ptr< M > &message) const
void callback(const sensor_msgs::PointCloud2::ConstPtr &pc)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
pcl::PointCloud< PointT > PointCloudT
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
sick_ldmrs_msgs::SICK_LDMRS_Point PointT
int main(int argc, char **argv)
ROSCPP_DECL void spin(Spinner &spinner)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
#define ROS_ERROR_THROTTLE(period,...)
PointCloudT::Ptr cloud_bg_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)