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.19;
52 goal.target_pose.pose.position.y = 1.90;
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;
62 move_base_msgs::MoveBaseGoal goal;
64 goal.target_pose.header.frame_id =
"map";
65 goal.target_pose.pose.position.x = 2.1;
66 goal.target_pose.pose.position.y = 0.45;
67 goal.target_pose.pose.position.z = 0.0;
68 goal.target_pose.pose.orientation.x = 0.0;
69 goal.target_pose.pose.orientation.y = 0.0;
70 goal.target_pose.pose.orientation.z = 1.0;
71 goal.target_pose.pose.orientation.w = 0.0;
90 <<
"Action didn't get active: " <<
move_base_->getState().toString()
100 <<
"Action didn't get inactive: " <<
move_base_->getState().toString()
110 ASSERT_EQ(planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND,
120 <<
"Action didn't get active: " <<
move_base_->getState().toString()
128 <<
"Action didn't get inactive: " <<
move_base_->getState().toString()
136 ASSERT_EQ(planner_cspace_msgs::PlannerStatus::GOING_WELL,
140 int main(
int argc,
char** argv)
142 testing::InitGoogleTest(&argc, argv);
147 int ret = RUN_ALL_TESTS();
int main(int argc, char **argv)
planner_cspace_msgs::PlannerStatus::ConstPtr planner_status_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string statusString() const
ActionClientPtr move_base_
TEST_F(AbortTest, AbortByGoalInRock)
move_base_msgs::MoveBaseGoal createGoalInRock()
move_base_msgs::MoveBaseGoal createGoalInFree()
ROSCPP_DECL void shutdown()