32 #include <move_base_msgs/MoveBaseAction.h> 33 #include <planner_cspace_msgs/PlannerStatus.h> 35 #include <gtest/gtest.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.24;
72 goal.target_pose.pose.position.y = 0.65;
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;
84 planner_cspace_msgs::PlannerStatus
status_;
104 ASSERT_EQ(planner_cspace_msgs::PlannerStatus::GOING_WELL,
106 ASSERT_EQ(planner_cspace_msgs::PlannerStatus::DONE,
110 int main(
int argc,
char** argv)
112 testing::InitGoogleTest(&argc, argv);
117 int ret = RUN_ALL_TESTS();
std::shared_ptr< ActionClient > ActionClientPtr
TEST_F(PreemptTest, Preempt)
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)
planner_cspace_msgs::PlannerStatus status_
move_base_msgs::MoveBaseGoal CreateGoalInFree()
ros::Subscriber status_sub_
void StatusCallback(const planner_cspace_msgs::PlannerStatus &msg)
ROSCPP_DECL void shutdown()
int main(int argc, char **argv)
ActionClientPtr move_base_