37 #include <nav_2d_msgs/NavGridOfDoubles.h> 38 #include <nav_2d_msgs/NavGridOfDoublesUpdate.h> 65 :
NavGridDisplay(
ros::message_traits::datatype<nav_2d_msgs::NavGridOfDoubles>(), true)
99 min_value_ = std::numeric_limits<double>::max();
123 bool extremes_changed =
false;
124 if (bounds == full_bounds)
143 extremes_changed =
true;
148 extremes_changed =
true;
154 if (extremes_changed)
156 updated_bounds.
merge(full_bounds);
162 updated_bounds.
merge(bounds);
167 if (denominator == 0)
nav_grid_pub_sub::NavGridOfDoublesSubscriber sub_
NavGridOfDoublesDisplay()
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
void resetExtremeValues()
rviz::FloatProperty * ignore_property_
virtual bool setValue(const QVariant &new_value)
rviz::FloatProperty * max_property_
IgnoreType getIgnoreType() const
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)
rviz::FloatProperty * min_property_
nav_grid::VectorNavGrid< double > double_data_
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)