nav_grid_subscriber.h
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 
35 #ifndef NAV_GRID_PUB_SUB_NAV_GRID_SUBSCRIBER_H
36 #define NAV_GRID_PUB_SUB_NAV_GRID_SUBSCRIBER_H
37 
38 #include <ros/ros.h>
39 #include <nav_grid/nav_grid.h>
40 #include <nav_core2/bounds.h>
41 #include <nav_2d_msgs/NavGridOfChars.h>
42 #include <nav_2d_msgs/NavGridOfCharsUpdate.h>
43 #include <nav_2d_msgs/NavGridOfDoubles.h>
44 #include <nav_2d_msgs/NavGridOfDoublesUpdate.h>
45 #include <nav_msgs/OccupancyGrid.h>
46 #include <map_msgs/OccupancyGridUpdate.h>
47 #include <nav_2d_utils/bounds.h>
50 #include <string>
51 #include <vector>
52 
53 namespace nav_grid_pub_sub
54 {
55 template<typename NumericType, typename NavGridOfX, typename NavGridOfXUpdate>
57 {
58 public:
59  using NewDataCallback = std::function<void(const nav_core2::UIntBounds&)>;
60 
62  void init(ros::NodeHandle& nh, NewDataCallback callback, const std::string& topic = "map",
63  bool nav_grid = true, bool subscribe_to_updates = true)
64  {
65  nh_ = nh;
66  callback_ = callback;
67  topic_ = topic;
69  subscribe_to_updates_ = subscribe_to_updates;
70  activate();
71  }
72 
73  void activate()
74  {
75  std::string resolved_topic = nh_.resolveName(topic_);
76  map_received_ = false;
77  if (nav_grid_)
78  {
79  sub_ = nh_.subscribe(resolved_topic, 1, &GenericNavGridSubscriber::incomingNav, this);
81  {
82  update_sub_ = nh_.subscribe(resolved_topic + "_updates", 10,
84  }
85  }
86  else
87  {
88  sub_ = nh_.subscribe(resolved_topic, 1, &GenericNavGridSubscriber::incomingOcc, this);
90  {
91  update_sub_ = nh_.subscribe(resolved_topic + "_updates", 10,
93  }
94  }
95  }
96 
97  void deactivate()
98  {
99  sub_.shutdown();
101  }
102 
103  bool hasData() const { return map_received_; }
104 
105  void setCostInterpretation(const std::vector<NumericType>& cost_interpretation_table)
106  {
107  cost_interpretation_table_ = cost_interpretation_table;
108  }
109 protected:
110  void incomingNav(const NavGridOfX& new_map)
111  {
112  fromMsg(new_map, data_);
113  map_received_ = true;
115  }
116 
117  void incomingNavUpdate(const NavGridOfXUpdate& update)
118  {
119  if (!map_received_)
120  {
121  return;
122  }
123  nav_core2::UIntBounds bounds = fromUpdate(update, data_);
124  callback_(bounds);
125  }
126 
127  void incomingOcc(const nav_msgs::OccupancyGridConstPtr& new_map)
128  {
129  if (!map_received_)
130  {
131  return;
132  }
134  map_received_ = true;
136  }
137 
138  void incomingOccUpdate(const map_msgs::OccupancyGridUpdateConstPtr& update)
139  {
141  callback_(bounds);
142  }
143 
146 
147  std::vector<NumericType> cost_interpretation_table_;
148 
151 
153  std::string topic_;
155 };
156 
157 using NavGridSubscriber =
159 
162 
163 } // namespace nav_grid_pub_sub
164 
165 #endif // NAV_GRID_PUB_SUB_NAV_GRID_SUBSCRIBER_H
void setCostInterpretation(const std::vector< NumericType > &cost_interpretation_table)
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
void fromOccupancyGrid(const nav_msgs::OccupancyGrid &msg, nav_grid::NavGrid< NumericType > &grid, const std::vector< NumericType > &cost_interpretation_table)
generic OccupancyGrid to NavGrid conversion using cost_interpretation_table
void incomingNav(const NavGridOfX &new_map)
void incomingOcc(const nav_msgs::OccupancyGridConstPtr &new_map)
std::vector< NumericType > cost_interpretation_table_
std::function< void(const nav_core2::UIntBounds &)> NewDataCallback
void incomingOccUpdate(const map_msgs::OccupancyGridUpdateConstPtr &update)
nav_core2::UIntBounds fromOccupancyGridUpdate(const map_msgs::OccupancyGridUpdate &update, nav_grid::NavGrid< NumericType > &grid, const std::vector< NumericType > &cost_interpretation_table)
generic OccupancyGridUpdate to NavGrid conversion using cost_interpretation_table.
void init(ros::NodeHandle &nh, NewDataCallback callback, const std::string &topic="map", bool nav_grid=true, bool subscribe_to_updates=true)
nav_grid::NavGrid< NumericType > & data_
NavGridInfo getInfo() const
nav_core2::UIntBounds getFullUIntBounds(const nav_grid::NavGridInfo &info)
void fromMsg(const ROSMsgType &msg, nav_grid::NavGrid< NumericType > &grid)
Generic conversion from message of arbitrary type to grid of arbitrary type.
void incomingNavUpdate(const NavGridOfXUpdate &update)
nav_core2::UIntBounds fromUpdate(const ROSMsgType &update, nav_grid::NavGrid< NumericType > &grid)
Generic conversion from an update message to a portion of a grid of arbitrary type.
GenericNavGridSubscriber(nav_grid::NavGrid< NumericType > &data)


nav_grid_pub_sub
Author(s):
autogenerated on Sun Jan 10 2021 04:08:50