30 #ifndef PLANNER_CSPACE_ACTION_TEST_BASE_H 31 #define PLANNER_CSPACE_ACTION_TEST_BASE_H 36 #include <gtest/gtest.h> 41 #include <move_base_msgs/MoveBaseAction.h> 42 #include <nav_msgs/GetPlan.h> 43 #include <planner_cspace_msgs/PlannerStatus.h> 50 template <
typename ACTION,
char const* TOPIC>
58 move_base_ = std::make_shared<ActionClient>(TOPIC);
66 FAIL() <<
"Failed to connect move_base action";
71 "/planner_3d/make_plan");
76 nav_msgs::GetPlanRequest req;
77 nav_msgs::GetPlanResponse res;
79 req.start.header.frame_id =
"map";
80 req.start.pose.position.x = 1.24;
81 req.start.pose.position.y = 0.65;
82 req.start.pose.orientation.w = 1;
83 req.goal.header.frame_id =
"map";
84 req.goal.pose.position.x = 1.25;
85 req.goal.pose.position.y = 0.75;
86 req.goal.pose.orientation.w = 1;
87 if (srv_plan.
call(req, res))
94 FAIL() <<
"planner_3d didn't receive map";
108 void cbStatus(
const planner_cspace_msgs::PlannerStatus::ConstPtr& msg)
117 return "(no status)";
132 #endif // PLANNER_CSPACE_ACTION_TEST_BASE_H ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
planner_cspace_msgs::PlannerStatus::ConstPtr planner_status_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber sub_status_
constexpr const char ACTION_TOPIC_MOVE_BASE[]
bool call(MReq &req, MRes &res)
std::string statusString() const
ActionClientPtr move_base_
void cbStatus(const planner_cspace_msgs::PlannerStatus::ConstPtr &msg)
std::shared_ptr< ActionClient > ActionClientPtr
tf2_ros::TransformListener tfl_
constexpr const char ACTION_TOPIC_TOLERANT_MOVE[]
ROSCPP_DECL void spinOnce()