capture_stereo_synchronizer.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #ifndef JSK_PCL_ROS_CAPTURE_STEREO_SYNCHRONIZER_H_
37 #define JSK_PCL_ROS_CAPTURE_STEREO_SYNCHRONIZER_H_
38 
39 
40 
41 
42 #include <ros/ros.h>
47 
48 #include <sensor_msgs/Image.h>
49 #include <sensor_msgs/CameraInfo.h>
50 #include <stereo_msgs/DisparityImage.h>
51 #include <geometry_msgs/PoseStamped.h>
52 #include <pcl_msgs/PointIndices.h>
54 
55 namespace jsk_pcl_ros
56 {
58  {
59  public:
62  geometry_msgs::PoseStamped, // pose of checker board
63  sensor_msgs::Image, // mask image
64  pcl_msgs::PointIndices, // mask indices
65  sensor_msgs::Image, // left image rect
66  sensor_msgs::CameraInfo, // left cmaera info
67  sensor_msgs::CameraInfo, // right camera info
68  stereo_msgs::DisparityImage // stereo disparity
70  CaptureStereoSynchronizer(): DiagnosticNodelet("CaptureStereoSynchronizer") { }
71  protected:
73  // methods
75  virtual void onInit();
76  virtual void subscribe();
77  virtual void unsubscribe();
78  virtual void republish(
79  const geometry_msgs::PoseStamped::ConstPtr& pose, // pose of checker board
80  const sensor_msgs::Image::ConstPtr& mask, // mask image
81  const PCLIndicesMsg::ConstPtr& mask_indices, // mask indices
82  const sensor_msgs::Image::ConstPtr& left_image, // left image rect
83  const sensor_msgs::CameraInfo::ConstPtr& left_cam_info, // left cmaera info
84  const sensor_msgs::CameraInfo::ConstPtr& right_cam_info, // right camera info
85  const stereo_msgs::DisparityImage::ConstPtr& disparity // stereo disparity
86  );
87 
88  // check is there near pose or not
89  // if there is a near pose, return true
90  virtual bool checkNearPose(
91  const geometry_msgs::Pose& new_pose);
92 
94  // ROS variables
96  int counter_;
113  std::vector<geometry_msgs::Pose> poses_;
115  // Parameters
119  private:
120 
121  };
122 }
123 #endif
boost::shared_ptr< CaptureStereoSynchronizer > Ptr
message_filters::sync_policies::ExactTime< geometry_msgs::PoseStamped, sensor_msgs::Image, pcl_msgs::PointIndices, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo, stereo_msgs::DisparityImage > SyncPolicy
std::vector< geometry_msgs::Pose > poses_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_right_cam_info_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
pose
message_filters::Subscriber< PCLIndicesMsg > sub_mask_indices_
DiagnosticNodelet(const std::string &name)
virtual bool checkNearPose(const geometry_msgs::Pose &new_pose)
message_filters::Subscriber< sensor_msgs::Image > sub_mask_
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_pose_
message_filters::Subscriber< sensor_msgs::Image > sub_left_image_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_left_cam_info_
virtual void republish(const geometry_msgs::PoseStamped::ConstPtr &pose, const sensor_msgs::Image::ConstPtr &mask, const PCLIndicesMsg::ConstPtr &mask_indices, const sensor_msgs::Image::ConstPtr &left_image, const sensor_msgs::CameraInfo::ConstPtr &left_cam_info, const sensor_msgs::CameraInfo::ConstPtr &right_cam_info, const stereo_msgs::DisparityImage::ConstPtr &disparity)
message_filters::Subscriber< stereo_msgs::DisparityImage > sub_disparity_


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46