Skip to content

Commit 59f1f70

Browse files
authored
Use unsigned char instead of non-standard u_char type (#4867)
Signed-off-by: Silvio Traversaro <silvio@traversaro.it>
1 parent fe8bf72 commit 59f1f70

File tree

3 files changed

+11
-9
lines changed

3 files changed

+11
-9
lines changed

nav2_constrained_smoother/include/nav2_constrained_smoother/smoother.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -142,10 +142,10 @@ class Smoother
142142
std::vector<bool> & optimized)
143143
{
144144
// Create costmap grid
145-
costmap_grid_ = std::make_shared<ceres::Grid2D<u_char>>(
145+
costmap_grid_ = std::make_shared<ceres::Grid2D<unsigned char>>(
146146
costmap->getCharMap(), 0, costmap->getSizeInCellsY(), 0, costmap->getSizeInCellsX());
147-
auto costmap_interpolator = std::make_shared<ceres::BiCubicInterpolator<ceres::Grid2D<u_char>>>(
148-
*costmap_grid_);
147+
auto costmap_interpolator =
148+
std::make_shared<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>>(*costmap_grid_);
149149

150150
// Create residual blocks
151151
const double cusp_half_length = params.cusp_zone_length / 2;
@@ -394,7 +394,7 @@ class Smoother
394394

395395
bool debug_;
396396
ceres::Solver::Options options_;
397-
std::shared_ptr<ceres::Grid2D<u_char>> costmap_grid_;
397+
std::shared_ptr<ceres::Grid2D<unsigned char>> costmap_grid_;
398398
};
399399

400400
} // namespace nav2_constrained_smoother

nav2_constrained_smoother/include/nav2_constrained_smoother/smoother_cost_function.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,8 @@ class SmootherCostFunction
5757
double next_to_last_length_ratio,
5858
bool reversing,
5959
const nav2_costmap_2d::Costmap2D * costmap,
60-
const std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<u_char>>> & costmap_interpolator,
60+
const std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>> &
61+
costmap_interpolator,
6162
const SmootherParams & params,
6263
double costmap_weight)
6364
: original_pos_(original_pos),
@@ -244,7 +245,7 @@ class SmootherCostFunction
244245
double costmap_weight_;
245246
Eigen::Vector2d costmap_origin_;
246247
double costmap_resolution_;
247-
std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<u_char>>> costmap_interpolator_;
248+
std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>> costmap_interpolator_;
248249
};
249250

250251
} // namespace nav2_constrained_smoother

nav2_constrained_smoother/test/test_smoother_cost_function.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,8 @@ class TestableSmootherCostFunction : nav2_constrained_smoother::SmootherCostFunc
3333
double next_to_last_length_ratio,
3434
bool reversing,
3535
const nav2_costmap_2d::Costmap2D * costmap,
36-
const std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<u_char>>> & costmap_interpolator,
36+
const std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>> &
37+
costmap_interpolator,
3738
const nav2_constrained_smoother::SmootherParams & params,
3839
double costmap_weight)
3940
: SmootherCostFunction(
@@ -68,7 +69,7 @@ TEST_F(Test, testingCurvatureResidual)
6869
nav2_costmap_2d::Costmap2D costmap;
6970
TestableSmootherCostFunction fn(
7071
Eigen::Vector2d(1.0, 0.0), 1.0, false,
71-
&costmap, std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<u_char>>>(),
72+
&costmap, std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>>(),
7273
nav2_constrained_smoother::SmootherParams(), 0.0
7374
);
7475

@@ -81,7 +82,7 @@ TEST_F(Test, testingCurvatureResidual)
8182
params_no_min_turning_radius.max_curvature = 1.0f / 0.0;
8283
TestableSmootherCostFunction fn_no_min_turning_radius(
8384
Eigen::Vector2d(1.0, 0.0), 1.0, false,
84-
&costmap, std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<u_char>>>(),
85+
&costmap, std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>>(),
8586
params_no_min_turning_radius, 0.0
8687
);
8788
EXPECT_EQ(fn_no_min_turning_radius.getCurvatureResidual(1.0, pt, pt_other, pt_other), 0.0);

0 commit comments

Comments
 (0)