31 #include <gtest/gtest.h> 32 #include <move_base_msgs/MoveBaseAction.h> 33 #include <planner_cspace_msgs/PlannerStatus.h> 43 move_base_ = std::make_shared<ActionClient>(
"/move_base");
50 ROS_ERROR(
"Failed to connect move_base action");
68 move_base_msgs::MoveBaseGoal goal;
70 goal.target_pose.header.frame_id =
"map";
71 goal.target_pose.pose.position.x = 1.19;
72 goal.target_pose.pose.position.y = 1.90;
73 goal.target_pose.pose.position.z = 0.0;
74 goal.target_pose.pose.orientation.x = 0.0;
75 goal.target_pose.pose.orientation.y = 0.0;
76 goal.target_pose.pose.orientation.z = 0.0;
77 goal.target_pose.pose.orientation.w = 1.0;
82 move_base_msgs::MoveBaseGoal goal;
84 goal.target_pose.header.frame_id =
"map";
85 goal.target_pose.pose.position.x = 1.24;
86 goal.target_pose.pose.position.y = 0.65;
87 goal.target_pose.pose.position.z = 0.0;
88 goal.target_pose.pose.orientation.x = 0.0;
89 goal.target_pose.pose.orientation.y = 0.0;
90 goal.target_pose.pose.orientation.z = 0.0;
91 goal.target_pose.pose.orientation.w = 1.0;
98 planner_cspace_msgs::PlannerStatus
status_;
122 ASSERT_EQ(planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND,
142 ASSERT_EQ(planner_cspace_msgs::PlannerStatus::GOING_WELL,
146 int main(
int argc,
char** argv)
148 testing::InitGoogleTest(&argc, argv);
153 int ret = RUN_ALL_TESTS();
int main(int argc, char **argv)
planner_cspace_msgs::PlannerStatus status_
move_base_msgs::MoveBaseGoal CreateGoalInRock()
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ActionClientPtr move_base_
TEST_F(AbortTest, AbortByGoalInRock)
void StatusCallback(const planner_cspace_msgs::PlannerStatus &msg)
ros::Subscriber status_sub_
move_base_msgs::MoveBaseGoal CreateGoalInFree()
ROSCPP_DECL void shutdown()
std::shared_ptr< ActionClient > ActionClientPtr