Skip to content

Commit

Permalink
cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
amock committed Nov 19, 2024
1 parent acb2c0f commit c983453
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 14 deletions.
14 changes: 10 additions & 4 deletions mesh_map/include/mesh_map/mesh_map.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
11 changes: 1 addition & 10 deletions mesh_map/src/mesh_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -358,9 +358,6 @@ bool MeshMap::readMap()
return false;
}

// why?
sleep(1);

combineVertexCosts(map_stamp);
publishCostLayers(map_stamp);

Expand Down Expand Up @@ -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());
Expand All @@ -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<float>(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);
Expand Down

0 comments on commit c983453

Please sign in to comment.