00001
00002
00003
00004
00005
00006
00007
00008
00009 #include "grid_map_demos/IteratorsDemo.hpp"
00010
00011
00012 #include <geometry_msgs/PolygonStamped.h>
00013
00014 using namespace std;
00015 using namespace ros;
00016 using namespace grid_map;
00017
00018 namespace grid_map_demos {
00019
00020 IteratorsDemo::IteratorsDemo(ros::NodeHandle& nodeHandle)
00021 : nodeHandle_(nodeHandle),
00022 map_(vector<string>({"type"}))
00023 {
00024 ROS_INFO("Grid map iterators demo node started.");
00025 gridMapPublisher_ = nodeHandle_.advertise<grid_map_msgs::GridMap>("grid_map", 1, true);
00026 polygonPublisher_ = nodeHandle_.advertise<geometry_msgs::PolygonStamped>("polygon", 1, true);
00027
00028
00029 map_.setGeometry(Length(1.0, 1.0), 0.05, Position(0.0, 0.0));
00030 map_.setFrameId("map");
00031
00032 publish();
00033 ros::Duration duration(2.0);
00034 duration.sleep();
00035
00036 demoGridMapIterator();
00037 demoSubmapIterator();
00038 demoCircleIterator();
00039 demoEllipseIterator();
00040 demoSpiralIterator();
00041 demoLineIterator();
00042 demoPolygonIterator();
00043 demoSlidingWindowIterator();
00044 }
00045
00046 IteratorsDemo::~IteratorsDemo() {}
00047
00048 void IteratorsDemo::demoGridMapIterator()
00049 {
00050 ROS_INFO("Running grid map iterator demo.");
00051 map_.clearAll();
00052 publish();
00053
00054
00055
00056
00057 grid_map::Matrix& data = map_["type"];
00058 for (grid_map::GridMapIterator iterator(map_); !iterator.isPastEnd(); ++iterator) {
00059 const int i = iterator.getLinearIndex();
00060 data(i) = 1.0;
00061 publish();
00062 ros::Duration duration(0.01);
00063 duration.sleep();
00064 }
00065
00066 ros::Duration duration(1.0);
00067 duration.sleep();
00068 }
00069
00070 void IteratorsDemo::demoSubmapIterator()
00071 {
00072 ROS_INFO("Running submap iterator demo.");
00073 map_.clearAll();
00074 publish();
00075
00076 Index submapStartIndex(3, 5);
00077 Index submapBufferSize(12, 7);
00078
00079 for (grid_map::SubmapIterator iterator(map_, submapStartIndex, submapBufferSize);
00080 !iterator.isPastEnd(); ++iterator) {
00081 map_.at("type", *iterator) = 1.0;
00082 publish();
00083 ros::Duration duration(0.02);
00084 duration.sleep();
00085 }
00086
00087 ros::Duration duration(1.0);
00088 duration.sleep();
00089 }
00090
00091 void IteratorsDemo::demoCircleIterator()
00092 {
00093 ROS_INFO("Running circle iterator demo.");
00094 map_.clearAll();
00095 publish();
00096
00097 Position center(0.0, -0.15);
00098 double radius = 0.4;
00099
00100 for (grid_map::CircleIterator iterator(map_, center, radius);
00101 !iterator.isPastEnd(); ++iterator) {
00102 map_.at("type", *iterator) = 1.0;
00103 publish();
00104 ros::Duration duration(0.02);
00105 duration.sleep();
00106 }
00107
00108 ros::Duration duration(1.0);
00109 duration.sleep();
00110 }
00111
00112 void IteratorsDemo::demoEllipseIterator()
00113 {
00114 ROS_INFO("Running ellipse iterator demo.");
00115 map_.clearAll();
00116 publish();
00117
00118 Position center(0.0, -0.15);
00119 Length length(0.45, 0.9);
00120
00121 for (grid_map::EllipseIterator iterator(map_, center, length, M_PI_4);
00122 !iterator.isPastEnd(); ++iterator) {
00123 map_.at("type", *iterator) = 1.0;
00124 publish();
00125 ros::Duration duration(0.02);
00126 duration.sleep();
00127 }
00128
00129 ros::Duration duration(1.0);
00130 duration.sleep();
00131 }
00132
00133 void IteratorsDemo::demoSpiralIterator()
00134 {
00135 ROS_INFO("Running spiral iterator demo.");
00136 map_.clearAll();
00137 publish();
00138
00139 Position center(0.0, -0.15);
00140 double radius = 0.4;
00141
00142 for (grid_map::SpiralIterator iterator(map_, center, radius);
00143 !iterator.isPastEnd(); ++iterator) {
00144 map_.at("type", *iterator) = 1.0;
00145 publish();
00146 ros::Duration duration(0.02);
00147 duration.sleep();
00148 }
00149
00150 ros::Duration duration(1.0);
00151 duration.sleep();
00152 }
00153
00154 void IteratorsDemo::demoLineIterator()
00155 {
00156 ROS_INFO("Running line iterator demo.");
00157 map_.clearAll();
00158 publish();
00159
00160 Index start(18, 2);
00161 Index end(2, 13);
00162
00163 for (grid_map::LineIterator iterator(map_, start, end);
00164 !iterator.isPastEnd(); ++iterator) {
00165 map_.at("type", *iterator) = 1.0;
00166 publish();
00167 ros::Duration duration(0.02);
00168 duration.sleep();
00169 }
00170
00171 ros::Duration duration(1.0);
00172 duration.sleep();
00173 }
00174
00175 void IteratorsDemo::demoPolygonIterator(const bool prepareForOtherDemos)
00176 {
00177 ROS_INFO("Running polygon iterator demo.");
00178 map_.clearAll();
00179 if (prepareForOtherDemos) map_["type"].setZero();
00180 publish();
00181
00182 grid_map::Polygon polygon;
00183 polygon.setFrameId(map_.getFrameId());
00184 polygon.addVertex(Position( 0.480, 0.000));
00185 polygon.addVertex(Position( 0.164, 0.155));
00186 polygon.addVertex(Position( 0.116, 0.500));
00187 polygon.addVertex(Position(-0.133, 0.250));
00188 polygon.addVertex(Position(-0.480, 0.399));
00189 polygon.addVertex(Position(-0.316, 0.000));
00190 polygon.addVertex(Position(-0.480, -0.399));
00191 polygon.addVertex(Position(-0.133, -0.250));
00192 polygon.addVertex(Position( 0.116, -0.500));
00193 polygon.addVertex(Position( 0.164, -0.155));
00194 polygon.addVertex(Position( 0.480, 0.000));
00195
00196 geometry_msgs::PolygonStamped message;
00197 grid_map::PolygonRosConverter::toMessage(polygon, message);
00198 polygonPublisher_.publish(message);
00199
00200 for (grid_map::PolygonIterator iterator(map_, polygon);
00201 !iterator.isPastEnd(); ++iterator) {
00202 map_.at("type", *iterator) = 1.0;
00203 if (!prepareForOtherDemos) {
00204 publish();
00205 ros::Duration duration(0.02);
00206 duration.sleep();
00207 }
00208 }
00209
00210 if (!prepareForOtherDemos) {
00211 ros::Duration duration(1.0);
00212 duration.sleep();
00213 }
00214 }
00215
00216 void IteratorsDemo::demoSlidingWindowIterator()
00217 {
00218 ROS_INFO("Running sliding window iterator demo.");
00219 demoPolygonIterator(true);
00220 publish();
00221 const size_t windowSize = 3;
00222 const grid_map::SlidingWindowIterator::EdgeHandling edgeHandling = grid_map::SlidingWindowIterator::EdgeHandling::CROP;
00223 map_.add("copy", map_["type"]);
00224
00225 for (grid_map::SlidingWindowIterator iterator(map_, "copy", edgeHandling, windowSize);
00226 !iterator.isPastEnd(); ++iterator) {
00227 map_.at("type", *iterator) = iterator.getData().meanOfFinites();
00228 publish();
00229
00230
00231 grid_map::Polygon polygon;
00232 Position center;
00233 map_.getPosition(*iterator, center);
00234 const Length windowHalfLength(Length::Constant(0.5 * (double) windowSize * map_.getResolution()));
00235 polygon.addVertex(center + (Eigen::Array2d(-1.0,-1.0) * windowHalfLength).matrix());
00236 polygon.addVertex(center + (Eigen::Array2d(-1.0, 1.0) * windowHalfLength).matrix());
00237 polygon.addVertex(center + (Eigen::Array2d( 1.0, 1.0) * windowHalfLength).matrix());
00238 polygon.addVertex(center + (Eigen::Array2d( 1.0,-1.0) * windowHalfLength).matrix());
00239 polygon.setFrameId(map_.getFrameId());
00240 geometry_msgs::PolygonStamped message;
00241 grid_map::PolygonRosConverter::toMessage(polygon, message);
00242 polygonPublisher_.publish(message);
00243
00244 ros::Duration duration(0.02);
00245 duration.sleep();
00246 }
00247 }
00248
00249 void IteratorsDemo::publish()
00250 {
00251 map_.setTimestamp(ros::Time::now().toNSec());
00252 grid_map_msgs::GridMap message;
00253 grid_map::GridMapRosConverter::toMessage(map_, message);
00254 gridMapPublisher_.publish(message);
00255 ROS_DEBUG("Grid map (timestamp %f) published.", message.info.header.stamp.toSec());
00256 }
00257
00258 }