3 #include <grid_map_msgs/GridMap.h> 8 int main(
int argc,
char** argv)
11 ros::init(argc, argv,
"grid_map_simple_demo");
18 map.setGeometry(
Length(1.2, 2.0), 0.03);
19 ROS_INFO(
"Created map with size %f x %f m (%i x %i cells).",
20 map.getLength().x(), map.getLength().y(),
21 map.getSize()(0), map.getSize()(1));
31 map.getPosition(*it, position);
32 map.at(
"elevation", *it) = -0.04 + 0.2 * std::sin(3.0 * time.
toSec() + 5.0 * position.y()) * position.x();
36 map.setTimestamp(time.
toNSec());
37 grid_map_msgs::GridMap message;
40 ROS_INFO_THROTTLE(1.0,
"Grid map (timestamp %f) published.", message.info.header.stamp.toSec());
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static void toMessage(const grid_map::GridMap &gridMap, grid_map_msgs::GridMap &message)
int main(int argc, char **argv)
#define ROS_INFO_THROTTLE(period,...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void setFrameId(const std::string &frameId)