Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav_grid_pub_sub::ScaleGridPublisher< NumericType > Class Template Reference

An interface for publishing NavGridOfDoubles/OccupancyGrid msgs and their updates periodically. More...

#include <nav_grid_publisher.h>

Inheritance diagram for nav_grid_pub_sub::ScaleGridPublisher< NumericType >:
Inheritance graph
[legend]

Public Member Functions

void setIgnoreValue (NumericType ignore_value)
 
- Public Member Functions inherited from nav_grid_pub_sub::GenericGridPublisher< NumericType, nav_2d_msgs::NavGridOfDoubles, nav_2d_msgs::NavGridOfDoublesUpdate >
 GenericGridPublisher (nav_grid::NavGrid< NumericType > &data)
 
void init (ros::NodeHandle &nh, const std::string &nav_grid_topic="grid", const std::string &occupancy_grid_topic="costmap", const std::string &update_area_topic="update_area", bool publish_updates=true, ros::Duration full_publish_cycle=ros::Duration(0), ros::Duration update_publish_cycle=ros::Duration(0))
 Initialize method for determining what gets published when. More...
 
void publish ()
 Publish the full grid if the full_publish_cycle allows. More...
 
void publish (const nav_core2::UIntBounds &bounds)
 Publish the full grid or updates, as dictated by parameters passed to init. More...
 

Protected Member Functions

nav_msgs::OccupancyGrid toOccupancyGrid (const ros::Time &timestamp) override
 
map_msgs::OccupancyGridUpdate toOccupancyGridUpdate (const nav_core2::UIntBounds &bounds, const ros::Time &timestamp) override
 
- Protected Member Functions inherited from nav_grid_pub_sub::GenericGridPublisher< NumericType, nav_2d_msgs::NavGridOfDoubles, nav_2d_msgs::NavGridOfDoublesUpdate >
void createPublishers (ros::NodeHandle &nh, const std::string &topic, Callback new_subscription_callback, ros::Publisher &full_grid_pub, ros::Publisher &update_pub, bool publish_updates)
 
void onNewSubscriptionNav (const ros::SingleSubscriberPublisher &pub)
 
void onNewSubscriptionOcc (const ros::SingleSubscriberPublisher &pub)
 
void publishNav ()
 
void publishNavUpdate (const nav_core2::UIntBounds &bounds)
 
void publishOcc ()
 
void publishOccUpdate (const nav_core2::UIntBounds &bounds)
 
void publishUpdateArea (const nav_grid::NavGridInfo &info, const nav_core2::UIntBounds &bounds)
 
bool shouldPublishFull () const
 
bool shouldPublishHelper (const ros::Time &last_publish, const ros::Duration &cycle) const
 
bool shouldPublishUpdate () const
 

Protected Attributes

NumericType ignore_value_ { std::numeric_limits<NumericType>::max() }
 
NumericType max_val_
 
NumericType min_val_
 
- Protected Attributes inherited from nav_grid_pub_sub::GenericGridPublisher< NumericType, nav_2d_msgs::NavGridOfDoubles, nav_2d_msgs::NavGridOfDoublesUpdate >
nav_grid::NavGrid< NumericType > & data_
 
ros::Duration full_publish_cycle_
 
ros::Time last_full_publish_
 
ros::Time last_update_publish_
 
ros::Publisher nav_pub_
 
ros::Publisher nav_update_pub_
 
ros::Publisher occ_pub_
 
ros::Publisher occ_update_pub_
 
bool publish_updates_
 
nav_grid::NavGridInfo saved_info_
 
ros::Time synced_time_stamp_
 
ros::Publisher update_area_pub_
 
nav_core2::UIntBounds update_bounds_
 
ros::Duration update_publish_cycle_
 

Detailed Description

template<typename NumericType>
class nav_grid_pub_sub::ScaleGridPublisher< NumericType >

An interface for publishing NavGridOfDoubles/OccupancyGrid msgs and their updates periodically.

Definition at line 364 of file nav_grid_publisher.h.

Member Function Documentation

template<typename NumericType >
void nav_grid_pub_sub::ScaleGridPublisher< NumericType >::setIgnoreValue ( NumericType  ignore_value)
inline

Definition at line 371 of file nav_grid_publisher.h.

template<typename NumericType >
nav_msgs::OccupancyGrid nav_grid_pub_sub::ScaleGridPublisher< NumericType >::toOccupancyGrid ( const ros::Time timestamp)
inlineoverrideprotectedvirtual
template<typename NumericType >
map_msgs::OccupancyGridUpdate nav_grid_pub_sub::ScaleGridPublisher< NumericType >::toOccupancyGridUpdate ( const nav_core2::UIntBounds bounds,
const ros::Time timestamp 
)
inlineoverrideprotectedvirtual

Member Data Documentation

template<typename NumericType >
NumericType nav_grid_pub_sub::ScaleGridPublisher< NumericType >::ignore_value_ { std::numeric_limits<NumericType>::max() }
protected

Definition at line 386 of file nav_grid_publisher.h.

template<typename NumericType >
NumericType nav_grid_pub_sub::ScaleGridPublisher< NumericType >::max_val_
protected

Definition at line 387 of file nav_grid_publisher.h.

template<typename NumericType >
NumericType nav_grid_pub_sub::ScaleGridPublisher< NumericType >::min_val_
protected

Definition at line 387 of file nav_grid_publisher.h.


The documentation for this class was generated from the following file:


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