them file test static_layer

This commit is contained in:
2025-11-07 17:44:42 +07:00
parent 79e706b798
commit 498b606e15
148 changed files with 6363 additions and 1599 deletions

View File

@@ -2,9 +2,9 @@
#include <costmap_2d/inflation_layer.h>
#include <costmap_2d/costmap_math.h>
#include <costmap_2d/footprint.h>
#include <costmap_2d/utils.h>
#include <boost/thread.hpp>
// PLUGINLIB_EXPORT_CLASS(costmap_2d::InflationLayer, costmap_2d::Layer)
#include <boost/dll/alias.hpp>
using costmap_2d::LETHAL_OBSTACLE;
using costmap_2d::INSCRIBED_INFLATED_OBSTACLE;
@@ -54,13 +54,14 @@ bool InflationLayer::getParams()
{
try {
YAML::Node config = YAML::LoadFile("../cfg/config.yaml");
double cost_scaling_factor = config["inflation_layer"]["cost_scaling_factor"].as<double>();
double inflation_radius = config["inflation_layer"]["inflation_radius"].as<double>();
YAML::Node layer = config["inflation_layer"];
double cost_scaling_factor = loadParam(layer, "cost_scaling_factor", 15.0);
double inflation_radius = loadParam(layer, "inflation_radius", 0.55);
setInflationParameters(inflation_radius, cost_scaling_factor);
bool enabled = config["inflation_layer"]["enabled"].as<bool>();
bool inflate_unknown = config["inflation_layer"]["inflate_unknown"].as<bool>();
bool enabled = loadParam(layer, "enabled", true);
bool inflate_unknown = loadParam(layer, "inflate_unknown", false);
if (enabled_ != enabled || inflate_unknown_ != inflate_unknown) {
enabled_ = enabled;
inflate_unknown_ = inflate_unknown;