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
00037 #include <laser3D_pointcloud/laser3D_pointcloud.h>
00038
00039
00040
00041 las3D_PointCloud *g_las3D;
00042 int phis_count=0;
00043 int firstscan=1;
00044 ros::Time firstscan_stamp;
00045 ros::Time phi1_stamp;
00046 ros::Time phi2_stamp;
00047 sensor_msgs::JointStatePtr first_state1(new sensor_msgs::JointState);
00048 sensor_msgs::JointStatePtr first_state2(new sensor_msgs::JointState);
00049
00055 void state_cb (const sensor_msgs::JointState::ConstPtr& state_in)
00056 {
00057
00058 std::string joint_name = "/connect_laser_roof_rotating";
00059 if (joint_name.compare(state_in->name[0]) != 0)
00060 return;
00061
00062 if (firstscan)
00063 {
00064 *first_state1=*first_state2;
00065 *first_state2=*state_in;
00066
00067 phi1_stamp=phi2_stamp;
00068 phi2_stamp = state_in->header.stamp;
00069
00070 phis_count++;
00071 }
00072
00073 sensor_msgs::JointStatePtr new_state(new sensor_msgs::JointState);
00074 *new_state=*state_in;
00075
00076 if (!firstscan)
00077 g_las3D->joints.push_back(new_state);
00078
00079 }
00080
00086 void scan_cb(const sensor_msgs::LaserScan::ConstPtr& scan_in)
00087 {
00088
00089 if (g_las3D->accumulation_mode==2 || g_las3D->accumulation_mode==3)
00090 {
00091 sensor_msgs::LaserScanPtr new_scan(new sensor_msgs::LaserScan);
00092 *new_scan=*scan_in;
00093 int error=0;
00094 sensor_msgs::PointCloud2 pcmsg_in;
00095
00096
00097 error=g_las3D->las3D_transformLaserScanToPointCloud(ros::names::remap("/ac_frame"), *new_scan,pcmsg_in,*g_las3D->p_listener);
00098
00099 if (error)
00100 return;
00101
00102 pcl::PointCloud<pcl::PointXYZ> pc_in;
00103 pcl::fromROSMsg(pcmsg_in,pc_in);
00104
00105
00106 g_las3D->accumulate_cloud(&pc_in);
00107
00108 g_las3D->laser_count++;
00109 g_las3D->laserscan_arrived=true;
00110
00111 }
00112 else if (g_las3D->accumulation_mode==1)
00113 {
00114 if (phis_count<2)
00115 return;
00116
00117 if (firstscan)
00118 {
00119 firstscan_stamp = scan_in->header.stamp;
00120
00121 if ( (firstscan_stamp>phi1_stamp && firstscan_stamp<phi2_stamp) && (phi1_stamp.toSec()>0))
00122 {
00123 firstscan=0;
00124 g_las3D->joints.push_back(first_state1);
00125 g_las3D->joints.push_back(first_state2);
00126 }
00127 else
00128 return;
00129 }
00130
00131 int error=0;
00132
00133 sensor_msgs::LaserScanPtr new_scan(new sensor_msgs::LaserScan);
00134 *new_scan=*scan_in;
00135
00136 g_las3D->scans.push_back(new_scan);
00137
00138 if(g_las3D->joints.size()<2)
00139 return;
00140
00141 while(g_las3D->joints.size()>=2 && g_las3D->scans.size()>0)
00142 {
00143 int need_state=0;
00144 sensor_msgs::LaserScanPtr working_scan(new sensor_msgs::LaserScan);
00145 *working_scan=*g_las3D->scans[0];
00146 g_las3D->scans.erase(g_las3D->scans.begin());
00147
00148
00149 sensor_msgs::JointStatePtr state_start(new sensor_msgs::JointState);
00150 *state_start=*g_las3D->joints[0];
00151
00152 g_las3D->joints.erase(g_las3D->joints.begin());
00153
00154
00155 sensor_msgs::JointStatePtr state_end(new sensor_msgs::JointState);
00156 *state_end=*g_las3D->joints[0];
00157
00158
00159 while (working_scan->header.stamp<state_start->header.stamp)
00160 {
00161 if (g_las3D->scans.size()>0)
00162 *working_scan=*g_las3D->scans[0];
00163 else
00164 {
00165 need_state=1;
00166 break;
00167 }
00168
00169 g_las3D->scans.erase(g_las3D->scans.begin());
00170
00171 }
00172
00173 while (working_scan->header.stamp>state_end->header.stamp)
00174 {
00175 g_las3D->joints.erase(g_las3D->joints.begin());
00176
00177 if (g_las3D->joints.size()>0)
00178 *state_end=*g_las3D->joints[0];
00179 else
00180 {
00181 need_state=1;
00182 break;
00183 }
00184 }
00185
00186 if (need_state)
00187 return;
00188
00189 sensor_msgs::PointCloud2 pcmsg_in;
00190
00191
00192 if (g_las3D->accumulation_mode==1)
00193 error=g_las3D->las3D_transformLaserScanToPointCloud(ros::names::remap("/ac_frame"), *working_scan,pcmsg_in,*state_start,*state_end,*g_las3D->p_listener);
00194
00195 if (error)
00196 return;
00197
00198 pcl::PointCloud<pcl::PointXYZ> pc_in;
00199 pcl::fromROSMsg(pcmsg_in,pc_in);
00200
00201 g_las3D->accumulate_cloud(&pc_in);
00202
00203 g_las3D->laser_count++;
00204 g_las3D->laserscan_arrived=true;
00205
00206
00207 if (g_las3D->laser_count>g_las3D->max_scans_accumulated)
00208 g_las3D->pc_accumulated.erase(g_las3D->pc_accumulated.begin(),g_las3D->pc_accumulated.begin()+g_las3D->cloud_size);
00209 }
00210 }
00211
00212 }
00213
00214
00215 int main(int argc, char **argv)
00216 {
00217 ros::init(argc, argv, "laser3D_pointcloud");
00218 ros::NodeHandle n("~");
00219 tf::TransformListener listener(n,ros::Duration(100));
00220
00221 las3D_PointCloud las3D;
00222 g_las3D=&las3D;
00223
00224 g_las3D->p_listener=&listener;
00225
00226 double output_freq;
00227 n.param("output_frequency", output_freq, 200.0);
00228 n.param("accumulation_mode", g_las3D->accumulation_mode, 1);
00229 n.param("max_scans_accumulated", g_las3D->max_scans_accumulated, 450);
00230 n.param("pointcloud_stamp", g_las3D->pointcloud_stamp,1);
00231
00232
00233 if (ros::names::remap("/ac_frame")=="/ac_frame")
00234 {
00235 ROS_ERROR("/ac_frame was not remapped. Aborting program.");
00236 ros::shutdown();
00237 }
00238
00239
00240 ros::Subscriber sub_phiversion = n.subscribe ("/laserscan0", 100, scan_cb);
00241 ros::Subscriber sub_state = n.subscribe ("/joint_state", 100, state_cb);
00242
00243
00244 ros::Publisher pub = n.advertise<sensor_msgs::PointCloud2>("/pc_out", 1);
00245
00246 ros::Rate loop_rate(output_freq);
00247
00248 while (n.ok())
00249 {
00250 ros::spinOnce();
00251
00252 if (g_las3D->laserscan_arrived)
00253 {
00254 g_las3D->laserscan_arrived=false;
00255 sensor_msgs::PointCloud2 pcmsg_out;
00256 pcl::toROSMsg(g_las3D->pc_accumulated, pcmsg_out);
00257
00258 if (g_las3D->pointcloud_stamp)
00259 pcmsg_out.header.stamp = ros::Time::now();
00260 else
00261 pcmsg_out.header.stamp = g_las3D->pc_accumulated.header.stamp;
00262 #if _USE_DEBUG_
00263 ROS_INFO("Publishing pc_accumulated with %d points", (int)g_las3D->pc_accumulated.size());
00264 #endif
00265
00266 pub.publish(pcmsg_out);
00267
00268 }
00269
00270 loop_rate.sleep();
00271 }
00272
00273 }