Skip to content

Commit

Permalink
Change parameter name
Browse files Browse the repository at this point in the history
  • Loading branch information
nhatao committed Sep 12, 2023
1 parent 8b992e2 commit f2a3f38
Show file tree
Hide file tree
Showing 4 changed files with 18 additions and 16 deletions.
21 changes: 11 additions & 10 deletions costmap_cspace/include/costmap_cspace/costmap_3d_layer/footprint.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class Costmap3dLayerFootprint : public Costmap3dLayerBase
geometry_msgs::PolygonStamped footprint_;
float linear_expand_;
float linear_spread_;
int cutoff_cost_;
int linear_spread_min_cost_;
Polygon footprint_p_;
bool keep_unknown_;

Expand All @@ -72,18 +72,19 @@ class Costmap3dLayerFootprint : public Costmap3dLayerBase
Costmap3dLayerFootprint()
: linear_expand_(0.0)
, linear_spread_(0.0)
, cutoff_cost_(0)
, linear_spread_min_cost_(0)
, keep_unknown_(false)
, range_max_(0)
{
}
void loadConfig(XmlRpc::XmlRpcValue config)
{
const int cutoff_cost = config.hasMember("cutoff_cost") ? static_cast<int>(config["cutoff_cost"]) : 0;
const int linear_spread_min_cost =
config.hasMember("linear_spread_min_cost") ? static_cast<int>(config["linear_spread_min_cost"]) : 0;
setExpansion(
static_cast<double>(config["linear_expand"]),
static_cast<double>(config["linear_spread"]),
cutoff_cost);
linear_spread_min_cost);
setFootprint(costmap_cspace::Polygon(config["footprint"]));
if (config.hasMember("keep_unknown"))
setKeepUnknown(config["keep_unknown"]);
Expand All @@ -95,18 +96,18 @@ class Costmap3dLayerFootprint : public Costmap3dLayerBase
void setExpansion(
const float linear_expand,
const float linear_spread,
const int cutoff_cost = 0)
const int linear_spread_min_cost = 0)
{
linear_expand_ = linear_expand;
linear_spread_ = linear_spread;
cutoff_cost_ = cutoff_cost;
linear_spread_min_cost_ = linear_spread_min_cost;

ROS_ASSERT(linear_expand >= 0.0);
ROS_ASSERT(std::isfinite(linear_expand));
ROS_ASSERT(linear_spread >= 0.0);
ROS_ASSERT(std::isfinite(linear_spread));
ROS_ASSERT(cutoff_cost_ >= 0);
ROS_ASSERT(cutoff_cost_ < 100);
ROS_ASSERT(linear_spread_min_cost_ >= 0);
ROS_ASSERT(linear_spread_min_cost_ < 100);
}
void setFootprint(const Polygon footprint)
{
Expand Down Expand Up @@ -170,11 +171,11 @@ class Costmap3dLayerFootprint : public Costmap3dLayerBase
}
else if (d < linear_expand_ + linear_spread_)
{
cs_template_.e(x, y, yaw) = 100 - (d - linear_expand_) * (100 - cutoff_cost_) / linear_spread_;
cs_template_.e(x, y, yaw) = 100 - (d - linear_expand_) * (100 - linear_spread_min_cost_) / linear_spread_;
}
else if (std::abs(linear_expand_ + linear_spread_ - d) < eps)
{
cs_template_.e(x, y, yaw) = cutoff_cost_;
cs_template_.e(x, y, yaw) = linear_spread_min_cost_;
}
else
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,11 +59,12 @@ class Costmap3dLayerPlain : public Costmap3dLayerFootprint
}
void loadConfig(XmlRpc::XmlRpcValue config)
{
const int cutoff_cost = config.hasMember("cutoff_cost") ? static_cast<int>(config["cutoff_cost"]) : 0;
const int linear_spread_min_cost =
config.hasMember("linear_spread_min_cost") ? static_cast<int>(config["linear_spread_min_cost"]) : 0;
setExpansion(
static_cast<double>(config["linear_expand"]),
static_cast<double>(config["linear_spread"]),
cutoff_cost);
linear_spread_min_cost);
}
};
} // namespace costmap_cspace
Expand Down
6 changes: 3 additions & 3 deletions costmap_cspace/src/costmap_3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -213,9 +213,9 @@ class Costmap3DOFNode
float linear_spread;
pnh_.param("linear_expand", linear_expand, 0.2f);
pnh_.param("linear_spread", linear_spread, 0.5f);
int cutoff_cost;
pnh_.param("cutoff_cost", cutoff_cost, 0);
root_layer->setExpansion(linear_expand, linear_spread, cutoff_cost);
int linear_spread_min_cost;
pnh_.param("linear_spread_min_cost", linear_spread_min_cost, 0);
root_layer->setExpansion(linear_expand, linear_spread, linear_spread_min_cost);
root_layer->setFootprint(footprint);

if (pnh_.hasParam("static_layers"))
Expand Down
2 changes: 1 addition & 1 deletion costmap_cspace/test/src/test_costmap_3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1021,7 +1021,7 @@ TEST(Costmap3dLayerFootprint, PlainOnFootprint)
}
}

TEST(Costmap3dLayerOutput, CutoffCost)
TEST(Costmap3dLayerOutput, LinearSpreadMinCost)
{
// clang-format off
const std::vector<int8_t> input_base(49, 0);
Expand Down

0 comments on commit f2a3f38

Please sign in to comment.