00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef TOPOLOGICAL_ROADMAP_MOVE_BASE_TOPO_H_
00039 #define TOPOLOGICAL_ROADMAP_MOVE_BASE_TOPO_H_
00040
00041 #include <ros/ros.h>
00042 #include <topological_nav_msgs/TopologicalRoadmap.h>
00043 #include <topological_nav_msgs/TopologicalGraph.h>
00044 #include <nav_msgs/GetPlan.h>
00045
00046 #include <topological_roadmap/roadmap.h>
00047 #include <topological_roadmap/shortest_paths.h>
00048
00049 #include <boost/thread.hpp>
00050
00051 #include <topological_nav_msgs/MoveBaseTopoAction.h>
00052 #include <actionlib/server/simple_action_server.h>
00053
00054 #include <tf/transform_listener.h>
00055 #include <costmap_2d/costmap_2d_ros.h>
00056
00057 #include <navfn/navfn_ros.h>
00058
00059 #include <boost/foreach.hpp>
00060
00061 #include <sstream>
00062
00063 #include <actionlib/client/simple_action_client.h>
00064 #include <move_base_msgs/MoveBaseAction.h>
00065 #include <warehouse/warehouse_client.h>
00066
00067 namespace topological_roadmap
00068 {
00069
00070 typedef std::vector<unsigned> WaypointVec;
00071
00072 struct BlockedEdge
00073 {
00074 unsigned from, to;
00075 ros::Time blocked_time;
00076
00077 BlockedEdge(unsigned from, unsigned to, ros::Time blocked_time):
00078 from(from), to(to), blocked_time(blocked_time){}
00079 };
00080
00081 class MoveBaseTopo
00082 {
00083 public:
00084 MoveBaseTopo();
00085
00086 void roadmapCB(topological_nav_msgs::TopologicalRoadmap::ConstPtr roadmap);
00087 void localizationCB(const geometry_msgs::PoseStamped& l);
00088 void executeCB(const topological_nav_msgs::MoveBaseTopoGoal::ConstPtr& goal);
00089 double shortestPathDistance(const geometry_msgs::Pose& p1);
00090 geometry_msgs::PoseStamped nodePoseOnGrid(unsigned n, unsigned g) const;
00091 typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;
00092
00093 private:
00094 void cleanup();
00095 unsigned bestGrid (const WaypointVec& path) const;
00096 bool robotWithinTolerance(double tolerance_dist, unsigned node_id);
00097 unsigned lastWaypointOnGridIndex(const Path& plan, const std::string& global_frame);
00098 unsigned lastWaypointOnGridIndex(const WaypointVec& plan, const unsigned g) const;
00099 bool makeRoadmapPlan(const topological_nav_msgs::MoveBaseTopoGoal::ConstPtr& goal,
00100 boost::optional<Path>& plan, std::string& error_string);
00101 void checkEdgeTimeouts(const ros::TimerEvent& e);
00102 void removeBlockedEdges(const std::list<BlockedEdge>& blocked_edges, Roadmap& roadmap);
00103 void gridUpdateCB (const warehouse::UpdateNotification& m);
00104 nav_msgs::OccupancyGrid::ConstPtr getGrid (const unsigned g) const;
00105 void graphCB (topological_nav_msgs::TopologicalGraph::ConstPtr m);
00106
00107 inline double squareDist(const geometry_msgs::PoseStamped& p1, const geometry_msgs::PoseStamped& p2){
00108 return (p1.pose.position.x - p2.pose.position.x) * (p1.pose.position.x - p2.pose.position.x)
00109 + (p1.pose.position.y - p2.pose.position.y) * (p1.pose.position.y - p2.pose.position.y);
00110 }
00111
00112 tf::TransformListener tf_;
00113 warehouse::WarehouseClient db_;
00114 warehouse::Collection<nav_msgs::OccupancyGrid> grids_;
00115 ros::Subscriber roadmap_sub_, localization_sub_, grid_update_sub_, tmap_sub_;
00116 ros::Publisher path_pub_;
00117 ros::ServiceClient switch_grid_client_;
00118 mutable boost::mutex mutex_;
00119 Roadmap roadmap_;
00120 topological_map_2d::TopologicalMap tmap_;
00121 actionlib::SimpleActionServer<topological_nav_msgs::MoveBaseTopoAction> as_;
00122 boost::optional<unsigned> current_grid_;
00123 costmap_2d::Costmap2DROS costmap_;
00124 mutable navfn::NavfnROS planner_;
00125 MoveBaseClient move_base_client_;
00126 double progress_check_frequency_, next_waypoint_distance_;
00127 bool grid_switch_;
00128 std::string tf_prefix_;
00129 ros::Time last_valid_plan_;
00130 double planner_patience_;
00131 std::list<BlockedEdge> blocked_edges_;
00132 ros::Timer edge_watchdog_;
00133 double blocked_edge_timeout_;
00134 ros::ServiceClient make_plan_client_;
00135 };
00136 };
00137
00138 #endif // include guard