goal_checker.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 
40 
42  double x0, double y0, double theta0,
43  double x1, double y1, double theta1,
44  double xv, double yv, double thetav,
45  bool expected_result)
46 {
47  gc.reset();
48  geometry_msgs::Pose2D pose0, pose1;
49  pose0.x = x0;
50  pose0.y = y0;
51  pose0.theta = theta0;
52  pose1.x = x1;
53  pose1.y = y1;
54  pose1.theta = theta1;
55  nav_2d_msgs::Twist2D v;
56  v.x = xv;
57  v.y = yv;
58  v.theta = thetav;
59  if (expected_result)
60  EXPECT_TRUE(gc.isGoalReached(pose0, pose1, v));
61  else
62  EXPECT_FALSE(gc.isGoalReached(pose0, pose1, v));
63 }
64 
66  double x0, double y0, double theta0,
67  double x1, double y1, double theta1,
68  double xv, double yv, double thetav,
69  bool expected_result)
70 {
71  checkMacro(gc0, x0, y0, theta0, x1, y1, theta1, xv, yv, thetav, expected_result);
72  checkMacro(gc1, x0, y0, theta0, x1, y1, theta1, xv, yv, thetav, expected_result);
73 }
74 
76  double x0, double y0, double theta0,
77  double x1, double y1, double theta1,
78  double xv, double yv, double thetav)
79 {
80  checkMacro(gc0, x0, y0, theta0, x1, y1, theta1, xv, yv, thetav, true);
81  checkMacro(gc1, x0, y0, theta0, x1, y1, theta1, xv, yv, thetav, false);
82 }
83 
84 TEST(VelocityIterator, two_checks)
85 {
89  gc.initialize(x);
90  sgc.initialize(x);
91  sameResult(gc, sgc, 0, 0, 0, 0, 0, 0, 0, 0, 0, true);
92  sameResult(gc, sgc, 0, 0, 0, 1, 0, 0, 0, 0, 0, false);
93  sameResult(gc, sgc, 0, 0, 0, 0, 1, 0, 0, 0, 0, false);
94  sameResult(gc, sgc, 0, 0, 0, 0, 0, 1, 0, 0, 0, false);
95  sameResult(gc, sgc, 0, 0, 3.14, 0, 0, -3.14, 0, 0, 0, true);
96  trueFalse(gc, sgc, 0, 0, 3.14, 0, 0, -3.14, 1, 0, 0);
97  trueFalse(gc, sgc, 0, 0, 0, 0, 0, 0, 1, 0, 0);
98  trueFalse(gc, sgc, 0, 0, 0, 0, 0, 0, 0, 1, 0);
99  trueFalse(gc, sgc, 0, 0, 0, 0, 0, 0, 0, 0, 1);
100 }
101 
102 int main(int argc, char **argv)
103 {
104  ros::init(argc, argv, "goal_checker");
105  testing::InitGoogleTest(&argc, argv);
106  return RUN_ALL_TESTS();
107 }
int main(int argc, char **argv)
Goal Checker plugin that checks the position difference and velocity.
void sameResult(dwb_local_planner::GoalChecker &gc0, dwb_local_planner::GoalChecker &gc1, double x0, double y0, double theta0, double x1, double y1, double theta1, double xv, double yv, double thetav, bool expected_result)
void checkMacro(dwb_local_planner::GoalChecker &gc, double x0, double y0, double theta0, double x1, double y1, double theta1, double xv, double yv, double thetav, bool expected_result)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void initialize(const ros::NodeHandle &nh) override
Goal Checker plugin that only checks the position difference.
void initialize(const ros::NodeHandle &nh) override
TFSIMD_FORCE_INLINE const tfScalar & x() const
TEST(VelocityIterator, two_checks)
virtual bool isGoalReached(const geometry_msgs::Pose2D &query_pose, const geometry_msgs::Pose2D &goal_pose, const nav_2d_msgs::Twist2D &velocity)=0
void trueFalse(dwb_local_planner::GoalChecker &gc0, dwb_local_planner::GoalChecker &gc1, double x0, double y0, double theta0, double x1, double y1, double theta1, double xv, double yv, double thetav)


dwb_plugins
Author(s):
autogenerated on Sun Jan 10 2021 04:08:37