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 #include <ros/ros.h>
00036 #include <nav_grid_iterators/iterators.h>
00037 #include <nav_grid/vector_nav_grid.h>
00038 #include <nav_msgs/OccupancyGrid.h>
00039 #include <nav_2d_utils/conversions.h>
00040 #include <vector>
00041
00042 template<class Iterator>
00043 class InfiniteIterator
00044 {
00045 public:
00046 InfiniteIterator(Iterator it, unsigned char active_value, unsigned char seen_value)
00047 : it_(it), active_(active_value), seen_(seen_value)
00048 {
00049 }
00050
00051 void iterate(nav_grid::NavGrid<unsigned char>& grid)
00052 {
00053
00054 grid.setValue(*it_, seen_);
00055 ++it_;
00056 if (it_ == it_.end())
00057 {
00058 it_ = it_.begin();
00059 }
00060 grid.setValue(*it_, active_);
00061 }
00062
00063 private:
00064 Iterator it_;
00065 unsigned char active_, seen_;
00066 };
00067
00068 int main(int argc, char** argv)
00069 {
00070 ros::init(argc, argv, "iterator_demo");
00071 nav_grid::VectorNavGrid<unsigned char> grid;
00072 nav_grid::NavGridInfo info;
00073 sleep(5.0);
00074 info.width = 75;
00075 info.height = 60;
00076 info.resolution = 0.1;
00077 grid.setInfo(info);
00078
00079 ros::NodeHandle nh("~");
00080 ros::Publisher pub = nh.advertise<nav_msgs::OccupancyGrid>("/map", 1);
00081 ros::Rate r(33);
00082
00083 nav_2d_msgs::Polygon2D triangle;
00084 triangle.points.resize(3);
00085 triangle.points[0].x = 1.9;
00086 triangle.points[0].y = 0.5;
00087 triangle.points[1].x = 3.5;
00088 triangle.points[1].y = 1.0;
00089 triangle.points[2].x = 2.0;
00090 triangle.points[2].y = 2.4;
00091
00092 nav_2d_msgs::Polygon2D diamond;
00093 diamond.points.resize(4);
00094 diamond.points[0].x = 4.5;
00095 diamond.points[0].y = 0.0;
00096 diamond.points[1].x = 5.3;
00097 diamond.points[1].y = 1.25;
00098 diamond.points[2].x = 4.5;
00099 diamond.points[2].y = 2.5;
00100 diamond.points[3].x = 3.7;
00101 diamond.points[3].y = 1.25;
00102
00103 nav_2d_msgs::Polygon2D diamond2;
00104 diamond2.points.resize(4);
00105 diamond2.points[0].x = 6.5;
00106 diamond2.points[0].y = 0.0;
00107 diamond2.points[1].x = 7.3;
00108 diamond2.points[1].y = 1.25;
00109 diamond2.points[2].x = 6.5;
00110 diamond2.points[2].y = 2.5;
00111 diamond2.points[3].x = 5.7;
00112 diamond2.points[3].y = 1.25;
00113
00114 InfiniteIterator<nav_grid_iterators::WholeGrid> whole_grid(nav_grid_iterators::WholeGrid(&info), 100, 50);
00115 InfiniteIterator<nav_grid_iterators::SubGrid> sub_grid(nav_grid_iterators::SubGrid(&info, 3, 5, 14, 15), 99, 101);
00116 InfiniteIterator<nav_grid_iterators::Line> line(nav_grid_iterators::Line(&info, 7.3, 2.8, 0.2, 2.5), 126, 200);
00117 InfiniteIterator<nav_grid_iterators::Line> line2(nav_grid_iterators::Line(&info, 7.3, 3.3, 0.2, 3.0, true, false),
00118 126, 200);
00119 InfiniteIterator<nav_grid_iterators::CircleFill> circle_fill(nav_grid_iterators::CircleFill(&info, 1.25, 4.8, 1.0),
00120 254, 255);
00121 InfiniteIterator<nav_grid_iterators::Spiral> spiral(nav_grid_iterators::Spiral(&info, 3.75, 4.8, 1.0), 254, 126);
00122 InfiniteIterator<nav_grid_iterators::CircleOutline> circle_o(nav_grid_iterators::CircleOutline(&info, 6.25, 4.8, 1.0),
00123 254, 99);
00124 InfiniteIterator<nav_grid_iterators::PolygonFill> poly_f(nav_grid_iterators::PolygonFill(&info, triangle), 126, 254);
00125 InfiniteIterator<nav_grid_iterators::PolygonOutline> poly_o(nav_grid_iterators::PolygonOutline(&info, diamond), 0, 1);
00126 InfiniteIterator<nav_grid_iterators::PolygonOutline> poly_r(nav_grid_iterators::PolygonOutline(&info, diamond2, 0),
00127 0, 1);
00128
00129 nav_msgs::OccupancyGrid ogrid;
00130 ogrid.header.frame_id = info.frame_id;
00131 ogrid.info = nav_2d_utils::infoToInfo(info);
00132 ogrid.data.resize(info.width * info.height);
00133
00134 while (ros::ok())
00135 {
00136 whole_grid.iterate(grid);
00137 sub_grid.iterate(grid);
00138 line.iterate(grid);
00139 line2.iterate(grid);
00140 circle_fill.iterate(grid);
00141 spiral.iterate(grid);
00142 circle_o.iterate(grid);
00143 poly_f.iterate(grid);
00144 poly_o.iterate(grid);
00145 poly_r.iterate(grid);
00146
00147
00148 ogrid.header.stamp = ros::Time::now();
00149
00150 unsigned int data_index = 0;
00151 for (const nav_grid::Index& index : nav_grid_iterators::WholeGrid(info))
00152 {
00153 ogrid.data[data_index++] = grid(index);
00154 }
00155 pub.publish(ogrid);
00156 r.sleep();
00157 }
00158
00159 return 0;
00160 }