34 #include <gtest/gtest.h> 47 void checkLimits(
const std::vector<nav_2d_msgs::Twist2D>& twists,
48 double exp_min_x,
double exp_max_x,
double exp_min_y,
double exp_max_y,
49 double exp_min_theta,
double exp_max_theta,
50 double exp_max_xy = -1.0,
51 double exp_min_xy = -1.0,
double exp_min_speed_theta = -1.0)
53 ASSERT_GT(twists.size(), 0U);
54 nav_2d_msgs::Twist2D first = twists[0];
56 double min_x = first.x, max_x = first.x, min_y = first.y, max_y = first.y;
57 double min_theta = first.theta, max_theta = first.theta;
58 double max_xy = hypot(first.x, first.y);
60 for (nav_2d_msgs::Twist2D twist : twists)
62 min_x = std::min(min_x, twist.x);
63 min_y = std::min(min_y, twist.y);
64 min_theta = std::min(min_theta, twist.theta);
65 max_x = std::max(max_x, twist.x);
66 max_y = std::max(max_y, twist.y);
67 max_theta = std::max(max_theta, twist.theta);
68 double hyp = hypot(twist.x, twist.y);
69 max_xy = std::max(max_xy, hyp);
71 if (exp_min_xy >= 0 && exp_min_speed_theta >= 0)
73 EXPECT_TRUE(fabs(twist.theta) >= exp_min_speed_theta || hyp >= exp_min_xy);
76 EXPECT_DOUBLE_EQ(min_x, exp_min_x);
77 EXPECT_DOUBLE_EQ(max_x, exp_max_x);
78 EXPECT_DOUBLE_EQ(min_y, exp_min_y);
79 EXPECT_DOUBLE_EQ(max_y, exp_max_y);
80 EXPECT_DOUBLE_EQ(min_theta, exp_min_theta);
81 EXPECT_DOUBLE_EQ(max_theta, exp_max_theta);
84 EXPECT_DOUBLE_EQ(max_xy, exp_max_xy);
88 TEST(VelocityIterator, standard_gen)
93 std::vector<nav_2d_msgs::Twist2D> twists = gen.
getTwists(
zero);
94 EXPECT_EQ(twists.size(), 1926U);
95 checkLimits(twists, 0.0, 0.55, -0.1, 0.1, -1.0, 1.0, 0.55, 0.1, 0.4);
98 TEST(VelocityIterator, max_xy)
105 std::vector<nav_2d_msgs::Twist2D> twists = gen.
getTwists(
zero);
107 EXPECT_EQ(twists.size(), 2010U);
108 checkLimits(twists, 0.0, 0.55, -0.1, 0.1, -1.0, 1.0, hypot(0.55, 0.1));
117 std::vector<nav_2d_msgs::Twist2D> twists = gen.
getTwists(
zero);
119 EXPECT_EQ(twists.size(), 2015U);
120 checkLimits(twists, 0.0, 0.55, -0.1, 0.1, -1.0, 1.0);
123 TEST(VelocityIterator, min_theta)
129 std::vector<nav_2d_msgs::Twist2D> twists = gen.
getTwists(
zero);
131 EXPECT_EQ(twists.size(), 2015U);
132 checkLimits(twists, 0.0, 0.55, -0.1, 0.1, -1.0, 1.0);
135 TEST(VelocityIterator, no_limits)
143 std::vector<nav_2d_msgs::Twist2D> twists = gen.
getTwists(
zero);
145 EXPECT_EQ(twists.size(),
static_cast<unsigned int>(20 * 20 * 5 + 100 - 1));
146 checkLimits(twists, 0.0, 0.55, -0.1, 0.1, -1.0, 1.0, hypot(0.55, 0.1), 0.0, 0.0);
149 TEST(VelocityIterator, no_limits_samples)
155 int x_samples = 10, y_samples = 3, theta_samples = 5;
156 nh.
setParam(
"vx_samples", x_samples);
157 nh.
setParam(
"vy_samples", y_samples);
158 nh.
setParam(
"vtheta_samples", theta_samples);
161 std::vector<nav_2d_msgs::Twist2D> twists = gen.
getTwists(
zero);
162 EXPECT_EQ(twists.size(),
static_cast<unsigned int>(x_samples * y_samples * theta_samples - 1));
163 checkLimits(twists, 0.0, 0.55, -0.1, 0.1, -1.0, 1.0, hypot(0.55, 0.1), 0.0, 0.0);
166 TEST(VelocityIterator, dwa_gen_exception)
174 TEST(VelocityIterator, no_dwa_gen_exception)
182 TEST(VelocityIterator, dwa_gen)
189 std::vector<nav_2d_msgs::Twist2D> twists = gen.
getTwists(
zero);
191 EXPECT_EQ(twists.size(),
static_cast<unsigned int>(20 * 20 * 5 + 100 - 1));
192 checkLimits(twists, 0.0, 0.125, -0.1, 0.1, -0.16, 0.16, hypot(0.125, 0.1), 0.0, 0.1);
195 TEST(VelocityIterator, dwa_gen_no_param)
201 std::vector<nav_2d_msgs::Twist2D> twists = gen.
getTwists(
zero);
202 EXPECT_EQ(twists.size(),
static_cast<unsigned int>(20 * 20 * 5 + 100 - 1));
203 checkLimits(twists, 0.0, 0.125, -0.1, 0.1, -0.16, 0.16, hypot(0.125, 0.1), 0.0, 0.1);
206 TEST(VelocityIterator, nonzero)
213 nav_2d_msgs::Twist2D initial;
216 initial.theta = 0.05;
217 std::vector<nav_2d_msgs::Twist2D> twists = gen.
getTwists(initial);
218 EXPECT_EQ(twists.size(), 2519U);
219 checkLimits(twists, 0.0, 0.225, -0.1, 0.045, -0.11000000000000003, 0.21,
220 0.24622144504490268, 0.0, 0.1);
223 void matchPose(
const geometry_msgs::Pose2D& a,
const geometry_msgs::Pose2D& b)
225 EXPECT_DOUBLE_EQ(a.x, b.x);
226 EXPECT_DOUBLE_EQ(a.y, b.y);
227 EXPECT_DOUBLE_EQ(a.theta, b.theta);
230 void matchPose(
const geometry_msgs::Pose2D& a,
const double x,
const double y,
const double theta)
232 EXPECT_DOUBLE_EQ(a.x, x);
233 EXPECT_DOUBLE_EQ(a.y, y);
234 EXPECT_DOUBLE_EQ(a.theta, theta);
237 void matchTwist(
const nav_2d_msgs::Twist2D& a,
const nav_2d_msgs::Twist2D& b)
239 EXPECT_DOUBLE_EQ(a.x, b.x);
240 EXPECT_DOUBLE_EQ(a.y, b.y);
241 EXPECT_DOUBLE_EQ(a.theta, b.theta);
244 void matchTwist(
const nav_2d_msgs::Twist2D& a,
const double x,
const double y,
const double theta)
246 EXPECT_DOUBLE_EQ(a.x, x);
247 EXPECT_DOUBLE_EQ(a.y, y);
248 EXPECT_DOUBLE_EQ(a.theta, theta);
253 TEST(TrajectoryGenerator, basic)
257 nh.
setParam(
"linear_granularity", 0.5);
262 int n = res.poses.size();
270 TEST(TrajectoryGenerator, basic_no_last_point)
274 nh.
setParam(
"include_last_point",
false);
275 nh.
setParam(
"linear_granularity", 0.5);
280 int n = res.poses.size();
285 matchPose(res.poses[n - 1], 0.255, 0, 0);
288 TEST(TrajectoryGenerator, too_slow)
292 nh.
setParam(
"linear_granularity", 0.5);
294 nav_2d_msgs::Twist2D
cmd;
299 int n = res.poses.size();
306 TEST(TrajectoryGenerator, holonomic)
310 nh.
setParam(
"linear_granularity", 0.5);
312 nav_2d_msgs::Twist2D
cmd;
318 int n = res.poses.size();
326 TEST(TrajectoryGenerator, twisty)
330 nh.
setParam(
"linear_granularity", 0.5);
331 nh.
setParam(
"angular_granularity", 0.025);
333 nav_2d_msgs::Twist2D
cmd;
341 int n = res.poses.size();
349 TEST(TrajectoryGenerator, sim_time)
352 const double sim_time = 2.5;
354 nh.
setParam(
"linear_granularity", 0.5);
359 EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), sim_time);
360 int n = res.poses.size();
368 TEST(TrajectoryGenerator, accel)
372 nh.
setParam(
"discretize_by_time",
true);
373 nh.
setParam(
"sim_granularity", 1.0);
381 EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), 5.0);
382 ASSERT_EQ(res.poses.size(), 6U);
397 nh.
setParam(
"discretize_by_time",
true);
398 nh.
setParam(
"sim_granularity", 1.0);
406 EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), 5.0);
407 ASSERT_EQ(res.poses.size(), 6U);
416 int main(
int argc,
char **argv)
420 testing::InitGoogleTest(&argc, argv);
421 return RUN_ALL_TESTS();
const double DEFAULT_SIM_TIME
dwb_msgs::Trajectory2D generateTrajectory(const geometry_msgs::Pose2D &start_pose, const nav_2d_msgs::Twist2D &start_vel, const nav_2d_msgs::Twist2D &cmd_vel) override
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void checkLimits(const std::vector< nav_2d_msgs::Twist2D > &twists, double exp_min_x, double exp_max_x, double exp_min_y, double exp_max_y, double exp_min_theta, double exp_max_theta, double exp_max_xy=-1.0, double exp_min_xy=-1.0, double exp_min_speed_theta=-1.0)
geometry_msgs::Pose2D origin
Limits the acceleration in the generated trajectories to a fraction of the simulated time...
Standard DWA-like trajectory generator.
nav_2d_msgs::Twist2D zero
void initialize(ros::NodeHandle &nh) override
void matchTwist(const nav_2d_msgs::Twist2D &a, const nav_2d_msgs::Twist2D &b)
virtual std::vector< nav_2d_msgs::Twist2D > getTwists(const nav_2d_msgs::Twist2D ¤t_velocity)
TEST(VelocityIterator, standard_gen)
nav_2d_msgs::Twist2D forward
int main(int argc, char **argv)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
void matchPose(const geometry_msgs::Pose2D &a, const geometry_msgs::Pose2D &b)
void initialize(ros::NodeHandle &nh) override