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 #ifndef EXPLORE_LOOP_CLOSURE_H
00038 #define EXPLORE_LOOP_CLOSURE_H
00039
00040
00041
00042
00043
00044
00045
00046 #include <tf/transform_datatypes.h>
00047 #include <actionlib/client/simple_action_client.h>
00048 #include <move_base_msgs/MoveBaseAction.h>
00049 #include <costmap_2d/costmap_2d_ros.h>
00050 #include <std_msgs/Float64.h>
00051 #include <navfn/navfn_ros.h>
00052
00053 #include <ros/node_handle.h>
00054
00055 #include <boost/thread/mutex.hpp>
00056 #include <boost/function.hpp>
00057
00058 #include <visualization_msgs/MarkerArray.h>
00059
00060 namespace explore
00061 {
00062
00063 class GraphNode
00064 {
00065 public:
00066 GraphNode(int id, const tf::Pose& pose) :
00067 id_(id), pose_(pose), next_(NULL), dijkstra_d_(0.0), slam_entropy_(0.0), path_length_(DBL_MAX) {}
00068
00069
00070 int id_;
00071
00072 tf::Pose pose_;
00073
00074
00075 GraphNode* next_;
00076
00077 double dijkstra_d_;
00078
00079 double slam_entropy_;
00080
00081 double path_length_;
00082 };
00083
00084 class LoopClosure
00085 {
00086 public:
00087 LoopClosure(double addition_dist_min,
00088 double loop_dist_min,
00089 double loop_dist_max,
00090 double slam_entropy_max_,
00091 double graph_update_frequency,
00092 actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction>& move_base_client,
00093 costmap_2d::Costmap2DROS& costmap,
00094 boost::mutex& control_mutex);
00095 ~LoopClosure();
00096
00097
00098
00099
00100 void updateGraph(const tf::Pose& pose);
00101
00102
00103 private:
00104
00105
00106 void addNode(const tf::Pose& pose);
00107 bool checkLoopClosure(const tf::Pose& pose, std::vector<GraphNode*>& candidates);
00108 void dijkstra(int source);
00109 void entropyCallback(const std_msgs::Float64::ConstPtr& entropy);
00110
00111 void visualizeNode(const tf::Pose& pose, visualization_msgs::MarkerArray& markers);
00112 void visualizeEdge(const tf::Pose& pose1, const tf::Pose& pose2, visualization_msgs::MarkerArray& markers);
00113 void visualizeGraph();
00114
00115 inline double distance(const geometry_msgs::PoseStamped& p1, const geometry_msgs::PoseStamped& p2){
00116 double x1 = p1.pose.position.x;
00117 double x2 = p2.pose.position.x;
00118 double y1 = p1.pose.position.y;
00119 double y2 = p2.pose.position.y;
00120 return sqrt((x1 - x2) * (x1 - x2) + (y1 - y2) * (y1 - y2));
00121 }
00122
00123 inline int sign(int x){
00124 return x > 0 ? 1.0 : -1.0;
00125 }
00126
00136 template <class ActionType>
00137 inline void raytraceLine(ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int size_x, unsigned int max_length = UINT_MAX){
00138 int dx = x1 - x0;
00139 int dy = y1 - y0;
00140
00141 unsigned int abs_dx = abs(dx);
00142 unsigned int abs_dy = abs(dy);
00143
00144 int offset_dx = sign(dx);
00145 int offset_dy = sign(dy) * size_x;
00146
00147 unsigned int offset = y0 * size_x + x0;
00148
00149
00150 double dist = sqrt((x0 - x1) * (x0 - x1) + (y0 - y1) * (y0 - y1));
00151 double scale = std::min(1.0, max_length / dist);
00152
00153
00154 if(abs_dx >= abs_dy){
00155 int error_y = abs_dx / 2;
00156 bresenham2D(at, abs_dx, abs_dy, error_y, offset_dx, offset_dy, offset, (unsigned int)(scale * abs_dx));
00157 return;
00158 }
00159
00160
00161 int error_x = abs_dy / 2;
00162 bresenham2D(at, abs_dy, abs_dx, error_x, offset_dy, offset_dx, offset, (unsigned int)(scale * abs_dy));
00163
00164 }
00165
00169 template <class ActionType>
00170 inline void bresenham2D(ActionType at, unsigned int abs_da, unsigned int abs_db, int error_b, int offset_a, int offset_b,
00171 unsigned int offset, unsigned int max_length){
00172 unsigned int end = std::min(max_length, abs_da);
00173 for(unsigned int i = 0; i < end; ++i){
00174 at(offset);
00175 offset += offset_a;
00176 error_b += abs_db;
00177 if((unsigned int)error_b >= abs_da){
00178 offset += offset_b;
00179 error_b -= abs_da;
00180 }
00181 }
00182 at(offset);
00183 }
00184
00185 class VisibilityChecker {
00186 public:
00187 VisibilityChecker(const unsigned char* costmap, bool& is_visible) : costmap_(costmap), is_visible_(is_visible) {}
00188 inline void operator()(unsigned int offset){
00189 unsigned char cost = costmap_[offset];
00190 if(cost >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
00191 is_visible_ = false;
00192 }
00193 }
00194
00195 public:
00196 const unsigned char* costmap_;
00197 bool& is_visible_;
00198 };
00199
00200
00201 GraphNode* curr_node_;
00202
00203 double addition_dist_min_;
00204
00205 double loop_dist_min_;
00206
00207 double loop_dist_max_;
00208
00209 double slam_entropy_max_;
00210
00211
00212 double graph_update_frequency_;
00213
00214
00215 actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction>& move_base_client_;
00216 ros::NodeHandle nh_;
00217
00218 std::vector<GraphNode*> nodes_;
00219
00220 std::vector<std::vector<int> > graph_;
00221
00222 ros::Subscriber entropy_subscriber_;
00223 ros::Publisher marker_publisher_;
00224 int marker_id_;
00225 costmap_2d::Costmap2DROS& costmap_;
00226
00227 boost::mutex& control_mutex_;
00228 navfn::NavfnROS* planner_;
00229 double slam_entropy_;
00230 double slam_entropy_time_;
00231 };
00232
00233 }
00234
00235 #endif