forked from ANYbotics/grid_map
-
Notifications
You must be signed in to change notification settings - Fork 0
/
simple_demo_node.cpp
47 lines (39 loc) · 1.35 KB
/
simple_demo_node.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
#include <ros/ros.h>
#include <grid_map_ros/grid_map_ros.hpp>
#include <grid_map_msgs/GridMap.h>
#include <cmath>
using namespace grid_map;
int main(int argc, char** argv)
{
// Initialize node and publisher.
ros::init(argc, argv, "grid_map_simple_demo");
ros::NodeHandle nh("~");
ros::Publisher publisher = nh.advertise<grid_map_msgs::GridMap>("grid_map", 1, true);
// Create grid map.
GridMap map({"elevation"});
map.setFrameId("map");
map.setGeometry(Length(1.2, 2.0), 0.03);
ROS_INFO("Created map with size %f x %f m (%i x %i cells).",
map.getLength().x(), map.getLength().y(),
map.getSize()(0), map.getSize()(1));
// Work with grid map in a loop.
ros::Rate rate(30.0);
while (nh.ok()) {
// Add data to grid map.
ros::Time time = ros::Time::now();
for (GridMapIterator it(map); !it.isPastEnd(); ++it) {
Position position;
map.getPosition(*it, position);
map.at("elevation", *it) = -0.04 + 0.2 * std::sin(3.0 * time.toSec() + 5.0 * position.y()) * position.x();
}
// Publish grid map.
map.setTimestamp(time.toNSec());
grid_map_msgs::GridMap message;
GridMapRosConverter::toMessage(map, message);
publisher.publish(message);
ROS_INFO_THROTTLE(1.0, "Grid map (timestamp %f) published.", message.info.header.stamp.toSec());
// Wait for next cycle.
rate.sleep();
}
return 0;
}