map_grid_visualizer.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Eric Perko
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 Eric Perko 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 OWNER 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 #include <base_local_planner/map_grid_visualizer.h>
00035 #include <base_local_planner/map_cell.h>
00036 #include <vector>
00037 
00038 namespace base_local_planner {
00039   MapGridVisualizer::MapGridVisualizer() {}
00040 
00041 
00042   void MapGridVisualizer::initialize(const std::string& name,const costmap_2d::Costmap2D * costmap, boost::function<bool (int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)> cost_function) {
00043     name_ = name;
00044     costmap_p_ = costmap;
00045     cost_function_ = cost_function;
00046 
00047     ns_nh_ = ros::NodeHandle("~/" + name_);
00048     ns_nh_.param("publish_cost_grid_pc", publish_cost_grid_pc_, false);
00049     ns_nh_.param("global_frame_id", frame_id_, std::string("odom"));
00050 
00051     cost_cloud_.header.frame_id = frame_id_;
00052     pub_.advertise(ns_nh_, "cost_cloud", 1);
00053   }
00054 
00055   void MapGridVisualizer::publishCostCloud() {
00056     if(publish_cost_grid_pc_) {
00057       unsigned int x_size = costmap_p_->getSizeInCellsX();
00058       unsigned int y_size = costmap_p_->getSizeInCellsY();
00059       double z_coord = 0.0;
00060       double x_coord, y_coord;
00061       MapGridCostPoint pt;
00062       cost_cloud_.points.clear();
00063       cost_cloud_.header.stamp = ros::Time::now();
00064       float path_cost, goal_cost, occ_cost, total_cost;
00065       for (unsigned int cx = 0; cx < x_size; cx++) {
00066         for(unsigned int cy = 0; cy < y_size; cy++) {
00067           costmap_p_->mapToWorld(cx, cy, x_coord, y_coord);
00068           if(cost_function_(cx, cy, path_cost, goal_cost, occ_cost, total_cost)) {
00069             pt.x = x_coord;
00070             pt.y = y_coord;
00071             pt.z = z_coord;
00072             pt.path_cost = path_cost;
00073             pt.goal_cost = goal_cost;
00074             pt.occ_cost = occ_cost;
00075             pt.total_cost = total_cost;
00076             cost_cloud_.push_back(pt);
00077           }
00078         }
00079       }
00080       pub_.publish(cost_cloud_);
00081       ROS_DEBUG("Cost PointCloud published");
00082     }
00083   }
00084 };


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko
autogenerated on Sat Dec 28 2013 17:13:50