00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00034 #define PFLN {printf("%s %d\n",__FILE__, __LINE__);}
00035
00036 #include <pc_accumulation/pc_accumulation.h>
00037
00038 ros::Publisher cloud_pc_laserScan;
00039 ros::Publisher cloud_pc_pointcloud;
00040 pc_accumulation *p_lib;
00041 double distance_from, timer_value;
00042 std::string laser_topic,pc_topic,acc_frame;
00043
00044
00045 bool process_laser_scan[5]={false,false,false,false,false};
00046 bool process_point_cloud[5]={false,false,false,false,false};
00047
00048
00053 void OdometryCallBack (const nav_msgs::OdometryConstPtr & odom_in)
00054 {
00055 p_lib->odometry_=*odom_in;
00056 }
00057
00062 void pointcloud_Callback(const sensor_msgs::PointCloud2Ptr& image)
00063 {
00064 p_lib->pointcloud_accumulated(*image,acc_frame);
00065 }
00066
00071 void laserscan_Callback(const sensor_msgs::LaserScanPtr& scan_in)
00072 {
00073 p_lib->pointcloud_accumulated(*scan_in,acc_frame);
00074 }
00075
00076
00081 void Remove_Publish(const ros::TimerEvent&)
00082 {
00083 sensor_msgs::PointCloud2 msg;
00084 p_lib->remove_points_from_pointcloud(p_lib->pcl_pc_acc,distance_from, acc_frame);
00085 pcl::toROSMsg(p_lib->pcl_pc_acc,msg);
00086 cloud_pc_pointcloud.publish(msg);
00087 }
00088
00089
00090 int main(int argc, char **argv)
00091 {
00092 ros::init(argc, argv, "nodelet");
00093 ros::NodeHandle n("~");
00094
00095
00096
00097 for (int i=0; i<5; i++)
00098 {
00099 char str[1024];
00100 sprintf(str,"/laserscan%d", i);
00101 if (ros::names::remap(str)!=str)
00102 {
00103 process_laser_scan[i] = true;
00104 }
00105 }
00106
00107
00108 for (int i=0; i<5; i++)
00109 {
00110 char str[1024];
00111 sprintf(str,"/pointcloud%d", i);
00112 if (ros::names::remap(str)!=str)
00113 {
00114 process_point_cloud[i] = true;
00115 }
00116 }
00117 std::vector<ros::Subscriber> sub;
00118
00119 for (int i=0; i<5; i++)
00120 {
00121 if (process_laser_scan[i]==true)
00122 {
00123 char str[1024];
00124 sprintf(str,"/laserscan%d", i);
00125 ros::Subscriber sub_ = n.subscribe (str, 1, laserscan_Callback);
00126 ROS_INFO("Subscribing to %s", (ros::names::remap(str)).c_str());
00127 sub.push_back(sub_);
00128 }
00129 }
00130
00131
00132 for (int i=0; i<5; i++)
00133 {
00134 if (process_point_cloud[i]==true)
00135 {
00136 char str[1024];
00137 sprintf(str,"/pointcloud%d", i);
00138 ros::Subscriber sub_ = n.subscribe (str, 1, pointcloud_Callback);
00139 ROS_INFO("Subscribing to %s", (ros::names::remap(str)).c_str());
00140 ROS_INFO("REcebeu pointcloud");
00141 sub.push_back(sub_);
00142 }
00143 }
00144
00145
00146 if (sub.size()==0)
00147 {
00148 ROS_ERROR("No /laserscan[0 4] or /pointcloud[0 4] where remapped. Aborting...");
00149 ros::shutdown();
00150 }
00151
00152
00153
00154 if (!n.hasParam("acc_frame"))
00155 {
00156 ROS_ERROR("Didn't introduce a accumulation frame");
00157 return -1;
00158 }
00159 else
00160 {
00161 n.getParam("acc_frame",acc_frame);
00162 }
00163
00164
00165
00166 if (!n.hasParam("distance_from"))
00167 ROS_WARN("distance for accumulation 15 meters");
00168 else
00169 n.param("distance_from",distance_from, 15.0);
00170
00171 if (!n.hasParam("timer_value"))
00172 ROS_WARN("Frequency of publication 2.0 sec");
00173 else
00174 n.param("timer_value",timer_value, 2.0);
00175
00176
00177
00178
00179 pc_accumulation lib;
00180
00181
00182 if (!n.hasParam("voxel_size"))
00183 ROS_WARN("Voxel_size Default 0.4 meter");
00184 else
00185 n.param("voxel_size",lib.voxel_size, 0.4);
00186
00187 string removed_from;
00188 if (!n.hasParam("removed_from"))
00189 {
00190 ROS_ERROR("Remove from frame not Defined");
00191 return -1;
00192 }
00193 else
00194 n.getParam("removed_from",removed_from);
00195
00196 lib._acc_frame_id=removed_from;
00197
00198
00199 p_lib=&lib;
00200
00201
00202 ros::Timer timer = n.createTimer(ros::Duration(timer_value), Remove_Publish);
00203
00204 tf::TransformListener listener(n,ros::Duration(10));
00205
00206 lib.p_listener=&listener;
00207
00208 lib.p_n=&n;
00209
00210 cloud_pc_pointcloud = n.advertise<sensor_msgs::PointCloud2>("/pc_out_pointcloud", 1);
00211 ros::Subscriber odom = n.subscribe ("odometry_topic", 1, OdometryCallBack);
00212
00213
00214 ros::Rate loop_rate(50);
00215 ros::spin();
00216
00217
00218 return 0;
00219 }