Skip to content

Commit

Permalink
Add map editing examples for C++ API
Browse files Browse the repository at this point in the history
  • Loading branch information
victorreijgwart committed Dec 13, 2024
1 parent 7392f41 commit a908112
Show file tree
Hide file tree
Showing 9 changed files with 127 additions and 8 deletions.
15 changes: 15 additions & 0 deletions examples/cpp/edit/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,19 @@
# Binaries
add_executable(crop_map crop_map.cc)
set_wavemap_target_properties(crop_map)
target_link_libraries(crop_map PUBLIC
wavemap::wavemap_core wavemap::wavemap_io)

add_executable(multiply_map multiply_map.cc)
set_wavemap_target_properties(multiply_map)
target_link_libraries(multiply_map PUBLIC
wavemap::wavemap_core wavemap::wavemap_io)

add_executable(sum_map sum_map.cc)
set_wavemap_target_properties(sum_map)
target_link_libraries(sum_map PUBLIC
wavemap::wavemap_core wavemap::wavemap_io)

add_executable(transform_map transform_map.cc)
set_wavemap_target_properties(transform_map)
target_link_libraries(transform_map PUBLIC
Expand Down
30 changes: 30 additions & 0 deletions examples/cpp/edit/crop_map.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#include <memory>

#include <wavemap/core/common.h>
#include <wavemap/core/utils/edit/crop.h>
#include <wavemap/io/file_conversions.h>

int main(int, char**) {
// Load the map
const std::filesystem::path home_dir = CHECK_NOTNULL(getenv("HOME"));
const std::filesystem::path input_map_path = home_dir / "your_map.wvmp";
wavemap::MapBase::Ptr map_base;
bool success = wavemap::io::fileToMap(input_map_path, map_base);
CHECK(success);

// Downcast it to a concrete map type
auto map = std::dynamic_pointer_cast<wavemap::HashedWaveletOctree>(map_base);
CHECK_NOTNULL(map);

// Crop the map
const wavemap::Point3D t_W_center{-2.2, -1.4, 0.0};
const wavemap::FloatingPoint radius = 3.0;
auto thread_pool = std::make_shared<wavemap::ThreadPool>(); // Optional
wavemap::edit::crop_to_sphere(*map, t_W_center, radius, 0, thread_pool);

// Save the map
const std::filesystem::path output_map_path =
home_dir / "your_map_cropped.wvmp";
success &= wavemap::io::mapToFile(*map, output_map_path);
CHECK(success);
}
29 changes: 29 additions & 0 deletions examples/cpp/edit/multiply_map.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
#include <memory>

#include <wavemap/core/common.h>
#include <wavemap/core/utils/edit/multiply.h>
#include <wavemap/io/file_conversions.h>

int main(int, char**) {
// Load the map
const std::filesystem::path home_dir = CHECK_NOTNULL(getenv("HOME"));
const std::filesystem::path input_map_path = home_dir / "your_map.wvmp";
wavemap::MapBase::Ptr map_base;
bool success = wavemap::io::fileToMap(input_map_path, map_base);
CHECK(success);

// Downcast it to a concrete map type
auto map = std::dynamic_pointer_cast<wavemap::HashedWaveletOctree>(map_base);
CHECK_NOTNULL(map);

// Use the multiply method to implement exponential forgetting
const wavemap::FloatingPoint decay_factor = 0.9;
auto thread_pool = std::make_shared<wavemap::ThreadPool>(); // Optional
wavemap::edit::multiply(*map, decay_factor, thread_pool);

// Save the map
const std::filesystem::path output_map_path =
home_dir / "your_map_decayed.wvmp";
success &= wavemap::io::mapToFile(*map, output_map_path);
CHECK(success);
}
40 changes: 40 additions & 0 deletions examples/cpp/edit/sum_map.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
#include <memory>

#include <wavemap/core/common.h>
#include <wavemap/core/utils/edit/crop.h>
#include <wavemap/core/utils/edit/sum.h>
#include <wavemap/core/utils/edit/transform.h>
#include <wavemap/io/file_conversions.h>

int main(int, char**) {
// Load the map
const std::filesystem::path home_dir = CHECK_NOTNULL(getenv("HOME"));
const std::filesystem::path input_map_path = home_dir / "your_map.wvmp";
wavemap::MapBase::Ptr map_base;
bool success = wavemap::io::fileToMap(input_map_path, map_base);
CHECK(success);

// Downcast it to a concrete map type
auto map = std::dynamic_pointer_cast<wavemap::HashedWaveletOctree>(map_base);
CHECK_NOTNULL(map);

// Crop the map
const wavemap::Point3D t_W_center{-2.2, -1.4, 0.0};
const wavemap::FloatingPoint radius = 3.0;
auto thread_pool = std::make_shared<wavemap::ThreadPool>(); // Optional
wavemap::edit::crop_to_sphere(*map, t_W_center, radius, 0, thread_pool);

// Create a translated copy
wavemap::Transformation3D T_AB;
T_AB.getPosition() = {5.0, 5.0, 0.0};
auto map_translated = wavemap::edit::transform(*map, T_AB, thread_pool);

// Merge them together
wavemap::edit::sum(*map, *map_translated);

// Save the map
const std::filesystem::path output_map_path =
home_dir / "your_map_merged.wvmp";
success &= wavemap::io::mapToFile(*map, output_map_path);
CHECK(success);
}
12 changes: 6 additions & 6 deletions examples/cpp/edit/transform_map.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@

int main(int, char**) {
// Load the map
std::filesystem::path input_map_path =
"/home/victor/data/wavemaps/newer_college_cloister_10cm.wvmp";
const std::filesystem::path home_dir = CHECK_NOTNULL(getenv("HOME"));
const std::filesystem::path input_map_path = home_dir / "your_map.wvmp";
wavemap::MapBase::Ptr map_base;
bool success = wavemap::io::fileToMap(input_map_path, map_base);
CHECK(success);
Expand All @@ -21,12 +21,12 @@ int main(int, char**) {
T_AB.getRotation() = wavemap::Rotation3D{0.f, 1.f, 0.f, 0.f};

// Transform the map
map = wavemap::edit::transform(*map, T_AB,
std::make_shared<wavemap::ThreadPool>());
auto thread_pool = std::make_shared<wavemap::ThreadPool>(); // Optional
map = wavemap::edit::transform(*map, T_AB, thread_pool);

// Save the map
std::filesystem::path output_map_path =
"/home/victor/data/wavemaps/newer_college_cloister_10cm_tranformed.wvmp";
const std::filesystem::path output_map_path =
home_dir / "your_map_transformed.wvmp";
success &= wavemap::io::mapToFile(*map, output_map_path);
CHECK(success);
}
4 changes: 2 additions & 2 deletions library/cpp/include/wavemap/core/utils/edit/crop.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,12 @@ void cropNodeRecursive(typename MapT::Block::OctreeType::NodeRefType node,
const OctreeIndex& node_index, FloatingPoint& node_value,
const Point3D& t_W_center, FloatingPoint radius,
FloatingPoint min_cell_width,
IndexElement termination_height);
IndexElement termination_height = 0);
} // namespace detail

template <typename MapT>
void crop_to_sphere(MapT& map, const Point3D& t_W_center, FloatingPoint radius,
IndexElement termination_height,
IndexElement termination_height = 0,
const std::shared_ptr<ThreadPool>& thread_pool = nullptr);
} // namespace wavemap::edit

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@

#include <memory>

#include "wavemap/core/indexing/ndtree_index.h"

namespace wavemap::edit {
namespace detail {
template <typename MapT>
Expand Down
2 changes: 2 additions & 0 deletions library/cpp/include/wavemap/core/utils/edit/impl/sum_inl.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
#include <memory>
#include <utility>

#include "wavemap/core/indexing/index_conversions.h"

namespace wavemap::edit {
namespace detail {
template <typename MapT, typename SamplingFn>
Expand Down
1 change: 1 addition & 0 deletions library/cpp/include/wavemap/core/utils/edit/sum.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
#include <memory>

#include "wavemap/core/common.h"
#include "wavemap/core/indexing/ndtree_index.h"
#include "wavemap/core/utils/thread_pool.h"

namespace wavemap::edit {
Expand Down

0 comments on commit a908112

Please sign in to comment.