torus_finder.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_TORUS_FINDER_H_
38 #define JSK_PCL_ROS_TORUS_FINDER_H_
39 
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
41 #include <sensor_msgs/PointCloud2.h>
42 #include <jsk_recognition_msgs/TorusArray.h>
43 #include <jsk_recognition_msgs/Torus.h>
44 #include <jsk_pcl_ros/TorusFinderConfig.h>
45 #include <dynamic_reconfigure/server.h>
46 #include <geometry_msgs/PoseStamped.h>
47 #include <Eigen/Core>
48 #include <geometry_msgs/PolygonStamped.h>
50 
51 namespace jsk_pcl_ros
52 {
53  class TorusFinder: public jsk_topic_tools::DiagnosticNodelet
54  {
55  public:
56  typedef TorusFinderConfig Config;
57  TorusFinder(): timer_(10), done_initialization_(false), DiagnosticNodelet("TorusFinder") {}
58  protected:
59  virtual void onInit();
60  virtual void subscribe();
61  virtual void unsubscribe();
62  virtual void segment(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
63  virtual void segmentFromPoints(const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg);
64  virtual void configCallback(Config &config, uint32_t level);
65 
67  // ROS variables
83  Eigen::Vector3f hint_axis_;
84 
86  // Parameters
88  std::string algorithm_;
89  double min_radius_;
90  double max_radius_;
91  double outlier_threshold_;
92  double eps_hint_angle_;
93  bool use_hint_;
94  bool use_normal_;
95  int max_iterations_;
96  int min_size_;
98  double voxel_size_;
100  private:
101  };
102 }
103 
104 #endif
jsk_pcl_ros::TorusFinder::done_initialization_
bool done_initialization_
Definition: torus_finder.h:163
jsk_pcl_ros::TorusFinder::eps_hint_angle_
double eps_hint_angle_
Definition: torus_finder.h:156
jsk_pcl_ros::TorusFinder::max_iterations_
int max_iterations_
Definition: torus_finder.h:159
ros::Publisher
jsk_pcl_ros::TorusFinder::max_radius_
double max_radius_
Definition: torus_finder.h:154
boost::shared_ptr
jsk_pcl_ros::TorusFinder::pub_coefficients_
ros::Publisher pub_coefficients_
Definition: torus_finder.h:141
jsk_pcl_ros::TorusFinder::pub_torus_array_
ros::Publisher pub_torus_array_
Definition: torus_finder.h:137
jsk_pcl_ros::TorusFinder::use_normal_
bool use_normal_
Definition: torus_finder.h:158
jsk_pcl_ros::TorusFinder::pub_inliers_
ros::Publisher pub_inliers_
Definition: torus_finder.h:140
jsk_pcl_ros::TorusFinder::pub_torus_array_with_failure_
ros::Publisher pub_torus_array_with_failure_
Definition: torus_finder.h:139
jsk_recognition_utils::WallDurationTimer
jsk_pcl_ros::TorusFinder::segment
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
Definition: torus_finder_nodelet.cpp:140
jsk_pcl_ros::TorusFinder::sub_points_
ros::Subscriber sub_points_
Definition: torus_finder.h:135
jsk_pcl_ros::TorusFinder::voxel_grid_sampling_
bool voxel_grid_sampling_
Definition: torus_finder.h:161
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::TorusFinder::sub_
ros::Subscriber sub_
Definition: torus_finder.h:134
jsk_pcl_ros::TorusFinder::subscribe
virtual void subscribe()
Definition: torus_finder_nodelet.cpp:104
jsk_pcl_ros::TorusFinder::hint_axis_
Eigen::Vector3f hint_axis_
Definition: torus_finder.h:147
jsk_pcl_ros::TorusFinder::pub_pose_stamped_
ros::Publisher pub_pose_stamped_
Definition: torus_finder.h:142
jsk_pcl_ros::TorusFinder::mutex_
boost::mutex mutex_
Definition: torus_finder.h:146
jsk_pcl_ros::TorusFinder::TorusFinder
TorusFinder()
Definition: torus_finder.h:121
jsk_pcl_ros::TorusFinder::timer_
jsk_recognition_utils::WallDurationTimer timer_
Definition: torus_finder.h:145
jsk_pcl_ros::TorusFinder::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: torus_finder.h:133
jsk_pcl_ros::TorusFinder::use_hint_
bool use_hint_
Definition: torus_finder.h:157
jsk_pcl_ros::TorusFinder::onInit
virtual void onInit()
Definition: torus_finder_nodelet.cpp:46
jsk_pcl_ros::TorusFinder::algorithm_
std::string algorithm_
Definition: torus_finder.h:152
jsk_pcl_ros::TorusFinder::outlier_threshold_
double outlier_threshold_
Definition: torus_finder.h:155
jsk_pcl_ros::TorusFinder::pub_latest_time_
ros::Publisher pub_latest_time_
Definition: torus_finder.h:143
jsk_pcl_ros::TorusFinder::min_radius_
double min_radius_
Definition: torus_finder.h:153
jsk_pcl_ros::TorusFinder::Config
TorusFinderConfig Config
Definition: torus_finder.h:120
jsk_pcl_ros::TorusFinder::pub_average_time_
ros::Publisher pub_average_time_
Definition: torus_finder.h:144
jsk_pcl_ros::TorusFinder::min_size_
int min_size_
Definition: torus_finder.h:160
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::TorusFinder::unsubscribe
virtual void unsubscribe()
Definition: torus_finder_nodelet.cpp:110
jsk_pcl_ros::TorusFinder::voxel_size_
double voxel_size_
Definition: torus_finder.h:162
jsk_pcl_ros::TorusFinder::segmentFromPoints
virtual void segmentFromPoints(const geometry_msgs::PolygonStamped::ConstPtr &polygon_msg)
Definition: torus_finder_nodelet.cpp:116
time_util.h
jsk_pcl_ros::TorusFinder::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: torus_finder_nodelet.cpp:90
jsk_pcl_ros::TorusFinder::pub_torus_with_failure_
ros::Publisher pub_torus_with_failure_
Definition: torus_finder.h:138
ros::Subscriber
jsk_pcl_ros::TorusFinder::pub_torus_
ros::Publisher pub_torus_
Definition: torus_finder.h:136


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