Class InputHandler

Inheritance Relationships

Derived Types

Class Documentation

class InputHandler

Subclassed by wavemap::DepthImageInputHandler, wavemap::PointcloudInputHandler

Public Functions

InputHandler(const InputHandlerConfig &config, const param::Value &params, std::string world_frame, VolumetricDataStructureBase::Ptr occupancy_map, std::shared_ptr<TfTransformer> transformer, std::shared_ptr<ThreadPool> thread_pool, const ros::NodeHandle &nh, ros::NodeHandle nh_private)
virtual ~InputHandler() = default
virtual InputHandlerType getType() const = 0
inline const std::string &getTopicName()
inline bool shouldPublishReprojectedPointcloud() const
inline bool shouldPublishProjectedRangeImage() const

Protected Functions

virtual void processQueue() = 0
void publishReprojectedPointcloud(const ros::Time &stamp, const PosedPointcloud<> &posed_pointcloud)
void publishProjectedRangeImage(const ros::Time &stamp, const Image<> &range_image)

Protected Attributes

const InputHandlerConfig config_
const std::string world_frame_
std::vector<IntegratorBase::Ptr> integrators_
Stopwatch integration_timer_
std::shared_ptr<TfTransformer> transformer_
ros::Timer queue_processing_retry_timer_
ros::Publisher reprojected_pointcloud_pub_
image_transport::Publisher projected_range_image_pub_