footprint_layer.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2008, 2013, 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  *         David V. Lu!!
00037  *********************************************************************/
00038 #include <costmap_2d/footprint_layer.h>
00039 #include <costmap_2d/footprint.h>
00040 #include <string>
00041 #include <sstream>
00042 #include <pluginlib/class_list_macros.h>
00043 
00044 PLUGINLIB_EXPORT_CLASS(costmap_2d::FootprintLayer, costmap_2d::Layer)
00045 
00046 namespace costmap_2d
00047 {
00048   void FootprintLayer::onInitialize()
00049   {
00050     ros::NodeHandle nh("~/" + name_);
00051     ros::NodeHandle g_nh;
00052     footprint_.header.frame_id = layered_costmap_->getGlobalFrameID();
00053     current_ = false;
00054 
00055     footprint_pub_ = nh.advertise<geometry_msgs::PolygonStamped>( "footprint_stamped", 1 );
00056 
00057     dsrv_ = new dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>(nh);
00058     dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>::CallbackType cb = boost::bind(&FootprintLayer::reconfigureCB, this, _1, _2);
00059     dsrv_->setCallback(cb);
00060 
00061     current_ = true;
00062   }
00063 
00064   FootprintLayer::~FootprintLayer()
00065   {
00066     if(dsrv_)
00067       delete dsrv_;
00068   }
00069 
00070   void FootprintLayer::reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level)
00071   {
00072     enabled_ = config.enabled;
00073   }
00074 
00075   void FootprintLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y, double* max_x, double* max_y)
00076   {
00077     if(!enabled_) return;
00078     //update transformed polygon
00079     footprint_.header.stamp = ros::Time::now();
00080     footprint_.polygon.points.clear();
00081     double cos_th = cos(robot_yaw);
00082     double sin_th = sin(robot_yaw);
00083     const std::vector<geometry_msgs::Point>& footprint_spec = getFootprint();
00084     for(unsigned int i = 0; i < footprint_spec.size(); ++i)
00085     {
00086       geometry_msgs::Point32 new_pt;
00087       new_pt.x = robot_x + (footprint_spec[i].x * cos_th - footprint_spec[i].y * sin_th);
00088       new_pt.y = robot_y + (footprint_spec[i].x * sin_th + footprint_spec[i].y * cos_th);
00089       footprint_.polygon.points.push_back(new_pt);
00090     }
00091 
00092     for(unsigned int i=0; i < footprint_.polygon.points.size(); i++)
00093     {
00094       double px = footprint_.polygon.points[i].x, py = footprint_.polygon.points[i].y;
00095       *min_x = std::min(px, *min_x);
00096       *min_y = std::min(py, *min_y);
00097       *max_x = std::max(px, *max_x);
00098       *max_y = std::max(py, *max_y);
00099     }
00100     footprint_pub_.publish( footprint_ );
00101   }
00102 
00103   void FootprintLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j)
00104   {
00105     if(!enabled_) return;
00106     std::vector<geometry_msgs::Point> footprint_points = costmap_2d::toPointVector(footprint_.polygon);
00107     master_grid.setConvexPolygonCost(footprint_points, costmap_2d::FREE_SPACE);
00108   }
00109 
00110 }  // namespace costmap_2d


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Aug 27 2015 14:06:55