global_rrt_detector.cpp
Go to the documentation of this file.
00001 #include "ros/ros.h"
00002 #include "std_msgs/String.h"
00003 #include <sstream>
00004 #include <iostream>
00005 #include <string>
00006 #include <vector>
00007 #include "stdint.h"
00008 #include "functions.h"
00009 #include "mtrand.h"
00010 
00011 
00012 #include "nav_msgs/OccupancyGrid.h"
00013 #include "geometry_msgs/PointStamped.h"
00014 #include "std_msgs/Header.h"
00015 #include "nav_msgs/MapMetaData.h"
00016 #include "geometry_msgs/Point.h"
00017 #include "visualization_msgs/Marker.h"
00018 #include <tf/transform_listener.h>
00019 
00020 
00021 
00022 // global variables
00023 nav_msgs::OccupancyGrid mapData;
00024 geometry_msgs::PointStamped clickedpoint;
00025 geometry_msgs::PointStamped exploration_goal;
00026 visualization_msgs::Marker points,line;
00027 float xdim,ydim,resolution,Xstartx,Xstarty,init_map_x,init_map_y;
00028 
00029 rdm r; // for genrating random numbers
00030 
00031 
00032 
00033 //Subscribers callback functions---------------------------------------
00034 void mapCallBack(const nav_msgs::OccupancyGrid::ConstPtr& msg)
00035 {
00036 mapData=*msg;
00037 }
00038 
00039 
00040  
00041 void rvizCallBack(const geometry_msgs::PointStamped::ConstPtr& msg)
00042 { 
00043 
00044 geometry_msgs::Point p;  
00045 p.x=msg->point.x;
00046 p.y=msg->point.y;
00047 p.z=msg->point.z;
00048 
00049 points.points.push_back(p);
00050 
00051 }
00052 
00053 
00054 
00055 
00056 int main(int argc, char **argv)
00057 {
00058 
00059   unsigned long init[4] = {0x123, 0x234, 0x345, 0x456}, length = 7;
00060   MTRand_int32 irand(init, length); // 32-bit int generator
00061 // this is an example of initializing by an array
00062 // you may use MTRand(seed) with any 32bit integer
00063 // as a seed for a simpler initialization
00064   MTRand drand; // double in [0, 1) generator, already init
00065 
00066 // generate the same numbers as in the original C test program
00067   ros::init(argc, argv, "global_rrt_frontier_detector");
00068   ros::NodeHandle nh;
00069   
00070   // fetching all parameters
00071   float eta,init_map_x,init_map_y,range;
00072   std::string map_topic,base_frame_topic;
00073   
00074   std::string ns;
00075   ns=ros::this_node::getName();
00076 
00077   ros::param::param<float>(ns+"/eta", eta, 0.5);
00078   ros::param::param<std::string>(ns+"/map_topic", map_topic, "/robot_1/map"); 
00079 //---------------------------------------------------------------
00080 ros::Subscriber sub= nh.subscribe(map_topic, 100 ,mapCallBack); 
00081 ros::Subscriber rviz_sub= nh.subscribe("/clicked_point", 100 ,rvizCallBack);    
00082 
00083 ros::Publisher targetspub = nh.advertise<geometry_msgs::PointStamped>("/detected_points", 10);
00084 ros::Publisher pub = nh.advertise<visualization_msgs::Marker>(ns+"_shapes", 10);
00085 
00086 ros::Rate rate(100); 
00087  
00088  
00089 // wait until map is received, when a map is received, mapData.header.seq will not be < 1  
00090 while (mapData.header.seq<1 or mapData.data.size()<1)  {  ros::spinOnce();  ros::Duration(0.1).sleep();}
00091 
00092 
00093 
00094 //visualizations  points and lines..
00095 points.header.frame_id=mapData.header.frame_id;
00096 line.header.frame_id=mapData.header.frame_id;
00097 points.header.stamp=ros::Time(0);
00098 line.header.stamp=ros::Time(0);
00099         
00100 points.ns=line.ns = "markers";
00101 points.id = 0;
00102 line.id =1;
00103 
00104 
00105 points.type = points.POINTS;
00106 line.type=line.LINE_LIST;
00107 
00108 //Set the marker action.  Options are ADD, DELETE, and new in ROS Indigo: 3 (DELETEALL)
00109 points.action =points.ADD;
00110 line.action = line.ADD;
00111 points.pose.orientation.w =1.0;
00112 line.pose.orientation.w = 1.0;
00113 line.scale.x =  0.03;
00114 line.scale.y= 0.03;
00115 points.scale.x=0.3; 
00116 points.scale.y=0.3; 
00117 
00118 line.color.r =9.0/255.0;
00119 line.color.g= 91.0/255.0;
00120 line.color.b =236.0/255.0;
00121 points.color.r = 255.0/255.0;
00122 points.color.g = 0.0/255.0;
00123 points.color.b = 0.0/255.0;
00124 points.color.a=1.0;
00125 line.color.a = 1.0;
00126 points.lifetime = ros::Duration();
00127 line.lifetime = ros::Duration();
00128 
00129 geometry_msgs::Point p;  
00130 
00131 
00132 while(points.points.size()<5)
00133 {
00134 ros::spinOnce();
00135 
00136 pub.publish(points) ;
00137 }
00138 
00139 
00140 
00141 
00142 std::vector<float> temp1;
00143 temp1.push_back(points.points[0].x);
00144 temp1.push_back(points.points[0].y);
00145         
00146 std::vector<float> temp2; 
00147 temp2.push_back(points.points[2].x);
00148 temp2.push_back(points.points[0].y);
00149 
00150 
00151 init_map_x=Norm(temp1,temp2);
00152 temp1.clear();          temp2.clear();
00153 
00154 temp1.push_back(points.points[0].x);
00155 temp1.push_back(points.points[0].y);
00156 
00157 temp2.push_back(points.points[0].x);
00158 temp2.push_back(points.points[2].y);
00159 
00160 init_map_y=Norm(temp1,temp2);
00161 temp1.clear();          temp2.clear();
00162 
00163 Xstartx=(points.points[0].x+points.points[2].x)*.5;
00164 Xstarty=(points.points[0].y+points.points[2].y)*.5;
00165 
00166 
00167 
00168 
00169 
00170 geometry_msgs::Point trans;
00171 trans=points.points[4];
00172 std::vector< std::vector<float>  > V; 
00173 std::vector<float> xnew; 
00174 xnew.push_back( trans.x);xnew.push_back( trans.y);  
00175 V.push_back(xnew);
00176 
00177 points.points.clear();
00178 pub.publish(points) ;
00179 
00180 
00181 
00182 
00183 
00184 
00185 
00186 std::vector<float> frontiers;
00187 int i=0;
00188 float xr,yr;
00189 std::vector<float> x_rand,x_nearest,x_new;
00190 
00191 
00192 // Main loop
00193 while (ros::ok()){
00194 
00195 
00196 // Sample free
00197 x_rand.clear();
00198 xr=(drand()*init_map_x)-(init_map_x*0.5)+Xstartx;
00199 yr=(drand()*init_map_y)-(init_map_y*0.5)+Xstarty;
00200 
00201 
00202 x_rand.push_back( xr ); x_rand.push_back( yr );
00203 
00204 
00205 // Nearest
00206 x_nearest=Nearest(V,x_rand);
00207 
00208 // Steer
00209 
00210 x_new=Steer(x_nearest,x_rand,eta);
00211 
00212 
00213 // ObstacleFree    1:free     -1:unkown (frontier region)      0:obstacle
00214 char   checking=ObstacleFree(x_nearest,x_new,mapData);
00215 
00216           if (checking==-1){
00217                 exploration_goal.header.stamp=ros::Time(0);
00218                 exploration_goal.header.frame_id=mapData.header.frame_id;
00219                 exploration_goal.point.x=x_new[0];
00220                 exploration_goal.point.y=x_new[1];
00221                 exploration_goal.point.z=0.0;
00222                 p.x=x_new[0]; 
00223                         p.y=x_new[1]; 
00224                         p.z=0.0;
00225                 points.points.push_back(p);
00226                 pub.publish(points) ;
00227                 targetspub.publish(exploration_goal);
00228                         points.points.clear();
00229                 
00230                 }
00231                 
00232           
00233           else if (checking==1){
00234                 V.push_back(x_new);
00235                 
00236                 p.x=x_new[0]; 
00237                 p.y=x_new[1]; 
00238                 p.z=0.0;
00239                 line.points.push_back(p);
00240                 p.x=x_nearest[0]; 
00241                 p.y=x_nearest[1]; 
00242                 p.z=0.0;
00243                 line.points.push_back(p);
00244 
00245                 }
00246 
00247 
00248 
00249 pub.publish(line);  
00250 
00251 
00252    
00253 
00254 ros::spinOnce();
00255 rate.sleep();
00256   }return 0;}


rrt_exploration
Author(s): Hassan Umari
autogenerated on Thu Jun 6 2019 20:54:03