8 int main(
int argc,
char** argv)
11 init(argc, argv,
"resolution_change_demo");
13 Publisher publisher = nodeHandle.
advertise<grid_map_msgs::GridMap>(
"grid_map", 1,
true);
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));
24 map[
"elevation"].setZero();
40 map.at(
"elevation", *iterator) = 0.3;
46 while (nodeHandle.
ok()) {
50 const double resolution = 0.05 + 0.04 * sin(time.
toSec());
57 grid_map_msgs::GridMap message;
60 ROS_INFO_STREAM(
"Published grid map with " << resolution <<
" m/cell resolution.");
void publish(const boost::shared_ptr< M > &message) const
int main(int argc, char **argv)
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)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void addVertex(const Position &vertex)
#define ROS_INFO_STREAM(args)
void setFrameId(const std::string &frameId)
static bool changeResolution(const GridMap &gridMapSource, GridMap &gridMapResult, const double resolution, const int interpolationAlgorithm=cv::INTER_CUBIC)
void setFrameId(const std::string &frameId)