pong.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
38 
39 int main(int argc, char** argv)
40 {
41  ros::init(argc, argv, "pong");
42  ros::NodeHandle nh("~");
45 
46  int size = 100;
47  nh.param("size", size, size);
48  info.width = size * 2;
49  info.height = size;
50  info.resolution = 0.1;
51  grid.setInfo(info);
52 
53  double radius = 4.0;
54  nh.param("radius", radius, radius);
55  radius *= info.resolution;
56 
57  double x = 0.0, y = size * info.resolution / 3;
58  double dx = info.resolution, dy = info.resolution;
59  double counter = 1.0;
60 
61  double max_x = info.resolution * info.width;
62  double max_y = info.resolution * info.height;
63 
64  bool publish_updates = true;
65  nh.param("updates", publish_updates, publish_updates);
66 
68  pub.init(nh);
69 
70  ros::Rate r(33);
71 
72  while (ros::ok())
73  {
74  nav_core2::UIntBounds bounds;
75  for (const nav_grid::Index& i : nav_grid_iterators::CircleFill(&info, x, y, radius))
76  {
77  grid.setValue(i, counter);
78  bounds.touch(i.x, i.y);
79  }
80  counter += 1.0;
81  x += dx;
82  y += dy;
83  if (x > max_x || x < 0.0) dx *= -1;
84  if (y > max_y || y < 0.0) dy *= -1;
85  if (publish_updates)
86  pub.publish(bounds);
87  else
88  pub.publish();
89  r.sleep();
90  ros::spinOnce();
91  }
92 
93  return 0;
94 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
Definition: pong.cpp:39
TFSIMD_FORCE_INLINE const tfScalar & y() const
void init(ros::NodeHandle &nh, const std::string &nav_grid_topic="grid", const std::string &occupancy_grid_topic="costmap", const std::string &update_area_topic="update_area", bool publish_updates=true, ros::Duration full_publish_cycle=ros::Duration(0), ros::Duration update_publish_cycle=ros::Duration(0))
void touch(unsigned intx, unsigned inty)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void setInfo(const NavGridInfo &new_info) override
ROSCPP_DECL bool ok()
TFSIMD_FORCE_INLINE const tfScalar & x() const
void setValue(const unsigned int x, const unsigned int y, const T &value) override
bool sleep()
ROSCPP_DECL void spinOnce()
r


robot_nav_viz_demos
Author(s):
autogenerated on Sun Jan 10 2021 04:09:02