$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2009, Willow Garage, Inc. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of Willow Garage, Inc. nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 * Author: Eitan Marder-Eppstein 00036 *********************************************************************/ 00037 #include <clear_costmap_recovery/clear_costmap_recovery.h> 00038 #include <pluginlib/class_list_macros.h> 00039 00040 //register this planner as a RecoveryBehavior plugin 00041 PLUGINLIB_DECLARE_CLASS(clear_costmap_recovery, ClearCostmapRecovery, clear_costmap_recovery::ClearCostmapRecovery, nav_core::RecoveryBehavior) 00042 00043 namespace clear_costmap_recovery { 00044 ClearCostmapRecovery::ClearCostmapRecovery(): global_costmap_(NULL), local_costmap_(NULL), 00045 tf_(NULL), initialized_(false) {} 00046 00047 void ClearCostmapRecovery::initialize(std::string name, tf::TransformListener* tf, 00048 costmap_2d::Costmap2DROS* global_costmap, costmap_2d::Costmap2DROS* local_costmap){ 00049 if(!initialized_){ 00050 name_ = name; 00051 tf_ = tf; 00052 global_costmap_ = global_costmap; 00053 local_costmap_ = local_costmap; 00054 00055 //get some parameters from the parameter server 00056 ros::NodeHandle private_nh("~/" + name_); 00057 00058 private_nh.param("reset_distance", reset_distance_, 3.0); 00059 00060 initialized_ = true; 00061 } 00062 else{ 00063 ROS_ERROR("You should not call initialize twice on this object, doing nothing"); 00064 } 00065 } 00066 00067 void ClearCostmapRecovery::runBehavior(){ 00068 if(!initialized_){ 00069 ROS_ERROR("This object must be initialized before runBehavior is called"); 00070 return; 00071 } 00072 00073 if(global_costmap_ == NULL || local_costmap_ == NULL){ 00074 ROS_ERROR("The costmaps passed to the ClearCostmapRecovery object cannot be NULL. Doing nothing."); 00075 return; 00076 } 00077 00078 double gc_radius = global_costmap_->getCircumscribedRadius(); 00079 double lc_radius = local_costmap_->getCircumscribedRadius(); 00080 00081 global_costmap_->resetMapOutsideWindow(reset_distance_, reset_distance_); 00082 local_costmap_->resetMapOutsideWindow(reset_distance_, reset_distance_); 00083 00084 global_costmap_->clearNonLethalWindow(4 * gc_radius, 4 * gc_radius); 00085 local_costmap_->clearNonLethalWindow(4 * lc_radius, 4 * lc_radius); 00086 } 00087 };