12 #include <geometry_msgs/PolygonStamped.h> 21 : nodeHandle_(nodeHandle),
22 map_(vector<string>({
"type"}))
24 ROS_INFO(
"Grid map iterators demo node started.");
50 ROS_INFO(
"Running grid map iterator demo.");
59 const int i = iterator.getLinearIndex();
72 ROS_INFO(
"Running submap iterator demo.");
76 Index submapStartIndex(3, 5);
77 Index submapBufferSize(12, 7);
81 map_.
at(
"type", *iterator) = 1.0;
93 ROS_INFO(
"Running circle iterator demo.");
102 map_.
at(
"type", *iterator) = 1.0;
114 ROS_INFO(
"Running ellipse iterator demo.");
123 map_.
at(
"type", *iterator) = 1.0;
135 ROS_INFO(
"Running spiral iterator demo.");
144 map_.
at(
"type", *iterator) = 1.0;
156 ROS_INFO(
"Running line iterator demo.");
165 map_.
at(
"type", *iterator) = 1.0;
177 ROS_INFO(
"Running polygon iterator demo.");
179 if (prepareForOtherDemos)
map_[
"type"].setZero();
196 geometry_msgs::PolygonStamped message;
202 map_.
at(
"type", *iterator) = 1.0;
203 if (!prepareForOtherDemos) {
210 if (!prepareForOtherDemos) {
218 ROS_INFO(
"Running sliding window iterator demo.");
221 const size_t windowSize = 3;
227 map_.
at(
"type", *iterator) = iterator.getData().meanOfFinites();
235 polygon.
addVertex(center + (Eigen::Array2d(-1.0,-1.0) * windowHalfLength).matrix());
236 polygon.
addVertex(center + (Eigen::Array2d(-1.0, 1.0) * windowHalfLength).matrix());
237 polygon.
addVertex(center + (Eigen::Array2d( 1.0, 1.0) * windowHalfLength).matrix());
238 polygon.
addVertex(center + (Eigen::Array2d( 1.0,-1.0) * windowHalfLength).matrix());
240 geometry_msgs::PolygonStamped message;
252 grid_map_msgs::GridMap message;
255 ROS_DEBUG(
"Grid map (timestamp %f) published.", message.info.header.stamp.toSec());
void setGeometry(const Length &length, const double resolution, const Position &position=Position::Zero())
grid_map::GridMap map_
Grid map data.
ros::Publisher polygonPublisher_
Polygon publisher.
void demoSubmapIterator()
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher gridMapPublisher_
Grid map publisher.
bool getPosition(const Index &index, Position &position) const
const std::string & getFrameId() const
static void toMessage(const grid_map::GridMap &gridMap, grid_map_msgs::GridMap &message)
ros::NodeHandle & nodeHandle_
ROS nodehandle.
void demoCircleIterator()
Node for comparing different normal filters performances.
void demoGridMapIterator()
double getResolution() const
void demoSpiralIterator()
static void toMessage(const grid_map::Polygon &polygon, geometry_msgs::PolygonStamped &message)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void addVertex(const Position &vertex)
float & at(const std::string &layer, const Index &index)
void add(const std::string &layer, const double value=NAN)
void demoPolygonIterator(const bool prepareForOtherDemos=false)
void setFrameId(const std::string &frameId)
void demoEllipseIterator()
void setFrameId(const std::string &frameId)
void setTimestamp(const Time timestamp)
void demoSlidingWindowIterator()