local_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, "local_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  ros::param::param<std::string>(ns+"/robot_frame", base_frame_topic, "/robot_1/base_link");
80 //---------------------------------------------------------------
81 ros::Subscriber sub= nh.subscribe(map_topic, 100 ,mapCallBack);
82 ros::Subscriber rviz_sub= nh.subscribe("/clicked_point", 100 ,rvizCallBack);
83 
84 ros::Publisher targetspub = nh.advertise<geometry_msgs::PointStamped>("/detected_points", 10);
85 ros::Publisher pub = nh.advertise<visualization_msgs::Marker>(ns+"_shapes", 10);
86 
87 ros::Rate rate(100);
88 
89 
90 // wait until map is received, when a map is received, mapData.header.seq will not be < 1
91 while (mapData.header.seq<1 or mapData.data.size()<1) { ros::spinOnce(); ros::Duration(0.1).sleep();}
92 
93 
94 
95 //visualizations points and lines..
96 points.header.frame_id=mapData.header.frame_id;
97 line.header.frame_id=mapData.header.frame_id;
98 points.header.stamp=ros::Time(0);
99 line.header.stamp=ros::Time(0);
100 
101 points.ns=line.ns = "markers";
102 points.id = 0;
103 line.id =1;
104 
105 
106 points.type = points.POINTS;
107 line.type=line.LINE_LIST;
108 
109 //Set the marker action. Options are ADD, DELETE, and new in ROS Indigo: 3 (DELETEALL)
110 points.action =points.ADD;
111 line.action = line.ADD;
112 points.pose.orientation.w =1.0;
113 line.pose.orientation.w = 1.0;
114 line.scale.x = 0.03;
115 line.scale.y= 0.03;
116 points.scale.x=0.3;
117 points.scale.y=0.3;
118 
119 line.color.r =255.0/255.0;
120 line.color.g= 0.0/255.0;
121 line.color.b =0.0/255.0;
122 points.color.r = 255.0/255.0;
123 points.color.g = 0.0/255.0;
124 points.color.b = 0.0/255.0;
125 points.color.a=0.3;
126 line.color.a = 1.0;
127 points.lifetime = ros::Duration();
128 line.lifetime = ros::Duration();
129 
130 geometry_msgs::Point p;
131 
132 
133 while(points.points.size()<5)
134 {
135 ros::spinOnce();
136 
137 pub.publish(points) ;
138 }
139 
140 
141 
142 
143 std::vector<float> temp1;
144 temp1.push_back(points.points[0].x);
145 temp1.push_back(points.points[0].y);
146 
147 std::vector<float> temp2;
148 temp2.push_back(points.points[2].x);
149 temp2.push_back(points.points[0].y);
150 
151 
152 init_map_x=Norm(temp1,temp2);
153 temp1.clear(); temp2.clear();
154 
155 temp1.push_back(points.points[0].x);
156 temp1.push_back(points.points[0].y);
157 
158 temp2.push_back(points.points[0].x);
159 temp2.push_back(points.points[2].y);
160 
161 init_map_y=Norm(temp1,temp2);
162 temp1.clear(); temp2.clear();
163 
164 Xstartx=(points.points[0].x+points.points[2].x)*.5;
165 Xstarty=(points.points[0].y+points.points[2].y)*.5;
166 
167 
168 
169 
170 
171 geometry_msgs::Point trans;
172 trans=points.points[4];
173 std::vector< std::vector<float> > V;
174 std::vector<float> xnew;
175 xnew.push_back( trans.x);xnew.push_back( trans.y);
176 V.push_back(xnew);
177 
178 points.points.clear();
179 pub.publish(points) ;
180 
181 
182 
183 
184 
185 
186 
187 std::vector<float> frontiers;
188 int i=0;
189 float xr,yr;
190 std::vector<float> x_rand,x_nearest,x_new;
191 
192 tf::TransformListener listener;
193 // Main loop
194 while (ros::ok()){
195 
196 
197 // Sample free
198 x_rand.clear();
199 xr=(drand()*init_map_x)-(init_map_x*0.5)+Xstartx;
200 yr=(drand()*init_map_y)-(init_map_y*0.5)+Xstarty;
201 
202 
203 x_rand.push_back( xr ); x_rand.push_back( yr );
204 
205 
206 // Nearest
207 x_nearest=Nearest(V,x_rand);
208 
209 // Steer
210 
211 x_new=Steer(x_nearest,x_rand,eta);
212 
213 
214 // ObstacleFree 1:free -1:unkown (frontier region) 0:obstacle
215 char checking=ObstacleFree(x_nearest,x_new,mapData);
216 
217  if (checking==-1){
218 
219  exploration_goal.header.stamp=ros::Time(0);
220  exploration_goal.header.frame_id=mapData.header.frame_id;
221  exploration_goal.point.x=x_new[0];
222  exploration_goal.point.y=x_new[1];
223  exploration_goal.point.z=0.0;
224  p.x=x_new[0];
225  p.y=x_new[1];
226  p.z=0.0;
227 
228  points.points.push_back(p);
229  pub.publish(points) ;
230  targetspub.publish(exploration_goal);
231  points.points.clear();
232  V.clear();
233 
234 
235  tf::StampedTransform transform;
236  int temp=0;
237  while (temp==0){
238  try{
239  temp=1;
240  listener.lookupTransform(map_topic, base_frame_topic , ros::Time(0), transform);
241  }
242  catch (tf::TransformException ex){
243  temp=0;
244  ros::Duration(0.1).sleep();
245  }}
246 
247  x_new[0]=transform.getOrigin().x();
248  x_new[1]=transform.getOrigin().y();
249  V.push_back(x_new);
250  line.points.clear();
251  }
252 
253 
254  else if (checking==1){
255  V.push_back(x_new);
256 
257  p.x=x_new[0];
258  p.y=x_new[1];
259  p.z=0.0;
260  line.points.push_back(p);
261  p.x=x_nearest[0];
262  p.y=x_nearest[1];
263  p.z=0.0;
264  line.points.push_back(p);
265 
266  }
267 
268 
269 
270 pub.publish(line);
271 
272 
273 
274 
275 ros::spinOnce();
276 rate.sleep();
277  }return 0;}
nav_msgs::OccupancyGrid mapData
float Xstartx
int main(int argc, char **argv)
float Xstarty
visualization_msgs::Marker line
void publish(const boost::shared_ptr< M > &message) const
void rvizCallBack(const geometry_msgs::PointStamped::ConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
float xdim
bool sleep() const
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
TFSIMD_FORCE_INLINE const tfScalar & x() const
char ObstacleFree(std::vector< float >, std::vector< float > &, nav_msgs::OccupancyGrid)
Definition: functions.cpp:99
float resolution
ROSCPP_DECL bool ok()
TFSIMD_FORCE_INLINE const tfScalar & y() const
Definition: functions.h:13
geometry_msgs::PointStamped clickedpoint
float ydim
void mapCallBack(const nav_msgs::OccupancyGrid::ConstPtr &msg)
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)
geometry_msgs::PointStamped exploration_goal
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
float init_map_y
std::vector< float > Nearest(std::vector< std::vector< float > >, std::vector< float >)
Definition: functions.cpp:26
Definition: mtrand.h:99
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
visualization_msgs::Marker points
ROSCPP_DECL void spinOnce()
float init_map_x
list frontiers
Definition: assigner.py:21


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