nav_grid_subscriber.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
40 #include <string>
41 #include <vector>
42 
43 namespace nav_grid_pub_sub
44 {
45 void NavGridSubscriber::init(ros::NodeHandle& nh, NewDataCallback callback, const std::string& topic,
46  bool nav_grid, bool subscribe_to_updates)
47 {
48  nh_ = nh;
49  callback_ = callback;
50  topic_ = topic;
51  nav_grid_ = nav_grid;
52  subscribe_to_updates_ = subscribe_to_updates;
53  activate();
54 }
55 
57 {
58  std::string resolved_topic = nh_.resolveName(topic_);
59  map_received_ = false;
60  if (nav_grid_)
61  {
62  sub_ = nh_.subscribe(resolved_topic, 1, &NavGridSubscriber::incomingNav, this);
64  {
65  update_sub_ = nh_.subscribe(resolved_topic + "_updates", 10, &NavGridSubscriber::incomingNavUpdate, this);
66  }
67  }
68  else
69  {
70  sub_ = nh_.subscribe(resolved_topic, 1, &NavGridSubscriber::incomingOcc, this);
72  {
73  update_sub_ = nh_.subscribe(resolved_topic + "_updates", 10, &NavGridSubscriber::incomingOccUpdate, this);
74  }
75  }
76 }
77 
79 {
80  sub_.shutdown();
82 }
83 
84 void NavGridSubscriber::incomingNav(const nav_2d_msgs::NavGridOfCharsConstPtr& new_map)
85 {
86  nav_grid::NavGridInfo info = nav_2d_utils::fromMsg(new_map->info);
87  const nav_grid::NavGridInfo current_info = data_.getInfo();
88  if (info != current_info)
89  {
90  data_.setInfo(info);
91  }
92 
93  unsigned int data_index = 0;
94  for (const nav_grid::Index& index : nav_grid_iterators::WholeGrid(info))
95  {
96  data_.setValue(index, new_map->data[data_index++]);
97  }
98  map_received_ = true;
99  callback_(nav_core2::UIntBounds(0, 0, info.width - 1, info.height - 1));
100 }
101 
102 void NavGridSubscriber::incomingNavUpdate(const nav_2d_msgs::NavGridOfCharsUpdateConstPtr& update)
103 {
104  const nav_grid::NavGridInfo& info = data_.getInfo();
105  nav_core2::UIntBounds bounds = nav_2d_utils::fromMsg(update->bounds);
106  unsigned int data_index = 0;
107  for (const nav_grid::Index& index : nav_grid_iterators::SubGrid(&info, bounds))
108  {
109  data_.setValue(index, update->data[data_index++]);
110  }
111  callback_(bounds);
112 }
113 
114 void NavGridSubscriber::incomingOcc(const nav_msgs::OccupancyGridConstPtr& new_map)
115 {
116  nav_grid::NavGridInfo info = nav_2d_utils::infoToInfo(new_map->info);
117  const nav_grid::NavGridInfo current_info = data_.getInfo();
118  if (info != current_info)
119  {
120  data_.setInfo(info);
121  data_.reset();
122  }
123  unsigned int data_index = 0;
124  for (const nav_grid::Index& index : nav_grid_iterators::WholeGrid(info))
125  {
126  data_.setValue(index, interpretCost(new_map->data[data_index++], cost_interpretation_table_));
127  }
128 
129  map_received_ = true;
130  callback_(nav_core2::UIntBounds(0, 0, info.width - 1, info.height - 1));
131 }
132 
133 void NavGridSubscriber::incomingOccUpdate(const map_msgs::OccupancyGridUpdateConstPtr& update)
134 {
135  const nav_grid::NavGridInfo& info = data_.getInfo();
136  nav_core2::UIntBounds bounds(update->x, update->y, update->x + update->width - 1, update->y + update->height - 1);
137  unsigned int data_index = 0;
138  for (const nav_grid::Index& index : nav_grid_iterators::SubGrid(&info, bounds))
139  {
140  data_.setValue(index, interpretCost(update->data[data_index++], cost_interpretation_table_));
141  }
142  callback_(bounds);
143 }
144 } // namespace nav_grid_pub_sub
void incomingNav(const nav_2d_msgs::NavGridOfCharsConstPtr &new_map)
virtual void setValue(const unsigned int x, const unsigned int y, const T &value)=0
virtual void reset()=0
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string resolveName(const std::string &name, bool remap=true) const
nav_grid::NavGridInfo fromMsg(const nav_2d_msgs::NavGridInfo &msg)
void incomingOccUpdate(const map_msgs::OccupancyGridUpdateConstPtr &update)
std::vector< unsigned char > cost_interpretation_table_
void init(ros::NodeHandle &nh, NewDataCallback callback, const std::string &topic="map", bool nav_grid=true, bool subscribe_to_updates=true)
void incomingOcc(const nav_msgs::OccupancyGridConstPtr &new_map)
void incomingNavUpdate(const nav_2d_msgs::NavGridOfCharsUpdateConstPtr &update)
unsigned char interpretCost(unsigned char original_value, const std::vector< unsigned char > &cost_interpretation_table)
return cost_interpretation_table[original_value] (or original_value if not a valid index) ...
virtual void setInfo(const NavGridInfo &new_info)=0
NavGridInfo getInfo() const
nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData &metadata)
std::function< void(const nav_core2::UIntBounds &)> NewDataCallback
nav_grid::NavGrid< unsigned char > & data_


nav_grid_pub_sub
Author(s):
autogenerated on Wed Jun 26 2019 20:06:28