From c983453db1e5bfda7b5563aec3850e22eeaf2e8c Mon Sep 17 00:00:00 2001 From: Alexander Mock Date: Tue, 19 Nov 2024 11:46:03 +0100 Subject: [PATCH] cleanup --- mesh_map/include/mesh_map/mesh_map.h | 14 ++++++++++---- mesh_map/src/mesh_map.cpp | 11 +---------- 2 files changed, 11 insertions(+), 14 deletions(-) diff --git a/mesh_map/include/mesh_map/mesh_map.h b/mesh_map/include/mesh_map/mesh_map.h index fce005dc..84c1c1d3 100644 --- a/mesh_map/include/mesh_map/mesh_map.h +++ b/mesh_map/include/mesh_map/mesh_map.h @@ -434,16 +434,22 @@ class MeshMap //! global frame / coordinate system id std::string global_frame; - //! mesh file + //! Filename of the input mesh. Can be any format the assimp library supports to load. + //! https://github.com/assimp/assimp/blob/master/doc/Fileformats.md std::string mesh_file; - //! mesh part + //! Part of the mesh that is loaded for navigation + //! For HDF5 meshes this is the H5 group name of the desired mesh part + //! For standard formats this would be the internal path thorugh the scene graph to the mesh std::string mesh_part; - //! mesh working file + //! This is the filename of the file where the work is done. Choosing it differently from the + //! input mesh prevents from accidentially overwrite your input data. + //! By default it will be set to the input mesh filename. + //! The working file must be of format HDF5 std::string mesh_working_file; - //! mesh working part + //! The name of the mesh part that is used for navigation stored to the working file std::string mesh_working_part; //! dynamic params callback handle diff --git a/mesh_map/src/mesh_map.cpp b/mesh_map/src/mesh_map.cpp index bc346c5e..2dfcb196 100644 --- a/mesh_map/src/mesh_map.cpp +++ b/mesh_map/src/mesh_map.cpp @@ -358,9 +358,6 @@ bool MeshMap::readMap() return false; } - // why? - sleep(1); - combineVertexCosts(map_stamp); publishCostLayers(map_stamp); @@ -465,10 +462,6 @@ bool MeshMap::initLayerPlugins() { RCLCPP_INFO_STREAM(node->get_logger(), "Computing layer '" << layer_name << "' ..."); layer_plugin->computeLayer(); - - // RCLCPP_INFO_STREAM(node->get_logger(), "Writing '" << layer_name << "' to file."); - // layer_plugin->writeLayer(); - // RCLCPP_INFO_STREAM(node->get_logger(), "Finished writing '" << layer_name << "' to file."); } lethal_indices[layer_name].insert(layer_plugin->lethals().begin(), layer_plugin->lethals().end()); @@ -495,9 +488,7 @@ void MeshMap::combineVertexCosts(const rclcpp::Time& map_stamp) mesh_map::getMinMax(costs, min, max); const float norm = max - min; const float factor = 1.0; - // TODO how to declare param for each plugin? - // Needs to be done after plugins are loaded, which happens when the map gets loaded. Who calls readMap() and when? - // const float factor = private_nh.param(MESH_MAP_NAMESPACE + "/" + layer.first + "/factor", 1.0); + // TODO: carefully think about this const float norm_factor = factor / norm; RCLCPP_INFO_STREAM(node->get_logger(), "Layer \"" << layer.first << "\" max value: " << max << " min value: " << min << " norm: " << norm << " factor: " << factor << " norm factor: " << norm_factor);