38 #include <navfn/MakeNavPlan.h> 39 #include <boost/shared_ptr.hpp> 46 using rm::PoseStamped;
57 bool makePlanService(MakeNavPlan::Request& req, MakeNavPlan::Response& resp);
69 vector<PoseStamped> path;
71 req.start.header.frame_id =
"/map";
72 req.goal.header.frame_id =
"/map";
73 bool success =
makePlan(req.start, req.goal, path);
74 resp.plan_found = success;
84 cmap_->getRobotPose(global_pose);
85 vector<PoseStamped> path;
86 rm::PoseStamped
start;
87 start.header.stamp = global_pose.
stamp_;
88 start.header.frame_id = global_pose.
frame_id_;
89 start.pose.position.x = global_pose.getOrigin().x();
90 start.pose.position.y = global_pose.getOrigin().y();
91 start.pose.position.z = global_pose.getOrigin().z();
92 start.pose.orientation.x = global_pose.getRotation().x();
93 start.pose.orientation.y = global_pose.getRotation().y();
94 start.pose.orientation.z = global_pose.getRotation().z();
95 start.pose.orientation.w = global_pose.getRotation().w();
111 int main (
int argc,
char** argv)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::ServiceServer make_plan_service_
NavfnWithCostmap(string name, Costmap2DROS *cmap)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Provides a ROS wrapper for the navfn planner which runs a fast, interpolated navigation function on a...
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
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.
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
void poseCallback(const rm::PoseStamped::ConstPtr &goal)
ros::Subscriber pose_sub_
bool makePlanService(MakeNavPlan::Request &req, MakeNavPlan::Response &resp)