39 #include <navfn/MakeNavPlan.h> 40 #include <boost/shared_ptr.hpp> 47 using rm::PoseStamped;
57 bool makePlanService(navfn::MakeNavPlan::Request& req, navfn::MakeNavPlan::Response& resp);
67 vector<PoseStamped> path;
69 req.start.header.frame_id =
"/map";
70 req.goal.header.frame_id =
"/map";
71 bool success =
makePlan(req.start, req.goal, path);
72 resp.plan_found = success;
82 cmap_->getRobotPose(global_pose);
83 vector<PoseStamped> path;
84 rm::PoseStamped
start;
85 start.header.stamp = global_pose.
stamp_;
86 start.header.frame_id = global_pose.
frame_id_;
87 start.pose.position.x = global_pose.getOrigin().x();
88 start.pose.position.y = global_pose.getOrigin().y();
89 start.pose.position.z = global_pose.getOrigin().z();
90 start.pose.orientation.x = global_pose.getRotation().x();
91 start.pose.orientation.y = global_pose.getRotation().y();
92 start.pose.orientation.z = global_pose.getRotation().z();
93 start.pose.orientation.w = global_pose.getRotation().w();
98 GlobalPlanner(name, cmap->getCostmap(), cmap->getGlobalFrameID()) {
107 int main(
int argc,
char** argv) {
bool makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
Given a goal pose in the world, compute a plan.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void poseCallback(const rm::PoseStamped::ConstPtr &goal)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
PlannerWithCostmap(string name, Costmap2DROS *cmap)
ROSCPP_DECL void spin(Spinner &spinner)
ros::Subscriber pose_sub_
ros::ServiceServer make_plan_service_
bool makePlanService(navfn::MakeNavPlan::Request &req, navfn::MakeNavPlan::Response &resp)