33 #include <gtest/gtest.h>
36 #include <move_base_msgs/MoveBaseAction.h>
37 #include <planner_cspace_msgs/PlannerStatus.h>
43 :
public ActionTestBase<move_base_msgs::MoveBaseAction, ACTION_TOPIC_MOVE_BASE>
48 move_base_msgs::MoveBaseGoal goal;
50 goal.target_pose.header.frame_id =
"map";
51 goal.target_pose.pose.position.x = 1.24;
52 goal.target_pose.pose.position.y = 0.65;
53 goal.target_pose.pose.position.z = 0.0;
54 goal.target_pose.pose.orientation.x = 0.0;
55 goal.target_pose.pose.orientation.y = 0.0;
56 goal.target_pose.pose.orientation.z = 0.0;
57 goal.target_pose.pose.orientation.w = 1.0;
67 move_base_->sendGoal(CreateGoalInFree());
68 while (move_base_->getState().state_ !=
73 <<
"Action didn't get active: " << move_base_->getState().toString()
76 while (move_base_->getState().state_ ==
79 move_base_->cancelAllGoals();
82 <<
"Action didn't get inactive: " << move_base_->getState().toString()
86 ASSERT_TRUE(planner_status_);
89 move_base_->getState().state_);
90 ASSERT_EQ(planner_cspace_msgs::PlannerStatus::GOING_WELL,
91 planner_status_->error);
92 ASSERT_EQ(planner_cspace_msgs::PlannerStatus::DONE,
93 planner_status_->status);
96 int main(
int argc,
char** argv)
98 testing::InitGoogleTest(&argc, argv);
103 int ret = RUN_ALL_TESTS();