twist_gen.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 #include <gtest/gtest.h>
37 #include <nav_core2/exceptions.h>
38 #include <vector>
39 #include <algorithm>
40 
42 
43 geometry_msgs::Pose2D origin;
44 nav_2d_msgs::Twist2D zero;
45 nav_2d_msgs::Twist2D forward;
46 
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)
52 {
53  ASSERT_GT(twists.size(), 0U);
54  nav_2d_msgs::Twist2D first = twists[0];
55 
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);
59 
60  for (nav_2d_msgs::Twist2D twist : twists)
61  {
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);
70 
71  if (exp_min_xy >= 0 && exp_min_speed_theta >= 0)
72  {
73  EXPECT_TRUE(fabs(twist.theta) >= exp_min_speed_theta || hyp >= exp_min_xy);
74  }
75  }
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);
82  if (exp_max_xy >= 0)
83  {
84  EXPECT_DOUBLE_EQ(max_xy, exp_max_xy);
85  }
86 }
87 
88 TEST(VelocityIterator, standard_gen)
89 {
90  ros::NodeHandle nh("st_gen");
92  gen.initialize(nh);
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);
96 }
97 
98 TEST(VelocityIterator, max_xy)
99 {
100  ros::NodeHandle nh("max_xy");
101  nh.setParam("max_speed_xy", 1.0);
103  gen.initialize(nh);
104 
105  std::vector<nav_2d_msgs::Twist2D> twists = gen.getTwists(zero);
106  // Expect more twists since max_speed_xy is now beyond feasible limits
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));
109 }
110 
111 TEST(VelocityIterator, min_xy)
112 {
113  ros::NodeHandle nh("min_xy");
114  nh.setParam("min_speed_xy", -1);
116  gen.initialize(nh);
117  std::vector<nav_2d_msgs::Twist2D> twists = gen.getTwists(zero);
118  // Expect even more since theres no min_speed_xy
119  EXPECT_EQ(twists.size(), 2015U);
120  checkLimits(twists, 0.0, 0.55, -0.1, 0.1, -1.0, 1.0);
121 }
122 
123 TEST(VelocityIterator, min_theta)
124 {
125  ros::NodeHandle nh("min_theta");
126  nh.setParam("min_speed_theta", -1);
128  gen.initialize(nh);
129  std::vector<nav_2d_msgs::Twist2D> twists = gen.getTwists(zero);
130  // Expect even more since theres no min_speed_xy
131  EXPECT_EQ(twists.size(), 2015U);
132  checkLimits(twists, 0.0, 0.55, -0.1, 0.1, -1.0, 1.0);
133 }
134 
135 TEST(VelocityIterator, no_limits)
136 {
137  ros::NodeHandle nh("no_limits");
138  nh.setParam("max_speed_xy", -1.0);
139  nh.setParam("min_speed_xy", -1);
140  nh.setParam("min_speed_theta", -1);
142  gen.initialize(nh);
143  std::vector<nav_2d_msgs::Twist2D> twists = gen.getTwists(zero);
144  // vx_samples * vtheta_samples * vy_samples + added zero theta samples - (0,0,0)
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);
147 }
148 
149 TEST(VelocityIterator, no_limits_samples)
150 {
151  ros::NodeHandle nh("no_limits_samples");
152  nh.setParam("max_speed_xy", -1.0);
153  nh.setParam("min_speed_xy", -1);
154  nh.setParam("min_speed_theta", -1);
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);
160  gen.initialize(nh);
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);
164 }
165 
166 TEST(VelocityIterator, dwa_gen_exception)
167 {
168  ros::NodeHandle nh("dwa_gen_exception");
169  nh.setParam("use_dwa", true);
171  EXPECT_THROW(gen.initialize(nh), nav_core2::PlannerException);
172 }
173 
174 TEST(VelocityIterator, no_dwa_gen_exception)
175 {
176  ros::NodeHandle nh("no_dwa_gen_exception");
177  nh.setParam("use_dwa", false);
179  EXPECT_THROW(gen.initialize(nh), nav_core2::PlannerException);
180 }
181 
182 TEST(VelocityIterator, dwa_gen)
183 {
184  ros::NodeHandle nh("dwa_gen");
185  nh.setParam("use_dwa", true);
186  nh.setParam("min_speed_theta", -1);
188  gen.initialize(nh);
189  std::vector<nav_2d_msgs::Twist2D> twists = gen.getTwists(zero);
190  // Same as no-limits since everything is within our velocity limits
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);
193 }
194 
195 TEST(VelocityIterator, dwa_gen_no_param)
196 {
197  ros::NodeHandle nh("dwa_gen_no_param");
198  nh.setParam("min_speed_theta", -1);
200  gen.initialize(nh);
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);
204 }
205 
206 TEST(VelocityIterator, nonzero)
207 {
208  ros::NodeHandle nh("nonzero");
209  nh.setParam("use_dwa", true);
210  nh.setParam("min_speed_theta", -1);
212  gen.initialize(nh);
213  nav_2d_msgs::Twist2D initial;
214  initial.x = 0.1;
215  initial.y = -0.08;
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);
221 }
222 
223 void matchPose(const geometry_msgs::Pose2D& a, const geometry_msgs::Pose2D& b)
224 {
225  EXPECT_DOUBLE_EQ(a.x, b.x);
226  EXPECT_DOUBLE_EQ(a.y, b.y);
227  EXPECT_DOUBLE_EQ(a.theta, b.theta);
228 }
229 
230 void matchPose(const geometry_msgs::Pose2D& a, const double x, const double y, const double theta)
231 {
232  EXPECT_DOUBLE_EQ(a.x, x);
233  EXPECT_DOUBLE_EQ(a.y, y);
234  EXPECT_DOUBLE_EQ(a.theta, theta);
235 }
236 
237 void matchTwist(const nav_2d_msgs::Twist2D& a, const nav_2d_msgs::Twist2D& b)
238 {
239  EXPECT_DOUBLE_EQ(a.x, b.x);
240  EXPECT_DOUBLE_EQ(a.y, b.y);
241  EXPECT_DOUBLE_EQ(a.theta, b.theta);
242 }
243 
244 void matchTwist(const nav_2d_msgs::Twist2D& a, const double x, const double y, const double theta)
245 {
246  EXPECT_DOUBLE_EQ(a.x, x);
247  EXPECT_DOUBLE_EQ(a.y, y);
248  EXPECT_DOUBLE_EQ(a.theta, theta);
249 }
250 
251 const double DEFAULT_SIM_TIME = 1.7;
252 
253 TEST(TrajectoryGenerator, basic)
254 {
255  ros::NodeHandle nh("basic");
257  nh.setParam("linear_granularity", 0.5);
258  gen.initialize(nh);
259  dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, forward, forward);
260  matchTwist(res.velocity, forward);
261  EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), DEFAULT_SIM_TIME);
262  int n = res.poses.size();
263  EXPECT_EQ(n, 3);
264  ASSERT_GT(n, 0);
265 
266  matchPose(res.poses[0], origin);
267  matchPose(res.poses[n - 1], DEFAULT_SIM_TIME * forward.x, 0, 0);
268 }
269 
270 TEST(TrajectoryGenerator, basic_no_last_point)
271 {
272  ros::NodeHandle nh("basic_no_last_point");
274  nh.setParam("include_last_point", false);
275  nh.setParam("linear_granularity", 0.5);
276  gen.initialize(nh);
277  dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, forward, forward);
278  matchTwist(res.velocity, forward);
279  EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), DEFAULT_SIM_TIME / 2);
280  int n = res.poses.size();
281  EXPECT_EQ(n, 2);
282  ASSERT_GT(n, 0);
283 
284  matchPose(res.poses[0], origin);
285  matchPose(res.poses[n - 1], 0.255, 0, 0);
286 }
287 
288 TEST(TrajectoryGenerator, too_slow)
289 {
290  ros::NodeHandle nh("too_slow");
292  nh.setParam("linear_granularity", 0.5);
293  gen.initialize(nh);
294  nav_2d_msgs::Twist2D cmd;
295  cmd.x = 0.2;
296  dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, cmd, cmd);
297  matchTwist(res.velocity, cmd);
298  EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), DEFAULT_SIM_TIME);
299  int n = res.poses.size();
300  EXPECT_EQ(n, 2);
301  ASSERT_GT(n, 0);
302 
303  matchPose(res.poses[0], origin);
304 }
305 
306 TEST(TrajectoryGenerator, holonomic)
307 {
308  ros::NodeHandle nh("holonomic");
310  nh.setParam("linear_granularity", 0.5);
311  gen.initialize(nh);
312  nav_2d_msgs::Twist2D cmd;
313  cmd.x = 0.3;
314  cmd.y = 0.2;
315  dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, cmd, cmd);
316  matchTwist(res.velocity, cmd);
317  EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), DEFAULT_SIM_TIME);
318  int n = res.poses.size();
319  EXPECT_EQ(n, 3);
320  ASSERT_GT(n, 0);
321 
322  matchPose(res.poses[0], origin);
323  matchPose(res.poses[n - 1], cmd.x*DEFAULT_SIM_TIME, cmd.y*DEFAULT_SIM_TIME, 0);
324 }
325 
326 TEST(TrajectoryGenerator, twisty)
327 {
328  ros::NodeHandle nh("twisty");
330  nh.setParam("linear_granularity", 0.5);
331  nh.setParam("angular_granularity", 0.025);
332  gen.initialize(nh);
333  nav_2d_msgs::Twist2D cmd;
334  cmd.x = 0.3;
335  cmd.y = -0.2;
336  cmd.theta = 0.111;
337  dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, cmd, cmd);
338  matchTwist(res.velocity, cmd);
339  EXPECT_NEAR(res.time_offsets.back().toSec(), DEFAULT_SIM_TIME, 1.0E-5);
340  // Given the number of poses, the resulting time is slightly less precise
341  int n = res.poses.size();
342  EXPECT_EQ(n, 9);
343  ASSERT_GT(n, 0);
344 
345  matchPose(res.poses[0], origin);
346  matchPose(res.poses[n - 1], 0.5355173615993063, -0.29635287789821596, cmd.theta * DEFAULT_SIM_TIME);
347 }
348 
349 TEST(TrajectoryGenerator, sim_time)
350 {
351  ros::NodeHandle nh("sim_time");
352  const double sim_time = 2.5;
353  nh.setParam("sim_time", sim_time);
354  nh.setParam("linear_granularity", 0.5);
356  gen.initialize(nh);
357  dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, forward, forward);
358  matchTwist(res.velocity, forward);
359  EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), sim_time);
360  int n = res.poses.size();
361  EXPECT_EQ(n, 3);
362  ASSERT_GT(n, 0);
363 
364  matchPose(res.poses[0], origin);
365  matchPose(res.poses[n - 1], sim_time * forward.x, 0, 0);
366 }
367 
368 TEST(TrajectoryGenerator, accel)
369 {
370  ros::NodeHandle nh("accel");
371  nh.setParam("sim_time", 5.0);
372  nh.setParam("discretize_by_time", true);
373  nh.setParam("sim_granularity", 1.0);
374  nh.setParam("acc_lim_x", 0.1);
375  nh.setParam("min_speed_xy", -1.0);
377  gen.initialize(nh);
378 
379  dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, zero, forward);
380  matchTwist(res.velocity, forward);
381  EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), 5.0);
382  ASSERT_EQ(res.poses.size(), 6U);
383  matchPose(res.poses[0], origin);
384  matchPose(res.poses[1], 0.1, 0, 0);
385  matchPose(res.poses[2], 0.3, 0, 0);
386  matchPose(res.poses[3], 0.6, 0, 0);
387  matchPose(res.poses[4], 0.9, 0, 0);
388  matchPose(res.poses[5], 1.2, 0, 0);
389 }
390 
391 TEST(TrajectoryGenerator, dwa)
392 {
393  ros::NodeHandle nh("dwa");
394  nh.setParam("use_dwa", true);
395  nh.setParam("sim_period", 1.0);
396  nh.setParam("sim_time", 5.0);
397  nh.setParam("discretize_by_time", true);
398  nh.setParam("sim_granularity", 1.0);
399  nh.setParam("acc_lim_x", 0.1);
400  nh.setParam("min_speed_xy", -1.0);
402  gen.initialize(nh);
403 
404  dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, zero, forward);
405  matchTwist(res.velocity, forward);
406  EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), 5.0);
407  ASSERT_EQ(res.poses.size(), 6U);
408  matchPose(res.poses[0], origin);
409  matchPose(res.poses[1], 0.3, 0, 0);
410  matchPose(res.poses[2], 0.6, 0, 0);
411  matchPose(res.poses[3], 0.9, 0, 0);
412  matchPose(res.poses[4], 1.2, 0, 0);
413  matchPose(res.poses[5], 1.5, 0, 0);
414 }
415 
416 int main(int argc, char **argv)
417 {
418  forward.x = 0.3;
419  ros::init(argc, argv, "twist_gen");
420  testing::InitGoogleTest(&argc, argv);
421  return RUN_ALL_TESTS();
422 }
const double DEFAULT_SIM_TIME
Definition: twist_gen.cpp:251
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
string cmd
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)
Definition: twist_gen.cpp:47
geometry_msgs::Pose2D origin
Definition: twist_gen.cpp:43
Limits the acceleration in the generated trajectories to a fraction of the simulated time...
Standard DWA-like trajectory generator.
nav_2d_msgs::Twist2D zero
Definition: twist_gen.cpp:44
void initialize(ros::NodeHandle &nh) override
void matchTwist(const nav_2d_msgs::Twist2D &a, const nav_2d_msgs::Twist2D &b)
Definition: twist_gen.cpp:237
virtual std::vector< nav_2d_msgs::Twist2D > getTwists(const nav_2d_msgs::Twist2D &current_velocity)
TEST(VelocityIterator, standard_gen)
Definition: twist_gen.cpp:88
nav_2d_msgs::Twist2D forward
Definition: twist_gen.cpp:45
int main(int argc, char **argv)
Definition: twist_gen.cpp:416
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
void matchPose(const geometry_msgs::Pose2D &a, const geometry_msgs::Pose2D &b)
Definition: twist_gen.cpp:223
void initialize(ros::NodeHandle &nh) override


dwb_plugins
Author(s):
autogenerated on Wed Jun 26 2019 20:06:16