find_object_on_plane.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, 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/or 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 
37 #ifndef JSK_PCL_ROS_FIND_OBJECT_ON_PLANE_H_
38 #define JSK_PCL_ROS_FIND_OBJECT_ON_PLANE_H_
39 
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
45 #include <sensor_msgs/Image.h>
46 #include <sensor_msgs/CameraInfo.h>
47 #include <pcl_msgs/ModelCoefficients.h>
51 
52 namespace jsk_pcl_ros
53 {
54  class FindObjectOnPlane: public jsk_topic_tools::DiagnosticNodelet
55  {
56  public:
58  sensor_msgs::Image,
59  sensor_msgs::CameraInfo,
60  pcl_msgs::ModelCoefficients > SyncPolicy;
61 
62  FindObjectOnPlane(): DiagnosticNodelet("FindObjectOnPlane") {}
63  virtual ~FindObjectOnPlane();
64  protected:
65  virtual void onInit();
66  virtual void subscribe();
67  virtual void unsubscribe();
68  virtual void find(
69  const sensor_msgs::Image::ConstPtr& image_msg,
70  const sensor_msgs::CameraInfo::ConstPtr& info_msg,
71  const pcl_msgs::ModelCoefficients::ConstPtr& polygon_3d_coefficient_msg);
72  virtual void generateStartPoints(
73  const cv::Point2f& point_2d,
75  const pcl::ModelCoefficients::Ptr& coefficients,
76  std::vector<cv::Point3f>& search_points_3d,
77  std::vector<cv::Point2f>& search_points_2d);
78  virtual void generateAngles(
79  const cv::Mat& blob_image, const cv::Point2f& test_point,
80  std::vector<double>& angles,
81  std::vector<double>& max_x,
82  std::vector<double>& max_y,
85  virtual double drawAngle(
86  cv::Mat& out_image, const cv::Point2f& test_point, const double angle,
87  const double max_x, const double max_y,
90  cv::Scalar color);
91  Eigen::Vector3f rayPlaneInteersect(
92  const cv::Point3d& ray,
94 
95  virtual cv::Point2d getUyEnd(
96  const cv::Point2d& ux_start,
97  const cv::Point2d& ux_end,
100 
106 
107  private:
108 
109  };
110 }
111 
112 #endif
jsk_pcl_ros::FindObjectOnPlane::unsubscribe
virtual void unsubscribe()
Definition: find_object_on_plane_nodelet.cpp:73
ros::Publisher
angles
boost::shared_ptr
pinhole_camera_model.h
geo_util.h
jsk_pcl_ros::FindObjectOnPlane::~FindObjectOnPlane
virtual ~FindObjectOnPlane()
Definition: find_object_on_plane_nodelet.cpp:51
jsk_pcl_ros::FindObjectOnPlane::sub_image_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
Definition: find_object_on_plane.h:166
jsk_pcl_ros::FindObjectOnPlane::onInit
virtual void onInit()
Definition: find_object_on_plane_nodelet.cpp:43
jsk_pcl_ros::FindObjectOnPlane::generateStartPoints
virtual void generateStartPoints(const cv::Point2f &point_2d, const image_geometry::PinholeCameraModel &model, const pcl::ModelCoefficients::Ptr &coefficients, std::vector< cv::Point3f > &search_points_3d, std::vector< cv::Point2f > &search_points_2d)
Definition: find_object_on_plane_nodelet.cpp:274
jsk_pcl_ros::FindObjectOnPlane::find
virtual void find(const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::CameraInfo::ConstPtr &info_msg, const pcl_msgs::ModelCoefficients::ConstPtr &polygon_3d_coefficient_msg)
Definition: find_object_on_plane_nodelet.cpp:79
message_filters::Subscriber< sensor_msgs::Image >
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::FindObjectOnPlane::SyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo, pcl_msgs::ModelCoefficients > SyncPolicy
Definition: find_object_on_plane.h:124
jsk_pcl_ros::FindObjectOnPlane::drawAngle
virtual double drawAngle(cv::Mat &out_image, const cv::Point2f &test_point, const double angle, const double max_x, const double max_y, const image_geometry::PinholeCameraModel &model, const jsk_recognition_utils::Plane::Ptr &plane, cv::Scalar color)
Definition: find_object_on_plane_nodelet.cpp:249
jsk_pcl_ros::FindObjectOnPlane::sub_info_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
Definition: find_object_on_plane.h:167
subscriber.h
jsk_pcl_ros::FindObjectOnPlane::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: find_object_on_plane.h:165
exact_time.h
depth_error_calibration.model
model
Definition: depth_error_calibration.py:37
jsk_pcl_ros::FindObjectOnPlane::rayPlaneInteersect
Eigen::Vector3f rayPlaneInteersect(const cv::Point3d &ray, const jsk_recognition_utils::Plane::Ptr &plane)
Definition: find_object_on_plane_nodelet.cpp:219
jsk_pcl_ros::FindObjectOnPlane::FindObjectOnPlane
FindObjectOnPlane()
Definition: find_object_on_plane.h:126
image_geometry::PinholeCameraModel
jsk_pcl_ros::FindObjectOnPlane::subscribe
virtual void subscribe()
Definition: find_object_on_plane_nodelet.cpp:62
jsk_pcl_ros::FindObjectOnPlane::generateAngles
virtual void generateAngles(const cv::Mat &blob_image, const cv::Point2f &test_point, std::vector< double > &angles, std::vector< double > &max_x, std::vector< double > &max_y, const image_geometry::PinholeCameraModel &model, const jsk_recognition_utils::Plane::Ptr &plane)
Definition: find_object_on_plane_nodelet.cpp:162
synchronizer.h
approximate_time.h
jsk_pcl_ros::FindObjectOnPlane::pub_min_area_rect_image_
ros::Publisher pub_min_area_rect_image_
Definition: find_object_on_plane.h:169
jsk_pcl_ros::FindObjectOnPlane::sub_coefficients_
message_filters::Subscriber< pcl_msgs::ModelCoefficients > sub_coefficients_
Definition: find_object_on_plane.h:168
jsk_pcl_ros::FindObjectOnPlane::getUyEnd
virtual cv::Point2d getUyEnd(const cv::Point2d &ux_start, const cv::Point2d &ux_end, const image_geometry::PinholeCameraModel &model, const jsk_recognition_utils::Plane::Ptr &plane)
Definition: find_object_on_plane_nodelet.cpp:229
pcl_conversions.h


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44