update file costmap_2d_robot and file config params

This commit is contained in:
2025-12-03 11:36:06 +07:00
parent 64db092d46
commit 4fb2554291
16 changed files with 169 additions and 130 deletions

View File

@@ -54,26 +54,18 @@ namespace costmap_2d
void VoxelLayer::onInitialize()
{
ObstacleLayer::onInitialize();
getParams();
std::string config_file_name = name_ + ".yaml";
getParams(config_file_name);
}
VoxelLayer::~VoxelLayer()
{}
bool VoxelLayer::getParams()
bool VoxelLayer::getParams(const std::string& config_file_name)
{
try {
std::string config_file_name = "config.yaml";
std::string folder = COSTMAP_2D_DIR;
std::string path_source = getSourceFile(folder,config_file_name);
if(path_source != " ")
{
std::cout << "Path source: " << path_source << std::endl;
}
else
{
std::cout << "/cfg folder not found!" << std::endl;
}
YAML::Node config = YAML::LoadFile(path_source);
YAML::Node layer = config["voxel_layer"];
@@ -82,12 +74,12 @@ bool VoxelLayer::getParams()
enabled_ = loadParam(layer, "enabled", true);
footprint_clearing_enabled_ = loadParam(layer, "footprint_clearing_enabled", true);
max_obstacle_height_ = loadParam(layer, "max_obstacle_height", 2.0);
size_z_ = loadParam(layer, "z_voxels", 10);
origin_z_ = loadParam(layer, "origin_z", 0);
size_z_ = loadParam(layer, "z_voxels", 10.0);
origin_z_ = loadParam(layer, "origin_z", 0.0);
z_resolution_ = loadParam(layer, "z_resolution", 0.2);
unknown_threshold_ = loadParam(layer, "max_obstacle_height", 15);
unknown_threshold_ = loadParam(layer, "unknown_threshold", 15.0) + (VOXEL_BITS - size_z_);
mark_threshold_ = loadParam(layer, "mark_threshold", 0);
combination_method_ = loadParam(layer, "combination_method", true);
combination_method_ = loadParam(layer, "combination_method", 0.0);
this->matchSize();
}
catch (const YAML::BadFile& e) {