test_planner_3d_cost.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <list>
31 #include <vector>
32 
33 #include <costmap_cspace_msgs/MapMetaData3D.h>
35 
36 #include <gtest/gtest.h>
37 
38 namespace planner_cspace
39 {
40 namespace planner_3d
41 {
43 {
44  costmap_cspace_msgs::MapMetaData3D map_info;
45  map_info.width = 100;
46  map_info.height = 100;
47  map_info.angle = 16;
48  map_info.linear_resolution = 1.0;
49  map_info.angular_resolution = M_PI * 2 / map_info.angle;
51  BlockMemGridmap<float, 3, 2> cost_estim_cache(GridAstarModel3D::Vec(100, 100, 16));
52  cm.clear(0);
53  cost_estim_cache.clear(0.0);
54  CostCoeff cc;
55  cc.weight_decel_ = 0.1;
56  cc.weight_backward_ = 0.1;
57  cc.weight_ang_vel_ = 1.0;
58  cc.weight_costmap_ = 0.1;
59  cc.weight_costmap_turn_ = 0.1;
60  cc.weight_remembered_ = 0.0;
61  cc.weight_hysteresis_ = 0.0;
62  cc.in_place_turn_ = 0.0;
63  cc.hysteresis_max_dist_ = 0.0;
64  cc.hysteresis_expand_ = 0.0;
65  cc.min_curve_radius_ = 0.0;
66  cc.max_vel_ = 1.0;
67  cc.max_ang_vel_ = 1.0;
68  cc.angle_resolution_aspect_ = 1.0;
70 
71  GridAstarModel3D model(
72  map_info,
73  GridAstarModel3D::Vecf(1.0f, 1.0f, 0.1f),
74  100.0,
75  cost_estim_cache, cm, cm, cm,
76  cc, 10);
77 
78  const GridAstarModel3D::Vec start(54, 50, 8);
79  const GridAstarModel3D::Vec goal_straight(50, 50, 8);
80  const GridAstarModel3D::Vec goal_curve(50, 50, 7);
81  const GridAstarModel3D::Vec goal_drift(50, 51, 8);
82  const GridAstarModel3D::Vec goal_curve_drift(50, 51, 7);
83  const GridAstarModel3D::Vec goal_curve_sign_err(50, 51, 9);
84  std::vector<GridAstarModel3D::VecWithCost> starts;
85  starts.emplace_back(start);
86 
87  const float c_straight = model.cost(start, goal_straight, starts, goal_straight);
88  const float c_curve = model.cost(start, goal_curve, starts, goal_curve);
89  const float c_drift = model.cost(start, goal_drift, starts, goal_drift);
90  const float c_drift_curve = model.cost(start, goal_curve_drift, starts, goal_curve_drift);
91 
92  EXPECT_LT(c_straight, c_curve);
93  EXPECT_LT(c_straight, c_drift);
94  EXPECT_LT(c_straight, c_drift_curve);
95 
96  // These tests are added to confirm that some bugs are fixed by https://github.com/at-wat/neonavigation/pull/725
97  const GridAstarModel3D::Vec start2(5, 5, 0);
98  const GridAstarModel3D::Vec occupied_waypoint(10, 5, 0);
99  const GridAstarModel3D::Vec goal2(10, 5, 3);
100  cm[occupied_waypoint] = 100;
101  // The cost toward the occupied cell should be negative.
102  EXPECT_LT(model.cost(start2, occupied_waypoint, {GridAstarModel3D::VecWithCost(start2)}, occupied_waypoint), 0);
103  // The cost from the occupied cell should be negative.
104  EXPECT_LT(model.cost(occupied_waypoint, goal2, {GridAstarModel3D::VecWithCost(occupied_waypoint)}, goal2), 0);
105 
106  const GridAstarModel3D::Vec start3(10, 20, 0);
107  cm[start3] = 99;
108  const GridAstarModel3D::Vec waypoint3(10, 20, 3);
109  const GridAstarModel3D::Vec goal3(10, 20, 6);
110  // The cost between start3 and waypoint3 is larger than the cost between waypoint3 and goal3 because start3
111  // has a penalty.
112  EXPECT_GT(model.cost(start3, waypoint3, {GridAstarModel3D::VecWithCost(start3)}, waypoint3),
113  model.cost(waypoint3, goal3, {GridAstarModel3D::VecWithCost(waypoint3)}, goal3));
114 }
115 } // namespace planner_3d
116 } // namespace planner_cspace
117 
118 int main(int argc, char** argv)
119 {
120  testing::InitGoogleTest(&argc, argv);
121 
122  return RUN_ALL_TESTS();
123 }
planner_cspace::planner_3d::CostCoeff
Definition: planner_3d/grid_astar_model.h:51
planner_cspace::planner_3d::CostCoeff::max_ang_vel_
float max_ang_vel_
Definition: planner_3d/grid_astar_model.h:67
planner_cspace
Definition: bbf.h:33
planner_cspace::planner_3d::CostCoeff::weight_decel_
float weight_decel_
Definition: planner_3d/grid_astar_model.h:54
planner_cspace::planner_3d::GridAstarModel3D::cost
float cost(const Vec &cur, const Vec &next, const std::vector< VecWithCost > &start, const Vec &goal) const override
Definition: grid_astar_model_3dof.cpp:170
planner_cspace::planner_3d::CostCoeff::weight_costmap_turn_
float weight_costmap_turn_
Definition: planner_3d/grid_astar_model.h:58
planner_cspace::planner_3d::GridAstarModel3D
Definition: planner_3d/grid_astar_model.h:72
planner_cspace::planner_3d::CostCoeff::weight_ang_vel_
float weight_ang_vel_
Definition: planner_3d/grid_astar_model.h:56
planner_cspace::BlockMemGridmap
Definition: blockmem_gridmap.h:67
grid_astar_model.h
planner_cspace::planner_3d::TEST
TEST(CostmapBBFImpl, ForEach)
Definition: test_costmap_bbf.cpp:42
f
f
planner_cspace::planner_3d::CostCoeff::turn_penalty_cost_threshold_
int turn_penalty_cost_threshold_
Definition: planner_3d/grid_astar_model.h:69
planner_cspace::planner_3d::CostCoeff::angle_resolution_aspect_
float angle_resolution_aspect_
Definition: planner_3d/grid_astar_model.h:68
planner_cspace::planner_3d::CostCoeff::max_vel_
float max_vel_
Definition: planner_3d/grid_astar_model.h:66
planner_cspace::planner_3d::CostCoeff::min_curve_radius_
float min_curve_radius_
Definition: planner_3d/grid_astar_model.h:65
planner_cspace::planner_3d::CostCoeff::weight_remembered_
float weight_remembered_
Definition: planner_3d/grid_astar_model.h:60
start
ROSCPP_DECL void start()
planner_cspace::planner_3d::CostCoeff::hysteresis_max_dist_
float hysteresis_max_dist_
Definition: planner_3d/grid_astar_model.h:63
planner_cspace::planner_3d::CostCoeff::hysteresis_expand_
float hysteresis_expand_
Definition: planner_3d/grid_astar_model.h:64
planner_cspace::BlockMemGridmap::clear
void clear(const T zero) override
Definition: blockmem_gridmap.h:129
planner_cspace::planner_3d::CostCoeff::weight_costmap_
float weight_costmap_
Definition: planner_3d/grid_astar_model.h:57
planner_cspace::planner_3d::CostCoeff::in_place_turn_
float in_place_turn_
Definition: planner_3d/grid_astar_model.h:62
planner_cspace::planner_3d::CostCoeff::weight_hysteresis_
float weight_hysteresis_
Definition: planner_3d/grid_astar_model.h:61
main
int main(int argc, char **argv)
Definition: test_planner_3d_cost.cpp:118
planner_cspace::planner_3d::CostCoeff::weight_backward_
float weight_backward_
Definition: planner_3d/grid_astar_model.h:55
planner_cspace::CyclicVecBase
Definition: cyclic_vec.h:78


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:23