Skip to content

Commit df1ffac

Browse files
committed
fix missing call to point cloud saving
1 parent e46ca6a commit df1ffac

File tree

1 file changed

+19
-3
lines changed

1 file changed

+19
-3
lines changed

src/laserMapping.cpp

Lines changed: 19 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@
3737
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
3838
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
3939
// POSSIBILITY OF SUCH DAMAGE.
40+
#include <boost/filesystem.hpp>
4041
#include <cv_bridge/cv_bridge.h>
4142
#include <geometry_msgs/Vector3.h>
4243
#include <ikd-Tree/ikd_Tree.h>
@@ -446,7 +447,14 @@ void publish_frame_world(const ros::Publisher & pubLaserCloudFull)
446447
if (pcl_wait_save->size() > 0 && pcd_save_interval > 0 && scan_wait_num >= pcd_save_interval)
447448
{
448449
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"));
450458
pcl::PCDWriter pcd_writer;
451459
cout << "current scan saved to /PCD/" << all_points_dir << endl;
452460
pcd_writer.writeBinary(all_points_dir, *pcl_wait_save);
@@ -1285,6 +1293,7 @@ int main(int argc, char** argv)
12851293

12861294
// Publish points
12871295
if (path_en) publish_path(pubPath);
1296+
if (scan_pub_en || pcd_save_en) publish_frame_world(pubLaserCloudFull);
12881297
if (scan_pub_en && scan_body_pub_en) publish_frame_body(pubLaserCloudFull_body);
12891298

12901299
full_cycle_timer.Stop();
@@ -1311,9 +1320,16 @@ int main(int argc, char** argv)
13111320
if (pcl_wait_save->size() > 0 && pcd_save_en)
13121321
{
13131322
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);
13151331
pcl::PCDWriter pcd_writer;
1316-
cout << "current scan saved to /PCD/" << file_name<<endl;
1332+
cout << "current scan saved to " << all_points_dir <<endl;
13171333
pcd_writer.writeBinary(all_points_dir, *pcl_wait_save);
13181334
}
13191335
return 0;

0 commit comments

Comments
 (0)