Skip to content

Commit

Permalink
Apply clang-format-11 with new setting (#605)
Browse files Browse the repository at this point in the history
* Apply clang-format-11 with new setting
* Remove clang-format off/on
  • Loading branch information
nhatao authored Jul 9, 2021
1 parent 8261f44 commit 7ae1061
Show file tree
Hide file tree
Showing 19 changed files with 300 additions and 332 deletions.
3 changes: 2 additions & 1 deletion costmap_cspace/src/costmap_3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,8 @@ class Costmap3DOFNode
costmap_cspace::Costmap3d::Ptr costmap_;
std::vector<
std::pair<nav_msgs::OccupancyGrid::ConstPtr,
costmap_cspace::Costmap3dLayerBase::Ptr>> map_buffer_;
costmap_cspace::Costmap3dLayerBase::Ptr>>
map_buffer_;

void cbMap(
const nav_msgs::OccupancyGrid::ConstPtr& msg,
Expand Down
90 changes: 45 additions & 45 deletions costmap_cspace/test/src/test_costmap_3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
Expand Down Expand Up @@ -61,12 +61,12 @@ const std::string footprint_str(
// 0 0 0
const char temp_dir[4][2] =
{
// x, y which must be occupied in the template
-1, 0,
0, -1,
1, 0,
0, 1
};
// x, y which must be occupied in the template
{-1, 0},
{0, -1},
{1, 0},
{0, 1},
};

TEST(Costmap3dLayerFootprint, CSpaceTemplate)
{
Expand Down Expand Up @@ -411,8 +411,8 @@ TEST(Costmap3dLayerFootprint, CSpaceOverwrite)
const int num_points_base_map = 2;
const int points_base_map[num_points_base_map][2] =
{
2, 3,
4, 4
{2, 3},
{4, 4},
};
for (int i = 0; i < num_points_base_map; ++i)
{
Expand All @@ -422,9 +422,9 @@ TEST(Costmap3dLayerFootprint, CSpaceOverwrite)
const int num_points_local_map = 3;
const int points_local_map[num_points_local_map][2] =
{
3, 4,
5, 3,
4, 4
{3, 4},
{5, 3},
{4, 4},
};
for (int i = 0; i < num_points_local_map; ++i)
{
Expand All @@ -437,8 +437,8 @@ TEST(Costmap3dLayerFootprint, CSpaceOverwrite)
// Overlay local map
costmap_cspace_msgs::CSpace3DUpdate::Ptr updated(new costmap_cspace_msgs::CSpace3DUpdate);
auto cb = [&updated](
const costmap_cspace::CSpace3DMsg::Ptr map,
const costmap_cspace_msgs::CSpace3DUpdate::Ptr& update) -> bool
const costmap_cspace::CSpace3DMsg::Ptr map,
const costmap_cspace_msgs::CSpace3DUpdate::Ptr& update) -> bool
{
updated = update;
return true;
Expand Down Expand Up @@ -481,8 +481,8 @@ TEST(Costmap3dLayerFootprint, CSpaceOverwrite)
cm_over->setOverlayMode(costmap_cspace::MapOverlayMode::MAX);
costmap_cspace_msgs::CSpace3DUpdate::Ptr updated_max(new costmap_cspace_msgs::CSpace3DUpdate);
auto cb_max = [&updated_max](
const costmap_cspace::CSpace3DMsg::Ptr map,
const costmap_cspace_msgs::CSpace3DUpdate::Ptr& update) -> bool
const costmap_cspace::CSpace3DMsg::Ptr map,
const costmap_cspace_msgs::CSpace3DUpdate::Ptr& update) -> bool
{
updated_max = update;
return true;
Expand Down Expand Up @@ -613,32 +613,32 @@ TEST(Costmap3dLayerOutput, CSpaceOutOfBoundary)
};
const TestData dataset[] =
{
{ "inside0", { 0.0, 0.0 }, true, { 0u, 0u, 0u, 2u, 2u, 4u } },
{ "inside1", { 1.0, 0.0 }, true, { 1u, 0u, 0u, 2u, 2u, 4u } },
{ "half-outside x0", { -1.0, 0.0 }, true, { 0u, 0u, 0u, 1u, 2u, 4u } },
{ "half-outside x1", { 3.0, 0.0 }, true, { 3u, 0u, 0u, 1u, 2u, 4u } },
{ "half-outside y0", { 0.0, -1.0 }, true, { 0u, 0u, 0u, 2u, 1u, 4u } },
{ "half-outside y1", { 0.0, 3.0 }, true, { 0u, 3u, 0u, 2u, 1u, 4u } },
{ "half-outside xy0", { -1.0, -1.0 }, true, { 0u, 0u, 0u, 1u, 1u, 4u } },
{ "half-outside xy1", { 3.0, -1.0 }, true, { 3u, 0u, 0u, 1u, 1u, 4u } },
{ "half-outside xy2", { 3.0, 3.0 }, true, { 3u, 3u, 0u, 1u, 1u, 4u } },
{ "half-outside xy3", { -1.0, 3.0 }, true, { 0u, 3u, 0u, 1u, 1u, 4u } },
{ "boundary x0", { -2.0, 0.0 }, false },
{ "boundary x1", { 4, 0.0 }, false },
{ "boundary y0", { 0, -2.0 }, false },
{ "boundary y1", { 0, 4.0 }, false },
{ "boundary xy0", { -2.0, -2.0 }, false },
{ "boundary xy1", { 4.0, -2.0 }, false },
{ "boundary xy2", { 4.0, 4.0 }, false },
{ "boundary xy3", { -2.0, 4.0 }, false },
{ "outside x0", { -3.0, 0.0 }, false },
{ "outside x1", { 5, 0.0 }, false },
{ "outside y0", { 0, -3.0 }, false },
{ "outside y1", { 0, 5.0 }, false },
{ "outside xy0", { -3.0, -3.0 }, false },
{ "outside xy1", { 5.0, -3.0 }, false },
{ "outside xy2", { 5.0, 5.0 }, false },
{ "outside xy3", { -3.0, 5.0 }, false },
{"inside0", {0.0, 0.0}, true, {0u, 0u, 0u, 2u, 2u, 4u}},
{"inside1", {1.0, 0.0}, true, {1u, 0u, 0u, 2u, 2u, 4u}},
{"half-outside x0", {-1.0, 0.0}, true, {0u, 0u, 0u, 1u, 2u, 4u}},
{"half-outside x1", {3.0, 0.0}, true, {3u, 0u, 0u, 1u, 2u, 4u}},
{"half-outside y0", {0.0, -1.0}, true, {0u, 0u, 0u, 2u, 1u, 4u}},
{"half-outside y1", {0.0, 3.0}, true, {0u, 3u, 0u, 2u, 1u, 4u}},
{"half-outside xy0", {-1.0, -1.0}, true, {0u, 0u, 0u, 1u, 1u, 4u}},
{"half-outside xy1", {3.0, -1.0}, true, {3u, 0u, 0u, 1u, 1u, 4u}},
{"half-outside xy2", {3.0, 3.0}, true, {3u, 3u, 0u, 1u, 1u, 4u}},
{"half-outside xy3", {-1.0, 3.0}, true, {0u, 3u, 0u, 1u, 1u, 4u}},
{"boundary x0", {-2.0, 0.0}, false},
{"boundary x1", {4, 0.0}, false},
{"boundary y0", {0, -2.0}, false},
{"boundary y1", {0, 4.0}, false},
{"boundary xy0", {-2.0, -2.0}, false},
{"boundary xy1", {4.0, -2.0}, false},
{"boundary xy2", {4.0, 4.0}, false},
{"boundary xy3", {-2.0, 4.0}, false},
{"outside x0", {-3.0, 0.0}, false},
{"outside x1", {5, 0.0}, false},
{"outside y0", {0, -3.0}, false},
{"outside y1", {0, 5.0}, false},
{"outside xy0", {-3.0, -3.0}, false},
{"outside xy1", {5.0, -3.0}, false},
{"outside xy2", {5.0, 5.0}, false},
{"outside xy3", {-3.0, 5.0}, false},
};

for (auto& d : dataset)
Expand Down Expand Up @@ -675,8 +675,8 @@ TEST(Costmap3dLayerOutput, CSpaceOutOfBoundary)
// Overlay local map
costmap_cspace_msgs::CSpace3DUpdate::Ptr updated;
auto cb = [&updated](
const costmap_cspace::CSpace3DMsg::Ptr& map,
const costmap_cspace_msgs::CSpace3DUpdate::Ptr& update) -> bool
const costmap_cspace::CSpace3DMsg::Ptr& map,
const costmap_cspace_msgs::CSpace3DUpdate::Ptr& update) -> bool
{
updated = update;
return true;
Expand Down
2 changes: 1 addition & 1 deletion planner_cspace/include/planner_cspace/bbf.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ class BinaryBayesFilter
public:
explicit BinaryBayesFilter(
const float& initial_odds = 1.0) noexcept
: odds_(initial_odds)
: odds_(initial_odds)
{
}
float update(const float& odds)
Expand Down
8 changes: 4 additions & 4 deletions planner_cspace/include/planner_cspace/grid_astar.h
Original file line number Diff line number Diff line change
Expand Up @@ -278,10 +278,10 @@ class GridAstar
findPath(ss_normalized, better, path_tmp);
const SearchStats stats =
{
.num_loop = num_loop,
.num_search_queue = num_search_queue,
.num_prev_updates = num_updates,
.num_total_updates = num_total_updates,
.num_loop = num_loop,
.num_search_queue = num_search_queue,
.num_prev_updates = num_updates,
.num_total_updates = num_total_updates,
};
if (!cb_progress(path_tmp, stats))
{
Expand Down
12 changes: 6 additions & 6 deletions planner_cspace/src/motion_cache.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,9 +68,9 @@ void MotionCache::reset(
const float yaw_e = d[2] * angular_resolution;
const float diff_val[3] =
{
d[0] * linear_resolution,
d[1] * linear_resolution,
d[2] * angular_resolution
d[0] * linear_resolution,
d[1] * linear_resolution,
d[2] * angular_resolution,
};
std::unordered_map<CyclicVecInt<3, 2>, bool, CyclicVecInt<3, 2>> registered;
registered[d] = true;
Expand Down Expand Up @@ -133,9 +133,9 @@ void MotionCache::reset(

const float posf_raw[3] =
{
(cx2 - r * cosf(cyaw + M_PI / 2)) / linear_resolution,
(cy2 - r * sinf(cyaw + M_PI / 2)) / linear_resolution,
cyaw / angular_resolution
(cx2 - r * cosf(cyaw + M_PI / 2)) / linear_resolution,
(cy2 - r * sinf(cyaw + M_PI / 2)) / linear_resolution,
cyaw / angular_resolution,
};
const CyclicVecFloat<3, 2> posf(posf_raw[0], posf_raw[1], posf_raw[2]);
CyclicVecInt<3, 2> pos(posf_raw[0], posf_raw[1], posf_raw[2]);
Expand Down
2 changes: 1 addition & 1 deletion planner_cspace/src/planner_2dof_serial_joints.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ class Planner2dofSerialJointsNode

void cbJoint(const sensor_msgs::JointState::ConstPtr& msg)
{
int id[2] = { -1, -1 };
int id[2] = {-1, -1};
for (size_t i = 0; i < msg->name.size(); i++)
{
if (msg->name[i].compare(links_[0].name_) == 0)
Expand Down
16 changes: 5 additions & 11 deletions planner_cspace/src/planner_3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1115,9 +1115,9 @@ class Planner3dNode

const int size[3] =
{
static_cast<int>(map_info_.width),
static_cast<int>(map_info_.height),
static_cast<int>(map_info_.angle)
static_cast<int>(map_info_.width),
static_cast<int>(map_info_.height),
static_cast<int>(map_info_.angle),
};
as_.reset(Astar::Vec(size[0], size[1], size[2]));
cm_.reset(Astar::Vec(size[0], size[1], size[2]));
Expand Down Expand Up @@ -1645,14 +1645,8 @@ class Planner3dNode
std::vector<Astar::VecWithCost> starts;
if (antialias_start_)
{
const int x_cand[] =
{
0, ((sf[0] - s[0]) < 0.5 ? -1 : 1)
};
const int y_cand[] =
{
0, ((sf[1] - s[1]) < 0.5 ? -1 : 1)
};
const int x_cand[] = {0, ((sf[0] - s[0]) < 0.5 ? -1 : 1)};
const int y_cand[] = {0, ((sf[1] - s[1]) < 0.5 ? -1 : 1)};
for (const int x : x_cand)
{
for (const int y : y_cand)
Expand Down
10 changes: 2 additions & 8 deletions planner_cspace/test/src/test_blockmem_gridmap_performance.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,14 +38,8 @@ namespace planner_cspace
{
TEST(BlockmemGridmap, SpacialAccessPerformance)
{
constexpr int size[3] =
{
0x420, 0x420, 0x28
};
constexpr int pad[3] =
{
0x204, 0x204, 0x10
};
constexpr int size[3] = {0x420, 0x420, 0x28};
constexpr int pad[3] = {0x204, 0x204, 0x10};
constexpr int range = 0x10;
constexpr int repeat = 4;

Expand Down
24 changes: 12 additions & 12 deletions planner_cspace/test/src/test_costmap_bbf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,27 +74,27 @@ TEST(CostmapBBF, Update)
const float odds_miss = bbf::probabilityToOdds(0.3);
const char costmap0[3][3] =
{
{ 10, 100, 100 },
{ 100, 100, 100 },
{ 100, 100, 100 },
{10, 100, 100},
{100, 100, 100},
{100, 100, 100},
};
const char costmap1[3][3] =
{
{ 0, -1, 0 },
{ 100, 0, 0 },
{ 0, 0, 100 },
{0, -1, 0},
{100, 0, 0},
{0, 0, 100},
};
const float expected_odds[3][3] =
{
{ bbf::MIN_ODDS, bbf::MIN_ODDS * odds_hit, bbf::MIN_ODDS * odds_hit * odds_miss },
{ bbf::MIN_ODDS * odds_hit * odds_hit, bbf::MIN_ODDS * odds_hit * odds_miss, bbf::MIN_ODDS },
{ bbf::MIN_ODDS * odds_hit * odds_miss, bbf::MIN_ODDS, bbf::MIN_ODDS },
{bbf::MIN_ODDS, bbf::MIN_ODDS * odds_hit, bbf::MIN_ODDS * odds_hit * odds_miss},
{bbf::MIN_ODDS * odds_hit * odds_hit, bbf::MIN_ODDS * odds_hit * odds_miss, bbf::MIN_ODDS},
{bbf::MIN_ODDS * odds_hit * odds_miss, bbf::MIN_ODDS, bbf::MIN_ODDS},
};
const char expected_cost[3][3] =
{
{ 0, 26, 8 },
{ 68, 8, 0 },
{ 8, 0, 0 },
{0, 26, 8},
{68, 8, 0},
{8, 0, 0},
};
BlockMemGridmap<char, 3, 2> cm;

Expand Down
10 changes: 2 additions & 8 deletions planner_cspace/test/src/test_cyclic_vec.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,7 @@ namespace planner_cspace
{
TEST(CyclicVec, InitFloat)
{
const float val[3] =
{
1.0, 2.0, 3.0
};
const float val[3] = {1.0, 2.0, 3.0};
CyclicVecFloat<3, 2> v(1.0f, 2.0f, 3.0f);
const CyclicVecFloat<3, 2> vc(1.0f, 2.0f, 3.0f);

Expand All @@ -54,10 +51,7 @@ TEST(CyclicVec, InitFloat)

TEST(CyclicVec, InitInt)
{
const int val[3] =
{
1, 2, 3
};
const int val[3] = {1, 2, 3};
CyclicVecInt<3, 2> v(1, 2, 3);
const CyclicVecInt<3, 2> vc(1, 2, 3);

Expand Down
36 changes: 18 additions & 18 deletions planner_cspace/test/src/test_debug_outputs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,18 +160,18 @@ TEST_F(DebugOutputsTest, Hysteresis)
// Robot is at (25, 4) and goal is at (10, 4)
const PositionAndValue data_set[] =
{
{ 25, 4, 0 },
{ 20, 4, 0 },
{ 15, 4, 0 },
{ 10, 4, 0 },
{ 25, 1, 100 },
{ 20, 1, 100 },
{ 15, 1, 100 },
{ 10, 1, 100 },
{ 25, 7, 100 },
{ 20, 7, 100 },
{ 15, 7, 100 },
{ 10, 7, 100 },
{25, 4, 0},
{20, 4, 0},
{15, 4, 0},
{10, 4, 0},
{25, 1, 100},
{20, 1, 100},
{15, 1, 100},
{10, 1, 100},
{25, 7, 100},
{20, 7, 100},
{15, 7, 100},
{10, 7, 100},
};
for (auto data : data_set)
{
Expand All @@ -193,12 +193,12 @@ TEST_F(DebugOutputsTest, Remembered)
// Costmap is expanded by 1 grid.
const PositionAndValue data_set[] =
{
{ 17, 0, 100 }, // occupied
{ 17, 1, 100 }, // expanded
{ 17, 2, 0 }, // free
{ 17, 8, 0 }, // free
{ 17, 9, 100 }, // expanded
{ 17, 10, 100 }, // occupied
{17, 0, 100}, // occupied
{17, 1, 100}, // expanded
{17, 2, 0}, // free
{17, 8, 0}, // free
{17, 9, 100}, // expanded
{17, 10, 100}, // occupied
};
for (auto data : data_set)
{
Expand Down
Loading

0 comments on commit 7ae1061

Please sign in to comment.