2 #include "std_msgs/String.h" 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" 34 void mapCallBack(
const nav_msgs::OccupancyGrid::ConstPtr& msg)
41 void rvizCallBack(
const geometry_msgs::PointStamped::ConstPtr& msg)
44 geometry_msgs::Point p;
49 points.points.push_back(p);
56 int main(
int argc,
char **argv)
59 unsigned long init[4] = {0x123, 0x234, 0x345, 0x456},
length = 7;
67 ros::init(argc, argv,
"local_rrt_frontier_detector");
72 std::string map_topic,base_frame_topic;
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");
112 points.pose.orientation.w =1.0;
113 line.pose.orientation.w = 1.0;
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;
130 geometry_msgs::Point p;
133 while(
points.points.size()<5)
143 std::vector<float> temp1;
144 temp1.push_back(
points.points[0].x);
145 temp1.push_back(
points.points[0].y);
147 std::vector<float> temp2;
148 temp2.push_back(
points.points[2].x);
149 temp2.push_back(
points.points[0].y);
152 init_map_x=
Norm(temp1,temp2);
153 temp1.clear(); temp2.clear();
155 temp1.push_back(
points.points[0].x);
156 temp1.push_back(
points.points[0].y);
158 temp2.push_back(
points.points[0].x);
159 temp2.push_back(
points.points[2].y);
161 init_map_y=
Norm(temp1,temp2);
162 temp1.clear(); temp2.clear();
171 geometry_msgs::Point trans;
173 std::vector< std::vector<float> > V;
174 std::vector<float> xnew;
175 xnew.push_back( trans.x);xnew.push_back( trans.y);
190 std::vector<float> x_rand,x_nearest,x_new;
203 x_rand.push_back( xr ); x_rand.push_back( yr );
211 x_new=
Steer(x_nearest,x_rand,eta);
228 points.points.push_back(p);
254 else if (checking==1){
260 line.points.push_back(p);
264 line.points.push_back(p);
nav_msgs::OccupancyGrid mapData
int main(int argc, char **argv)
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())
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)
TFSIMD_FORCE_INLINE const tfScalar & x() const
char ObstacleFree(std::vector< float >, std::vector< float > &, nav_msgs::OccupancyGrid)
TFSIMD_FORCE_INLINE const tfScalar & y() const
geometry_msgs::PointStamped clickedpoint
void mapCallBack(const nav_msgs::OccupancyGrid::ConstPtr &msg)
float Norm(std::vector< float >, std::vector< float >)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
geometry_msgs::PointStamped exploration_goal
std::vector< float > Nearest(std::vector< std::vector< float > >, std::vector< float >)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
visualization_msgs::Marker points
ROSCPP_DECL void spinOnce()