Private Types | |
typedef jsk_pcl_ros::ResizePointsPublisherConfig | Config |
typedef message_filters::sync_policies::ExactTime < sensor_msgs::PointCloud2, PCLIndicesMsg > | SyncPolicy |
Private Member Functions | |
void | configCallback (Config &config, uint32_t level) |
template<class T > | |
void | filter (const sensor_msgs::PointCloud2::ConstPtr &input) |
template<class T > | |
void | filter (const sensor_msgs::PointCloud2::ConstPtr &input, const PCLIndicesMsg::ConstPtr &indices) |
void | onInit () |
void | resizedmaskCallback (const sensor_msgs::Image::ConstPtr &msg) |
void | subscribe () |
void | unsubscribe () |
~ResizePointsPublisher () | |
Private Attributes | |
boost::mutex | mutex_ |
bool | not_use_rgb_ |
ros::Publisher | pub_ |
ros::Subscriber | resizedmask_sub_ |
boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ |
int | step_x_ |
int | step_y_ |
ros::Subscriber | sub_ |
message_filters::Subscriber < PCLIndicesMsg > | sub_indices_ |
message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_input_ |
boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ |
bool | use_indices_ |
Definition at line 27 of file resize_points_publisher_nodelet.cpp.
typedef jsk_pcl_ros::ResizePointsPublisherConfig jsk_pcl_ros::ResizePointsPublisher::Config [private] |
Definition at line 31 of file resize_points_publisher_nodelet.cpp.
typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, PCLIndicesMsg> jsk_pcl_ros::ResizePointsPublisher::SyncPolicy [private] |
Definition at line 30 of file resize_points_publisher_nodelet.cpp.
jsk_pcl_ros::ResizePointsPublisher::~ResizePointsPublisher | ( | ) | [inline, private] |
Definition at line 129 of file resize_points_publisher_nodelet.cpp.
void jsk_pcl_ros::ResizePointsPublisher::configCallback | ( | Config & | config, |
uint32_t | level | ||
) | [inline, private] |
Definition at line 59 of file resize_points_publisher_nodelet.cpp.
void jsk_pcl_ros::ResizePointsPublisher::filter | ( | const sensor_msgs::PointCloud2::ConstPtr & | input | ) | [inline, private] |
Definition at line 131 of file resize_points_publisher_nodelet.cpp.
void jsk_pcl_ros::ResizePointsPublisher::filter | ( | const sensor_msgs::PointCloud2::ConstPtr & | input, |
const PCLIndicesMsg::ConstPtr & | indices | ||
) | [inline, private] |
Definition at line 135 of file resize_points_publisher_nodelet.cpp.
void jsk_pcl_ros::ResizePointsPublisher::onInit | ( | void | ) | [inline, private] |
Definition at line 45 of file resize_points_publisher_nodelet.cpp.
void jsk_pcl_ros::ResizePointsPublisher::resizedmaskCallback | ( | const sensor_msgs::Image::ConstPtr & | msg | ) | [inline, private] |
Definition at line 65 of file resize_points_publisher_nodelet.cpp.
void jsk_pcl_ros::ResizePointsPublisher::subscribe | ( | ) | [inline, private] |
Definition at line 89 of file resize_points_publisher_nodelet.cpp.
void jsk_pcl_ros::ResizePointsPublisher::unsubscribe | ( | ) | [inline, private] |
Definition at line 118 of file resize_points_publisher_nodelet.cpp.
Definition at line 43 of file resize_points_publisher_nodelet.cpp.
bool jsk_pcl_ros::ResizePointsPublisher::not_use_rgb_ [private] |
Definition at line 42 of file resize_points_publisher_nodelet.cpp.
Definition at line 41 of file resize_points_publisher_nodelet.cpp.
Definition at line 39 of file resize_points_publisher_nodelet.cpp.
boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::ResizePointsPublisher::srv_ [private] |
Definition at line 37 of file resize_points_publisher_nodelet.cpp.
int jsk_pcl_ros::ResizePointsPublisher::step_x_ [private] |
Definition at line 34 of file resize_points_publisher_nodelet.cpp.
int jsk_pcl_ros::ResizePointsPublisher::step_y_ [private] |
Definition at line 34 of file resize_points_publisher_nodelet.cpp.
Definition at line 38 of file resize_points_publisher_nodelet.cpp.
message_filters::Subscriber<PCLIndicesMsg> jsk_pcl_ros::ResizePointsPublisher::sub_indices_ [private] |
Definition at line 36 of file resize_points_publisher_nodelet.cpp.
message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::ResizePointsPublisher::sub_input_ [private] |
Definition at line 35 of file resize_points_publisher_nodelet.cpp.
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::ResizePointsPublisher::sync_ [private] |
Definition at line 40 of file resize_points_publisher_nodelet.cpp.
bool jsk_pcl_ros::ResizePointsPublisher::use_indices_ [private] |
Definition at line 44 of file resize_points_publisher_nodelet.cpp.