footprint.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, 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 
35 #include <nav_2d_utils/footprint.h>
36 #include <nav_2d_utils/polygons.h>
37 #include <string>
38 
39 namespace nav_2d_utils
40 {
41 nav_2d_msgs::Polygon2D footprintFromParams(ros::NodeHandle& nh, bool write)
42 {
43  std::string full_param_name;
44  nav_2d_msgs::Polygon2D footprint;
45 
46  if (nh.searchParam("footprint", full_param_name))
47  {
48  footprint = polygonFromParams(nh, full_param_name, false);
49  if (write)
50  {
51  nh.setParam("footprint", polygonToXMLRPC(footprint));
52  }
53  }
54  else if (nh.searchParam("robot_radius", full_param_name))
55  {
56  double robot_radius = 0.0;
57  nh.getParam(full_param_name, robot_radius);
58  footprint = polygonFromRadius(robot_radius);
59  if (write)
60  {
61  nh.setParam("robot_radius", robot_radius);
62  }
63  }
64  return footprint;
65 }
66 
67 } // namespace nav_2d_utils
nav_2d_msgs::Polygon2D polygonFromParams(const ros::NodeHandle &nh, const std::string parameter_name, bool search=true)
Load a polygon from a parameter, whether it is a string or array, or two arrays.
Definition: polygons.cpp:249
nav_2d_msgs::Polygon2D footprintFromParams(ros::NodeHandle &nh, bool write=true)
Load the robot footprint either as a polygon from the footprint parameter or from robot_radius...
Definition: footprint.cpp:41
nav_2d_msgs::Polygon2D polygonFromRadius(const double radius, const unsigned int num_points=16)
Create a "circular" polygon from a given radius.
Definition: polygons.cpp:111
bool searchParam(const std::string &key, std::string &result) const
bool getParam(const std::string &key, std::string &s) const
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
XmlRpc::XmlRpcValue polygonToXMLRPC(const nav_2d_msgs::Polygon2D &polygon, bool array_of_arrays=true)
Create XMLRPC Value for writing the polygon to the parameter server.
Definition: polygons.cpp:286


nav_2d_utils
Author(s):
autogenerated on Wed Jun 26 2019 20:06:11