global_rrt_detector.cpp
Go to the documentation of this file.
1 #include "ros/ros.h"
2 #include "std_msgs/String.h"
3 #include <sstream>
4 #include <iostream>
5 #include <string>
6 #include <vector>
7 #include "stdint.h"
8 #include "functions.h"
9 #include "mtrand.h"
10 
11 
12 #include "nav_msgs/OccupancyGrid.h"
13 #include "geometry_msgs/PointStamped.h"
14 #include "std_msgs/Header.h"
15 #include "nav_msgs/MapMetaData.h"
16 #include "geometry_msgs/Point.h"
17 #include "visualization_msgs/Marker.h"
18 #include <tf/transform_listener.h>
19 
20 
21 
22 // global variables
23 nav_msgs::OccupancyGrid mapData;
24 geometry_msgs::PointStamped clickedpoint;
25 geometry_msgs::PointStamped exploration_goal;
26 visualization_msgs::Marker points,line;
28 
29 rdm r; // for genrating random numbers
30 
31 
32 
33 //Subscribers callback functions---------------------------------------
34 void mapCallBack(const nav_msgs::OccupancyGrid::ConstPtr& msg)
35 {
36 mapData=*msg;
37 }
38 
39 
40 
41 void rvizCallBack(const geometry_msgs::PointStamped::ConstPtr& msg)
42 {
43 
44 geometry_msgs::Point p;
45 p.x=msg->point.x;
46 p.y=msg->point.y;
47 p.z=msg->point.z;
48 
49 points.points.push_back(p);
50 
51 }
52 
53 
54 
55 
56 int main(int argc, char **argv)
57 {
58 
59  unsigned long init[4] = {0x123, 0x234, 0x345, 0x456}, length = 7;
60  MTRand_int32 irand(init, length); // 32-bit int generator
61 // this is an example of initializing by an array
62 // you may use MTRand(seed) with any 32bit integer
63 // as a seed for a simpler initialization
64  MTRand drand; // double in [0, 1) generator, already init
65 
66 // generate the same numbers as in the original C test program
67  ros::init(argc, argv, "global_rrt_frontier_detector");
68  ros::NodeHandle nh;
69 
70  // fetching all parameters
71  float eta,init_map_x,init_map_y,range;
72  std::string map_topic,base_frame_topic;
73 
74  std::string ns;
76 
77  ros::param::param<float>(ns+"/eta", eta, 0.5);
78  ros::param::param<std::string>(ns+"/map_topic", map_topic, "/robot_1/map");
79 //---------------------------------------------------------------
80 ros::Subscriber sub= nh.subscribe(map_topic, 100 ,mapCallBack);
81 ros::Subscriber rviz_sub= nh.subscribe("/clicked_point", 100 ,rvizCallBack);
82 
83 ros::Publisher targetspub = nh.advertise<geometry_msgs::PointStamped>("/detected_points", 10);
84 ros::Publisher pub = nh.advertise<visualization_msgs::Marker>(ns+"_shapes", 10);
85 
86 ros::Rate rate(100);
87 
88 
89 // wait until map is received, when a map is received, mapData.header.seq will not be < 1
90 while (mapData.header.seq<1 or mapData.data.size()<1) { ros::spinOnce(); ros::Duration(0.1).sleep();}
91 
92 
93 
94 //visualizations points and lines..
95 points.header.frame_id=mapData.header.frame_id;
96 line.header.frame_id=mapData.header.frame_id;
97 points.header.stamp=ros::Time(0);
98 line.header.stamp=ros::Time(0);
99 
100 points.ns=line.ns = "markers";
101 points.id = 0;
102 line.id =1;
103 
104 
105 points.type = points.POINTS;
106 line.type=line.LINE_LIST;
107 
108 //Set the marker action. Options are ADD, DELETE, and new in ROS Indigo: 3 (DELETEALL)
109 points.action =points.ADD;
110 line.action = line.ADD;
111 points.pose.orientation.w =1.0;
112 line.pose.orientation.w = 1.0;
113 line.scale.x = 0.03;
114 line.scale.y= 0.03;
115 points.scale.x=0.3;
116 points.scale.y=0.3;
117 
118 line.color.r =9.0/255.0;
119 line.color.g= 91.0/255.0;
120 line.color.b =236.0/255.0;
121 points.color.r = 255.0/255.0;
122 points.color.g = 0.0/255.0;
123 points.color.b = 0.0/255.0;
124 points.color.a=1.0;
125 line.color.a = 1.0;
126 points.lifetime = ros::Duration();
127 line.lifetime = ros::Duration();
128 
129 geometry_msgs::Point p;
130 
131 
132 while(points.points.size()<5)
133 {
134 ros::spinOnce();
135 
136 pub.publish(points) ;
137 }
138 
139 
140 
141 
142 std::vector<float> temp1;
143 temp1.push_back(points.points[0].x);
144 temp1.push_back(points.points[0].y);
145 
146 std::vector<float> temp2;
147 temp2.push_back(points.points[2].x);
148 temp2.push_back(points.points[0].y);
149 
150 
151 init_map_x=Norm(temp1,temp2);
152 temp1.clear(); temp2.clear();
153 
154 temp1.push_back(points.points[0].x);
155 temp1.push_back(points.points[0].y);
156 
157 temp2.push_back(points.points[0].x);
158 temp2.push_back(points.points[2].y);
159 
160 init_map_y=Norm(temp1,temp2);
161 temp1.clear(); temp2.clear();
162 
163 Xstartx=(points.points[0].x+points.points[2].x)*.5;
164 Xstarty=(points.points[0].y+points.points[2].y)*.5;
165 
166 
167 
168 
169 
170 geometry_msgs::Point trans;
171 trans=points.points[4];
172 std::vector< std::vector<float> > V;
173 std::vector<float> xnew;
174 xnew.push_back( trans.x);xnew.push_back( trans.y);
175 V.push_back(xnew);
176 
177 points.points.clear();
178 pub.publish(points) ;
179 
180 
181 
182 
183 
184 
185 
186 std::vector<float> frontiers;
187 int i=0;
188 float xr,yr;
189 std::vector<float> x_rand,x_nearest,x_new;
190 
191 
192 // Main loop
193 while (ros::ok()){
194 
195 
196 // Sample free
197 x_rand.clear();
198 xr=(drand()*init_map_x)-(init_map_x*0.5)+Xstartx;
199 yr=(drand()*init_map_y)-(init_map_y*0.5)+Xstarty;
200 
201 
202 x_rand.push_back( xr ); x_rand.push_back( yr );
203 
204 
205 // Nearest
206 x_nearest=Nearest(V,x_rand);
207 
208 // Steer
209 
210 x_new=Steer(x_nearest,x_rand,eta);
211 
212 
213 // ObstacleFree 1:free -1:unkown (frontier region) 0:obstacle
214 char checking=ObstacleFree(x_nearest,x_new,mapData);
215 
216  if (checking==-1){
217  exploration_goal.header.stamp=ros::Time(0);
218  exploration_goal.header.frame_id=mapData.header.frame_id;
219  exploration_goal.point.x=x_new[0];
220  exploration_goal.point.y=x_new[1];
221  exploration_goal.point.z=0.0;
222  p.x=x_new[0];
223  p.y=x_new[1];
224  p.z=0.0;
225  points.points.push_back(p);
226  pub.publish(points) ;
227  targetspub.publish(exploration_goal);
228  points.points.clear();
229 
230  }
231 
232 
233  else if (checking==1){
234  V.push_back(x_new);
235 
236  p.x=x_new[0];
237  p.y=x_new[1];
238  p.z=0.0;
239  line.points.push_back(p);
240  p.x=x_nearest[0];
241  p.y=x_nearest[1];
242  p.z=0.0;
243  line.points.push_back(p);
244 
245  }
246 
247 
248 
249 pub.publish(line);
250 
251 
252 
253 
254 ros::spinOnce();
255 rate.sleep();
256  }return 0;}
float init_map_x
void rvizCallBack(const geometry_msgs::PointStamped::ConstPtr &msg)
void publish(const boost::shared_ptr< M > &message) const
void mapCallBack(const nav_msgs::OccupancyGrid::ConstPtr &msg)
visualization_msgs::Marker line
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool sleep() const
nav_msgs::OccupancyGrid mapData
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL const std::string & getName()
std::vector< float > Steer(std::vector< float >, std::vector< float >, float)
Definition: functions.cpp:47
geometry_msgs::PointStamped clickedpoint
geometry_msgs::PointStamped exploration_goal
char ObstacleFree(std::vector< float >, std::vector< float > &, nav_msgs::OccupancyGrid)
Definition: functions.cpp:99
float ydim
visualization_msgs::Marker points
float Xstartx
ROSCPP_DECL bool ok()
Definition: functions.h:13
float Norm(std::vector< float >, std::vector< float >)
Definition: functions.cpp:11
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
float xdim
std::vector< float > Nearest(std::vector< std::vector< float > >, std::vector< float >)
Definition: functions.cpp:26
Definition: mtrand.h:99
float Xstarty
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
int main(int argc, char **argv)
float init_map_y
float resolution
ROSCPP_DECL void spinOnce()
list frontiers
Definition: assigner.py:21


rrt_exploration
Author(s): Hassan Umari
autogenerated on Mon Jun 10 2019 14:57:44