00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2018, Locus Robotics 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the copyright holder nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 */ 00034 00035 #include <nav_2d_utils/footprint.h> 00036 #include <nav_2d_utils/polygons.h> 00037 #include <string> 00038 00039 namespace nav_2d_utils 00040 { 00041 nav_2d_msgs::Polygon2D footprintFromParams(ros::NodeHandle& nh, bool write) 00042 { 00043 std::string full_param_name; 00044 nav_2d_msgs::Polygon2D footprint; 00045 00046 if (nh.searchParam("footprint", full_param_name)) 00047 { 00048 footprint = polygonFromParams(nh, full_param_name, false); 00049 if (write) 00050 { 00051 nh.setParam("footprint", polygonToXMLRPC(footprint)); 00052 } 00053 } 00054 else if (nh.searchParam("robot_radius", full_param_name)) 00055 { 00056 double robot_radius = 0.0; 00057 nh.getParam(full_param_name, robot_radius); 00058 footprint = polygonFromRadius(robot_radius); 00059 if (write) 00060 { 00061 nh.setParam("robot_radius", robot_radius); 00062 } 00063 } 00064 return footprint; 00065 } 00066 00067 } // namespace nav_2d_utils