nav_grid_of_doubles_display.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, 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 
37 #include <nav_2d_msgs/NavGridOfDoubles.h>
38 #include <nav_2d_msgs/NavGridOfDoublesUpdate.h>
39 #include <nav_2d_utils/bounds.h>
41 #include <limits>
42 #include <string>
43 
44 namespace robot_nav_rviz_plugins
45 {
62 {
63 public:
65  : NavGridDisplay(ros::message_traits::datatype<nav_2d_msgs::NavGridOfDoubles>(), true)
66  , sub_(double_data_) // set up the subscriber to update into `double_data_` which is translated to `panel_data_`
67  , first_data_(true)
68  {
69  // These properties can be defined here (and not the parent class) since they don't require qt events
70  min_property_ = new rviz::FloatProperty("Min Value", 0.0, "Minimum value in the grid (not editable)", this);
72  max_property_ = new rviz::FloatProperty("Max Value", 0.0, "Maximum value in the grid (not editable)", this);
74 
76  updateIgnore();
77  }
78 
79  void onSubscribe(const std::string& topic) override
80  {
82  sub_.init(update_nh_, std::bind(&NavGridOfDoublesDisplay::newDataCallback, this, std::placeholders::_1),
83  topic, true, true);
84  }
85 
86  void onUnsubscribe() override
87  {
88  sub_.deactivate();
89  }
90 
91  void updateIgnore()
92  {
95  }
96 protected:
98  {
99  min_value_ = std::numeric_limits<double>::max();
101  }
102 
104  {
105  if (bounds.isEmpty())
106  {
107  return;
108  }
109 
111 
112  if (first_data_)
113  {
114  panel_data_.setInfo(info);
115  first_data_ = false;
116  }
117  else
118  {
119  panel_data_.updateInfo(info);
120  }
122 
123  bool extremes_changed = false;
124  if (bounds == full_bounds)
125  {
126  // If the update covers the whole grid, start extreme value calculation from scratch
128  }
129 
130  // Search the updated area for new min/max values while ignoring `ignore_value_`.
131  IgnoreType ignore_type = getIgnoreType();
132  for (const nav_grid::Index& i : nav_grid_iterators::SubGrid(&info, bounds))
133  {
134  double value = double_data_(i);
135  if ((ignore_type == IgnoreType::VALUE && value == ignore_value_) ||
136  (ignore_type == IgnoreType::LIMIT && value >= ignore_value_))
137  {
138  continue;
139  }
140  else if (value < min_value_)
141  {
142  min_value_ = value;
143  extremes_changed = true;
144  }
145  else if (value > max_value_)
146  {
147  max_value_ = value;
148  extremes_changed = true;
149  }
150  }
151 
152  nav_core2::UIntBounds updated_bounds;
153  // If the extremes changed, then all the values need to be rescaled
154  if (extremes_changed)
155  {
156  updated_bounds.merge(full_bounds);
159  }
160  else
161  {
162  updated_bounds.merge(bounds);
163  }
164 
165  double denominator = max_value_ - min_value_;
166  // Ensure safe division
167  if (denominator == 0)
168  {
169  denominator = 1;
170  }
171 
172  for (const nav_grid::Index& i : nav_grid_iterators::SubGrid(&info, updated_bounds))
173  {
174  if ((ignore_type == IgnoreType::VALUE && double_data_(i) == ignore_value_) ||
175  (ignore_type == IgnoreType::LIMIT && double_data_(i) >= ignore_value_))
176  {
177  panel_data_.setValue(i, 0);
178  }
179  else
180  {
181  double ratio = (double_data_(i) - min_value_) / denominator;
182  panel_data_.setValue(i, 1 + static_cast<unsigned char>(254 * ratio));
183  }
184  }
185 
186  Q_EMIT mapUpdated(updated_bounds);
187  }
188 
194 
196 };
197 } // namespace robot_nav_rviz_plugins
198 
nav_grid_pub_sub::NavGridOfDoublesSubscriber sub_
void onUnsubscribe() override
Actual unsubscription logic, called by unsubscribe.
void onSubscribe(const std::string &topic) override
Actual subscription logic, called by subscribe.
ros::NodeHandle update_nh_
virtual float getFloat() const
virtual bool setValue(const QVariant &new_value)
nav_grid::VectorNavGrid< unsigned char > panel_data_
void newDataCallback(const nav_core2::UIntBounds &bounds)
Several reusable pieces for displaying polygons.
void setInfo(const NavGridInfo &new_info) override
void setValue(const unsigned int x, const unsigned int y, const T &value) override
void updateInfo(const NavGridInfo &new_info) override
void init(ros::NodeHandle &nh, NewDataCallback callback, const std::string &topic="map", bool nav_grid=true, bool subscribe_to_updates=true)
void merge(const GenericBounds< unsigned int > &other)
void mapUpdated(const nav_core2::UIntBounds &updated_bounds)
Custom signal emitted when new map data is received.
Displays a nav_grid of doubles along the XY plane.
NavGridInfo getInfo() const
nav_core2::UIntBounds getFullUIntBounds(const nav_grid::NavGridInfo &info)
Displays a nav_grid (of unspecified type) along the XY plane.
virtual void setReadOnly(bool read_only)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)


robot_nav_rviz_plugins
Author(s):
autogenerated on Sun Jan 10 2021 04:08:58