34 #include <gtest/gtest.h> 47 #include <geometry_msgs/Point.h> 48 #include <base_local_planner/Position2DInt.h> 59 void correctFootprint();
60 void footprintObstacles();
61 void checkGoalDistance();
62 void checkPathDistance();
72 : map_(g), wa(wave), cm(map), tc(cm, map, footprint_spec, 0.0, 1.0, 1.0, 1.0, 1.0, 2.0)
79 map_->operator ()(4, 6).target_dist = 1;
84 tc.
generateTrajectory(4.5, 4.5, M_PI_2, 0, 0, 0, 4, 0, 0, 4, 0, 0,
DBL_MAX, traj);
86 EXPECT_FLOAT_EQ(traj.cost_, -1.0);
99 tc.
generateTrajectory(4.5, 4.5, M_PI_2, 0, 0, 0, 0, 0, M_PI_2, 0, 0, M_PI_4, 100, traj);
101 EXPECT_FLOAT_EQ(traj.cost_, -1.0);
106 map_->operator ()(1, 2).target_dist = 1;
107 map_->operator ()(1, 1).target_dist = 1;
108 map_->operator ()(1, 0).target_dist = 1;
109 map_->operator ()(2, 0).target_dist = 1;
110 map_->operator ()(3, 0).target_dist = 1;
111 map_->operator ()(3, 1).target_dist = 1;
112 map_->operator ()(3, 2).target_dist = 1;
113 map_->operator ()(2, 2).target_dist = 1;
118 queue<MapCell*> target_dist_queue;
122 target_dist_queue.push(¤t);
125 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 8).target_dist, 1.0);
126 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 7).target_dist, 2.0);
127 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 6).target_dist, 100.0);
128 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 5).target_dist, 6.0);
129 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 4).target_dist, 7.0);
130 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 3).target_dist, 8.0);
131 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 2).target_dist, 9.0);
132 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 1).target_dist, 10.0);
133 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 0).target_dist, 11.0);
134 EXPECT_FLOAT_EQ(
tc.
path_map_(5, 8).target_dist, 2.0);
135 EXPECT_FLOAT_EQ(
tc.
path_map_(9, 4).target_dist, 10.0);
138 EXPECT_FLOAT_EQ(100.0,
tc.
path_map_(2, 2).target_dist);
144 queue<MapCell*> target_dist_queue;
148 target_dist_queue.push(¤t);
151 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 8).target_dist, 1.0);
152 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 7).target_dist, 2.0);
153 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 6).target_dist, 100.0);
154 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 5).target_dist, 6.0);
155 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 4).target_dist, 7.0);
156 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 3).target_dist, 8.0);
157 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 2).target_dist, 9.0);
158 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 1).target_dist, 10.0);
159 EXPECT_FLOAT_EQ(
tc.
path_map_(4, 0).target_dist, 11.0);
160 EXPECT_FLOAT_EQ(
tc.
path_map_(5, 8).target_dist, 2.0);
161 EXPECT_FLOAT_EQ(
tc.
path_map_(9, 4).target_dist, 10.0);
164 EXPECT_FLOAT_EQ(
tc.
path_map_(2, 2).target_dist, 100.0);
176 std::vector<geometry_msgs::Point> footprint_spec;
177 geometry_msgs::Point pt;
181 footprint_spec.push_back(pt);
184 footprint_spec.push_back(pt);
187 footprint_spec.push_back(pt);
190 footprint_spec.push_back(pt);
Computes control velocities for a robot given a costmap, a plan, and the robot's position in the worl...
void footprintObstacles()
void computeTargetDistance(std::queue< MapCell * > &dist_queue, const costmap_2d::Costmap2D &costmap)
Compute the distance from each cell in the local map grid to the planned path.
WavefrontMapAccessor * wa
const costmap_2d::Costmap2D & costmap_
Provides access to cost map information.
TrajectoryPlannerTest * tct
MapGrid path_map_
The local map grid where we propagate path distance.
TrajectoryPlannerTest * setup_testclass_singleton()
A grid of MapCell cells that is used to propagate path and goal distances for the trajectory controll...
unsigned char getCost(unsigned int mx, unsigned int my) const
bool target_mark
Marks for computing path/goal distances.
double target_dist
Distance to planner's path.
void generateTrajectory(double x, double y, double theta, double vx, double vy, double vtheta, double vx_samp, double vy_samp, double vtheta_samp, double acc_x, double acc_y, double acc_theta, double impossible_cost, Trajectory &traj)
Generate and score a single trajectory.
static const unsigned char LETHAL_OBSTACLE
Stores path distance and goal distance information used for scoring trajectories. ...
A class that implements the WorldModel interface to provide grid based collision checks for the traje...
TEST(FootprintHelperTest, correctFootprint)
void resetPathDist()
reset path distance fields for all cells
Holds a trajectory generated by considering an x, y, and theta velocity.