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

@@ -62,26 +62,18 @@ void ObstacleLayer::onInitialize()
current_ = true;
stop_receiving_data_ = false;
global_frame_ = layered_costmap_->getGlobalFrameID();
getParams();
std::string config_file_name = name_ + ".yaml";
getParams(config_file_name);
}
ObstacleLayer::~ObstacleLayer()
{}
bool ObstacleLayer::getParams()
bool ObstacleLayer::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);
@@ -94,9 +86,9 @@ bool ObstacleLayer::getParams()
default_value_ = FREE_SPACE;
double transform_tolerance = loadParam(layer,"transform_tolerance", 0.2);
// get the topics that we'll subscribe to from the parameter server
std::string topics_string = loadParam(layer,"observation_sources", std::string(""));
printf(" Subscribed to Topics: %s\n", topics_string.c_str());
// // get the topics that we'll subscribe to from the parameter server
// std::string topics_string = loadParam(layer,"observation_sources", std::string(""));
// printf("Subscribed to Topics: %s\n", topics_string.c_str());
// get the parameters for the specific topic
double observation_keep_time = 0, expected_update_rate = 0, min_obstacle_height = 0, max_obstacle_height = 2;