38 #include <nav_msgs/OccupancyGrid.h> 42 template<
class Iterator>
68 int main(
int argc,
char** argv)
83 nav_2d_msgs::Polygon2D triangle;
84 triangle.points.resize(3);
85 triangle.points[0].x = 1.9;
86 triangle.points[0].y = 0.5;
87 triangle.points[1].x = 3.5;
88 triangle.points[1].y = 1.0;
89 triangle.points[2].x = 2.0;
90 triangle.points[2].y = 2.4;
92 nav_2d_msgs::Polygon2D diamond;
93 diamond.points.resize(4);
94 diamond.points[0].x = 4.5;
95 diamond.points[0].y = 0.0;
96 diamond.points[1].x = 5.3;
97 diamond.points[1].y = 1.25;
98 diamond.points[2].x = 4.5;
99 diamond.points[2].y = 2.5;
100 diamond.points[3].x = 3.7;
101 diamond.points[3].y = 1.25;
103 nav_2d_msgs::Polygon2D diamond2;
104 diamond2.points.resize(4);
105 diamond2.points[0].x = 6.5;
106 diamond2.points[0].y = 0.0;
107 diamond2.points[1].x = 7.3;
108 diamond2.points[1].y = 1.25;
109 diamond2.points[2].x = 6.5;
110 diamond2.points[2].y = 2.5;
111 diamond2.points[3].x = 5.7;
112 diamond2.points[3].y = 1.25;
129 nav_msgs::OccupancyGrid ogrid;
130 ogrid.header.frame_id = info.
frame_id;
150 unsigned int data_index = 0;
153 ogrid.data[data_index++] = grid(index);
nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData &metadata, const std::string &frame)
void iterate(nav_grid::NavGrid< unsigned char > &grid)
virtual void setValue(const unsigned int x, const unsigned int y, const T &value)=0
void publish(const boost::shared_ptr< M > &message) const
InfiniteIterator(Iterator it, unsigned char active_value, unsigned char seen_value)
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Iterates over all of the valid indexes on the outline of a polygon.
Iterates over all of the valid indexes that lie within a circle from the center out.
Iterates over all of the valid indexes that lie within a circle in row major order.
void setInfo(const NavGridInfo &new_info) override
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Iterates over the valid indexes that lie on the outline of a circle.
Iterates over all of the valid indexes of a line.
Iterates over all of the valid indexes that lie within an arbitrary polygon in row major order...
Iterator for looping through every index within an aligned rectangular portion of the grid...