send_grid_cells_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include "ros/ros.h"
31 #include "nav_msgs/GridCells.h"
32 #include "math.h"
33 
34 int main(int argc, char** argv)
35 {
36  ros::init(argc, argv, "send_grid_cells");
37 
38  ros::NodeHandle nh;
39 
40  ros::Publisher pub = nh.advertise<nav_msgs::GridCells>("grid_cells", 100);
41  ros::Rate loop_rate(100);
42 
43  nav_msgs::GridCells msg;
44  int width = 500;
45  int length = 500;
46  msg.cells.resize(width * length);
47  msg.header.frame_id = "base_link";
48  msg.cell_width = .01;
49  msg.cell_height = .01;
50 
51  int count = 0;
52  while (ros::ok())
53  {
54  for (int x = 0; x < width; x++)
55  {
56  for (int y = 0; y < length; y++)
57  {
58  geometry_msgs::Point& point = msg.cells[x + y * width];
59  point.x = x / 100.0;
60  point.y = y / 100.0;
61  point.z = sin(x / 100.0 + y / 100.0 + count / 100.0);
62  // point.z = ((x + y + count) % 100) / 100.0;
63  }
64  }
65  msg.header.seq = count;
66  msg.header.stamp = ros::Time::now();
67 
68  pub.publish(msg);
69 
70  ros::spinOnce();
71  loop_rate.sleep();
72  ++count;
73  }
74 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static Time now()
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
ROSCPP_DECL void spinOnce()
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:25