34 #include <gtest/gtest.h> 42 double x0,
double y0,
double theta0,
43 double x1,
double y1,
double theta1,
44 double xv,
double yv,
double thetav,
48 geometry_msgs::Pose2D pose0, pose1;
55 nav_2d_msgs::Twist2D v;
66 double x0,
double y0,
double theta0,
67 double x1,
double y1,
double theta1,
68 double xv,
double yv,
double thetav,
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);
76 double x0,
double y0,
double theta0,
77 double x1,
double y1,
double theta1,
78 double xv,
double yv,
double thetav)
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);
84 TEST(VelocityIterator, two_checks)
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);
102 int main(
int argc,
char **argv)
105 testing::InitGoogleTest(&argc, argv);
106 return RUN_ALL_TESTS();
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)