Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
jsk_perception::GridLabel Class Reference

#include <grid_label.h>

List of all members.

Public Types

typedef GridLabelConfig Config

Public Member Functions

 GridLabel ()

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
virtual void imageCallback (const sensor_msgs::Image::ConstPtr &image_msg)
virtual void infoCallback (const sensor_msgs::CameraInfo::ConstPtr &info_msg)
virtual void makeLabel (cv::Mat &label, const std_msgs::Header &header)
virtual void onInit ()
virtual void subscribe ()
virtual void unsubscribe ()

Protected Attributes

int label_size_
boost::mutex mutex_
ros::Publisher pub_
boost::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
ros::Subscriber sub_
bool use_camera_info_

Detailed Description

Definition at line 49 of file grid_label.h.


Member Typedef Documentation

typedef GridLabelConfig jsk_perception::GridLabel::Config

Definition at line 52 of file grid_label.h.


Constructor & Destructor Documentation

Definition at line 53 of file grid_label.h.


Member Function Documentation

void jsk_perception::GridLabel::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]

Definition at line 78 of file grid_label.cpp.

void jsk_perception::GridLabel::imageCallback ( const sensor_msgs::Image::ConstPtr &  image_msg) [protected, virtual]

Definition at line 94 of file grid_label.cpp.

void jsk_perception::GridLabel::infoCallback ( const sensor_msgs::CameraInfo::ConstPtr &  info_msg) [protected, virtual]

Definition at line 84 of file grid_label.cpp.

void jsk_perception::GridLabel::makeLabel ( cv::Mat &  label,
const std_msgs::Header header 
) [protected, virtual]

Definition at line 104 of file grid_label.cpp.

void jsk_perception::GridLabel::onInit ( ) [protected, virtual]

Definition at line 45 of file grid_label.cpp.

void jsk_perception::GridLabel::subscribe ( ) [protected, virtual]

Definition at line 59 of file grid_label.cpp.

void jsk_perception::GridLabel::unsubscribe ( ) [protected, virtual]

Definition at line 73 of file grid_label.cpp.


Member Data Documentation

Definition at line 68 of file grid_label.h.

boost::mutex jsk_perception::GridLabel::mutex_ [protected]

Definition at line 66 of file grid_label.h.

Definition at line 70 of file grid_label.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_perception::GridLabel::srv_ [protected]

Definition at line 65 of file grid_label.h.

Definition at line 69 of file grid_label.h.

Definition at line 67 of file grid_label.h.


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


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Tue Jul 2 2019 19:41:08