nav_grid_subscriber.cpp
Go to the documentation of this file.
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_grid_pub_sub/nav_grid_subscriber.h>
00036 #include <nav_2d_utils/conversions.h>
00037 #include <nav_grid_pub_sub/cost_interpretation.h>
00038 #include <nav_grid_iterators/whole_grid.h>
00039 #include <nav_grid_iterators/sub_grid.h>
00040 #include <string>
00041 #include <vector>
00042 
00043 namespace nav_grid_pub_sub
00044 {
00045 void NavGridSubscriber::init(ros::NodeHandle& nh, NewDataCallback callback, const std::string& topic,
00046                              bool nav_grid, bool subscribe_to_updates)
00047 {
00048   nh_ = nh;
00049   callback_ = callback;
00050   topic_ = topic;
00051   nav_grid_ = nav_grid;
00052   subscribe_to_updates_ = subscribe_to_updates;
00053   activate();
00054 }
00055 
00056 void NavGridSubscriber::activate()
00057 {
00058   std::string resolved_topic = nh_.resolveName(topic_);
00059   map_received_ = false;
00060   if (nav_grid_)
00061   {
00062     sub_ = nh_.subscribe(resolved_topic, 1, &NavGridSubscriber::incomingNav, this);
00063     if (subscribe_to_updates_)
00064     {
00065       update_sub_ = nh_.subscribe(resolved_topic + "_updates", 10, &NavGridSubscriber::incomingNavUpdate, this);
00066     }
00067   }
00068   else
00069   {
00070     sub_ = nh_.subscribe(resolved_topic, 1, &NavGridSubscriber::incomingOcc, this);
00071     if (subscribe_to_updates_)
00072     {
00073       update_sub_ = nh_.subscribe(resolved_topic + "_updates", 10, &NavGridSubscriber::incomingOccUpdate, this);
00074     }
00075   }
00076 }
00077 
00078 void NavGridSubscriber::deactivate()
00079 {
00080   sub_.shutdown();
00081   update_sub_.shutdown();
00082 }
00083 
00084 void NavGridSubscriber::incomingNav(const nav_2d_msgs::NavGridOfCharsConstPtr& new_map)
00085 {
00086   nav_grid::NavGridInfo info = nav_2d_utils::fromMsg(new_map->info);
00087   const nav_grid::NavGridInfo current_info = data_.getInfo();
00088   if (info != current_info)
00089   {
00090     data_.setInfo(info);
00091   }
00092 
00093   unsigned int data_index = 0;
00094   for (const nav_grid::Index& index : nav_grid_iterators::WholeGrid(info))
00095   {
00096     data_.setValue(index, new_map->data[data_index++]);
00097   }
00098   map_received_ = true;
00099   callback_(nav_core2::UIntBounds(0, 0, info.width - 1, info.height - 1));
00100 }
00101 
00102 void NavGridSubscriber::incomingNavUpdate(const nav_2d_msgs::NavGridOfCharsUpdateConstPtr& update)
00103 {
00104   const nav_grid::NavGridInfo& info = data_.getInfo();
00105   nav_core2::UIntBounds bounds = nav_2d_utils::fromMsg(update->bounds);
00106   unsigned int data_index = 0;
00107   for (const nav_grid::Index& index : nav_grid_iterators::SubGrid(&info, bounds))
00108   {
00109     data_.setValue(index, update->data[data_index++]);
00110   }
00111   callback_(bounds);
00112 }
00113 
00114 void NavGridSubscriber::incomingOcc(const nav_msgs::OccupancyGridConstPtr& new_map)
00115 {
00116   nav_grid::NavGridInfo info = nav_2d_utils::infoToInfo(new_map->info);
00117   const nav_grid::NavGridInfo current_info = data_.getInfo();
00118   if (info != current_info)
00119   {
00120     data_.setInfo(info);
00121     data_.reset();
00122   }
00123   unsigned int data_index = 0;
00124   for (const nav_grid::Index& index : nav_grid_iterators::WholeGrid(info))
00125   {
00126     data_.setValue(index, interpretCost(new_map->data[data_index++], cost_interpretation_table_));
00127   }
00128 
00129   map_received_ = true;
00130   callback_(nav_core2::UIntBounds(0, 0, info.width - 1, info.height - 1));
00131 }
00132 
00133 void NavGridSubscriber::incomingOccUpdate(const map_msgs::OccupancyGridUpdateConstPtr& update)
00134 {
00135   const nav_grid::NavGridInfo& info = data_.getInfo();
00136   nav_core2::UIntBounds bounds(update->x, update->y, update->x + update->width - 1, update->y + update->height - 1);
00137   unsigned int data_index = 0;
00138   for (const nav_grid::Index& index : nav_grid_iterators::SubGrid(&info, bounds))
00139   {
00140     data_.setValue(index, interpretCost(update->data[data_index++], cost_interpretation_table_));
00141   }
00142   callback_(bounds);
00143 }
00144 }  // namespace nav_grid_pub_sub


nav_grid_pub_sub
Author(s):
autogenerated on Wed Jun 26 2019 20:09:52