37
37
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
38
38
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
39
39
// POSSIBILITY OF SUCH DAMAGE.
40
+ #include < boost/filesystem.hpp>
40
41
#include < cv_bridge/cv_bridge.h>
41
42
#include < geometry_msgs/Vector3.h>
42
43
#include < ikd-Tree/ikd_Tree.h>
@@ -446,7 +447,14 @@ void publish_frame_world(const ros::Publisher & pubLaserCloudFull)
446
447
if (pcl_wait_save->size () > 0 && pcd_save_interval > 0 && scan_wait_num >= pcd_save_interval)
447
448
{
448
449
pcd_index ++;
449
- string all_points_dir (string (string (ROOT_DIR) + " PCD/scans_" ) + to_string (pcd_index) + string (" .pcd" ));
450
+ string pcd_dir = string (ROOT_DIR) + " PCD/" ;
451
+ bool directory_exists = boost::filesystem::exists (pcd_dir) &&
452
+ boost::filesystem::is_directory (pcd_dir);
453
+ if (!directory_exists)
454
+ {
455
+ boost::filesystem::create_directory (pcd_dir);
456
+ }
457
+ string all_points_dir (pcd_dir + to_string (pcd_index) + string (" .pcd" ));
450
458
pcl::PCDWriter pcd_writer;
451
459
cout << " current scan saved to /PCD/" << all_points_dir << endl;
452
460
pcd_writer.writeBinary (all_points_dir, *pcl_wait_save);
@@ -1285,6 +1293,7 @@ int main(int argc, char** argv)
1285
1293
1286
1294
// Publish points
1287
1295
if (path_en) publish_path (pubPath);
1296
+ if (scan_pub_en || pcd_save_en) publish_frame_world (pubLaserCloudFull);
1288
1297
if (scan_pub_en && scan_body_pub_en) publish_frame_body (pubLaserCloudFull_body);
1289
1298
1290
1299
full_cycle_timer.Stop ();
@@ -1311,9 +1320,16 @@ int main(int argc, char** argv)
1311
1320
if (pcl_wait_save->size () > 0 && pcd_save_en)
1312
1321
{
1313
1322
string file_name = string (" scans.pcd" );
1314
- string all_points_dir (string (string (ROOT_DIR) + " PCD/" ) + file_name);
1323
+ string pcd_dir = string (ROOT_DIR) + " PCD/" ;
1324
+ bool directory_exists = boost::filesystem::exists (pcd_dir) &&
1325
+ boost::filesystem::is_directory (pcd_dir);
1326
+ if (!directory_exists)
1327
+ {
1328
+ boost::filesystem::create_directory (pcd_dir);
1329
+ }
1330
+ string all_points_dir (pcd_dir + file_name);
1315
1331
pcl::PCDWriter pcd_writer;
1316
- cout << " current scan saved to /PCD/ " << file_name <<endl;
1332
+ cout << " current scan saved to " << all_points_dir <<endl;
1317
1333
pcd_writer.writeBinary (all_points_dir, *pcl_wait_save);
1318
1334
}
1319
1335
return 0 ;
0 commit comments