snapit.h
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, 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 #ifndef JSK_PCL_ROS_SNAPIT_H_
37 #define JSK_PCL_ROS_SNAPIT_H_
38 
39 #include <ros/ros.h>
40 
41 #include <pcl/point_types.h>
42 #include <pcl_ros/pcl_nodelet.h>
43 #include <jsk_recognition_msgs/PolygonArray.h>
44 #include <geometry_msgs/PolygonStamped.h>
45 #include <geometry_msgs/PoseArray.h>
46 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
47 #include "jsk_recognition_msgs/CallSnapIt.h"
48 #include <tf/transform_listener.h>
49 #include <jsk_topic_tools/diagnostic_nodelet.h>
54 #include <jsk_recognition_msgs/SnapFootstep.h>
56 namespace jsk_pcl_ros
57 {
58  class SnapIt: public jsk_topic_tools::DiagnosticNodelet
59  {
60  public:
62  jsk_recognition_msgs::PolygonArray,
63  jsk_recognition_msgs::ModelCoefficientsArray> SyncPolygonPolicy;
64  SnapIt(): DiagnosticNodelet("SnapIt") {}
65  virtual ~SnapIt();
66  protected:
68  // methods
70  virtual void onInit();
71  virtual void subscribe();
72  virtual void unsubscribe();
73  virtual void polygonCallback(
74  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
75  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg);
76  virtual void polygonAlignCallback(
77  const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
78  virtual void convexAlignCallback(
79  const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
80  virtual void convexAlignPolygonCallback(
81  const geometry_msgs::PolygonStamped::ConstPtr& poly_msg);
82  virtual std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> createConvexes(
83  const std::string& frame_id, const ros::Time& stamp,
84  jsk_recognition_msgs::PolygonArray::ConstPtr polygons);
85  virtual int findNearestConvex(
86  const Eigen::Vector3f& pose_point,
87  const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);
88  virtual geometry_msgs::PoseStamped alignPose(
89  Eigen::Affine3f& pose, jsk_recognition_utils::ConvexPolygon::Ptr convex);
91  jsk_recognition_msgs::SnapFootstep::Request& req,
92  jsk_recognition_msgs::SnapFootstep::Response& res);
94  // ROS variables
107  bool use_service_;
109  jsk_recognition_msgs::PolygonArray::ConstPtr polygons_;
112  // parameters
114 
115  };
116 }
117 
118 #endif
ros::Publisher
boost::shared_ptr< ConvexPolygon >
attention_pose_set.stamp
stamp
Definition: attention_pose_set.py:15
ros.h
jsk_pcl_ros::SnapIt::onInit
virtual void onInit()
Definition: snapit_nodelet.cpp:91
geo_util.h
jsk_pcl_ros::SnapIt::polygonAlignCallback
virtual void polygonAlignCallback(const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
Definition: snapit_nodelet.cpp:159
jsk_pcl_ros::SnapIt::convexAlignCallback
virtual void convexAlignCallback(const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
Definition: snapit_nodelet.cpp:290
time_synchronizer.h
tf_listener_singleton.h
jsk_pcl_ros::SnapIt::sync_polygon_
boost::shared_ptr< message_filters::Synchronizer< SyncPolygonPolicy > > sync_polygon_
Definition: snapit.h:163
jsk_pcl_ros::SnapIt::convex_aligned_pose_array_marker_pub_
ros::Publisher convex_aligned_pose_array_marker_pub_
Definition: snapit.h:167
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray >
ros::ServiceServer
jsk_pcl_ros::SnapIt::createConvexes
virtual std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > createConvexes(const std::string &frame_id, const ros::Time &stamp, jsk_recognition_msgs::PolygonArray::ConstPtr polygons)
Definition: snapit_nodelet.cpp:347
pcl_nodelet.h
jsk_pcl_ros::SnapIt::subscribe
virtual void subscribe()
Definition: snapit_nodelet.cpp:121
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::SnapIt::convex_aligned_pub_
ros::Publisher convex_aligned_pub_
Definition: snapit.h:165
jsk_pcl_ros::SnapIt::SnapIt
SnapIt()
Definition: snapit.h:128
subscriber.h
jsk_pcl_ros::SnapIt::polygon_aligned_pub_
ros::Publisher polygon_aligned_pub_
Definition: snapit.h:164
jsk_pcl_ros::SnapIt::SyncPolygonPolicy
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolygonPolicy
Definition: snapit.h:127
jsk_pcl_ros::SnapIt::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: snapit.h:162
jsk_pcl_ros::SnapIt::footstepAlignServiceCallback
virtual bool footstepAlignServiceCallback(jsk_recognition_msgs::SnapFootstep::Request &req, jsk_recognition_msgs::SnapFootstep::Response &res)
Definition: snapit_nodelet.cpp:198
transform_listener.h
jsk_pcl_ros::SnapIt::convex_align_sub_
ros::Subscriber convex_align_sub_
Definition: snapit.h:169
jsk_pcl_ros::SnapIt::alignPose
virtual geometry_msgs::PoseStamped alignPose(Eigen::Affine3f &pose, jsk_recognition_utils::ConvexPolygon::Ptr convex)
Definition: snapit_nodelet.cpp:320
ros::Time
jsk_pcl_ros::SnapIt::~SnapIt
virtual ~SnapIt()
Definition: snapit_nodelet.cpp:110
jsk_pcl_ros::SnapIt::polygons_
jsk_recognition_msgs::PolygonArray::ConstPtr polygons_
Definition: snapit.h:173
jsk_pcl_ros::SnapIt::polygonCallback
virtual void polygonCallback(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
Definition: snapit_nodelet.cpp:150
jsk_pcl_ros::SnapIt::convex_aligned_pose_array_pub_
ros::Publisher convex_aligned_pose_array_pub_
Definition: snapit.h:166
tf::TransformListener
synchronizer.h
jsk_pcl_ros::SnapIt::use_service_
bool use_service_
Definition: snapit.h:171
jsk_pcl_ros::SnapIt::unsubscribe
virtual void unsubscribe()
Definition: snapit_nodelet.cpp:139
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
message_filters::sync_policies::ExactTime
attention_pose_set.frame_id
frame_id
Definition: attention_pose_set.py:16
jsk_pcl_ros::SnapIt::align_footstep_srv_
ros::ServiceServer align_footstep_srv_
Definition: snapit.h:172
jsk_pcl_ros::SnapIt::polygon_align_sub_
ros::Subscriber polygon_align_sub_
Definition: snapit.h:168
jsk_pcl_ros::SnapIt::tf_listener_
tf::TransformListener * tf_listener_
Definition: snapit.h:160
jsk_pcl_ros::SnapIt::convexAlignPolygonCallback
virtual void convexAlignPolygonCallback(const geometry_msgs::PolygonStamped::ConstPtr &poly_msg)
Definition: snapit_nodelet.cpp:235
jsk_pcl_ros::SnapIt::findNearestConvex
virtual int findNearestConvex(const Eigen::Vector3f &pose_point, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
Definition: snapit_nodelet.cpp:269
jsk_pcl_ros::SnapIt::sub_polygons_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
Definition: snapit.h:161
sample_pointcloud_localization_client.req
req
Definition: sample_pointcloud_localization_client.py:15
jsk_pcl_ros::SnapIt::convex_align_polygon_sub_
ros::Subscriber convex_align_polygon_sub_
Definition: snapit.h:170
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14
ros::Subscriber
jsk_pcl_ros::SnapIt::mutex_
boost::mutex mutex_
Definition: snapit.h:174


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