Go to the documentation of this file.
   38 #include <navfn/MakeNavPlan.h> 
   39 #include <boost/shared_ptr.hpp> 
   47 using rm::PoseStamped;
 
   58   bool makePlanService(MakeNavPlan::Request& req, MakeNavPlan::Response& resp);
 
   70   vector<PoseStamped> path;
 
   72   req.start.header.frame_id = 
"map";
 
   73   req.goal.header.frame_id = 
"map";
 
   74   bool success = 
makePlan(req.start, req.goal, path);
 
   75   resp.plan_found = success;
 
   84   geometry_msgs::PoseStamped global_pose;
 
   86   vector<PoseStamped> path;
 
  102 int main (
int argc, 
char** argv)
 
  
ros::Subscriber pose_sub_
 
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
 
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
 
void poseCallback(const rm::PoseStamped::ConstPtr &goal)
 
int main(int argc, char **argv)
 
Provides a ROS wrapper for the navfn planner which runs a fast, interpolated navigation function on a...
 
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
 
bool getRobotPose(geometry_msgs::PoseStamped &global_pose) const
 
ros::ServiceServer make_plan_service_
 
NavfnWithCostmap(string name, Costmap2DROS *cmap)
 
bool makePlanService(MakeNavPlan::Request &req, MakeNavPlan::Response &resp)
 
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.
 
navfn
Author(s): Kurt Konolige, Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:37