Skip to content

Commit

Permalink
refactor: move progressbar to shared lib
Browse files Browse the repository at this point in the history
  • Loading branch information
YifuTao committed Sep 11, 2024
1 parent 4cd101c commit b213526
Show file tree
Hide file tree
Showing 4 changed files with 45 additions and 22 deletions.
19 changes: 13 additions & 6 deletions octomap_utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,13 +10,20 @@ find_package(Octomap REQUIRED)
find_package(PCL REQUIRED)


# Include the OctoMap headers
include_directories(${OCTOMAP_INCLUDE_DIRS})
include_directories(${PCL_INCLUDE_DIRS})

include_directories(
include
${OCTOMAP_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
)

add_library(${PROJECT_NAME} SHARED
progress_bar.cpp
)
target_link_libraries(${PROJECT_NAME} ${OCTOMAP_LIBRARIES})
target_link_libraries(${PROJECT_NAME} ${PCL_LIBRARIES})

add_executable(pcd2bt pcd2bt.cpp)
target_link_libraries(pcd2bt ${OCTOMAP_LIBRARIES} ${PCL_LIBRARIES})
target_link_libraries(pcd2bt ${PROJECT_NAME})

add_executable(get_occ_free_from_bt get_occ_free_from_bt.cpp)
target_link_libraries(get_occ_free_from_bt ${OCTOMAP_LIBRARIES} ${PCL_LIBRARIES})
target_link_libraries(get_occ_free_from_bt ${PROJECT_NAME})
18 changes: 2 additions & 16 deletions octomap_utils/get_occ_free_from_bt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,26 +6,12 @@
#include <pcl/point_types.h>
#include <chrono>

#include "progress_bar.h"

using namespace std;
using namespace octomap;
using PointCloud = pcl::PointCloud<pcl::PointXYZ>;

// Function to display a simple progress bar
void displayProgressBar(size_t current, size_t total) {
const int barWidth = 50; // Width of the progress bar
float progress = static_cast<float>(current) / total;
int pos = static_cast<int>(barWidth * progress);

cout << "[";
for (int i = 0; i < barWidth; ++i) {
if (i < pos) cout << "=";
else if (i == pos) cout << ">";
else cout << " ";
}
cout << "] " << int(progress * 100.0) << "%\r";
cout.flush();
}

void convertOctreeToPointCloud(const OcTree& tree, PointCloud::Ptr& free_cloud, PointCloud::Ptr& occupied_cloud) {
// Get the total number of leaf nodes for the progress bar
size_t total_leafs = tree.getNumLeafNodes();
Expand Down
11 changes: 11 additions & 0 deletions octomap_utils/include/progress_bar.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
// progress_bar.h

#ifndef PROGRESS_BAR_H
#define PROGRESS_BAR_H

#include <iostream>

// Function to display a simple progress bar
void displayProgressBar(size_t current, size_t total);

#endif // PROGRESS_BAR_H
19 changes: 19 additions & 0 deletions octomap_utils/progress_bar.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
#include "progress_bar.h"

void displayProgressBar(size_t current, size_t total) {
const int barWidth = 50; // Width of the progress bar
float progress = static_cast<float>(current) / total;
int pos = static_cast<int>(barWidth * progress);

std::cout << "[";
for (int i = 0; i < barWidth; ++i) {
if (i < pos)
std::cout << "=";
else if (i == pos)
std::cout << ">";
else
std::cout << " ";
}
std::cout << "] " << int(progress * 100.0) << "%\r";
std::cout.flush();
}

0 comments on commit b213526

Please sign in to comment.