include
jsk_pcl_ros_utils
polygon_array_angle_likelihood.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
#ifndef JSK_PCL_ROS_UTILS_POLYGON_ARRAY_ANGLE_LIKELIHOOD_H_
37
#define JSK_PCL_ROS_UTILS_POLYGON_ARRAY_ANGLE_LIKELIHOOD_H_
38
39
#include <jsk_recognition_msgs/PolygonArray.h>
40
#include <jsk_topic_tools/diagnostic_nodelet.h>
41
42
#include <
tf/message_filter.h
>
43
#include <
message_filters/subscriber.h
>
44
#include <Eigen/Geometry>
45
46
namespace
jsk_pcl_ros_utils
47
{
48
class
PolygonArrayAngleLikelihood:
public
jsk_topic_tools::DiagnosticNodelet
49
{
50
public
:
51
typedef
boost::shared_ptr<PolygonArrayAngleLikelihood>
Ptr
;
52
PolygonArrayAngleLikelihood
(): DiagnosticNodelet(
"PolygonArrayAngleLikelihood"
) {}
53
54
protected
:
55
virtual
void
onInit
();
56
virtual
void
subscribe
();
57
virtual
void
unsubscribe
();
58
virtual
void
likelihood
(
const
jsk_recognition_msgs::PolygonArray::ConstPtr& msg);
59
60
message_filters::Subscriber<jsk_recognition_msgs::PolygonArray>
sub_
;
61
ros::Publisher
pub_
;
62
boost::shared_ptr<tf::MessageFilter<jsk_recognition_msgs::PolygonArray>
>
tf_filter_
;
63
tf::TransformListener
*
tf_listener_
;
64
std::string
target_frame_id_
;
65
int
tf_queue_size_
;
66
boost::mutex
mutex_
;
67
Eigen::Vector3f
axis_
;
68
private
:
69
70
};
71
}
72
73
#endif
jsk_pcl_ros_utils
Definition:
add_point_indices.h:51
ros::Publisher
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::pub_
ros::Publisher pub_
Definition:
polygon_array_angle_likelihood.h:125
boost::shared_ptr
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::PolygonArrayAngleLikelihood
PolygonArrayAngleLikelihood()
Definition:
polygon_array_angle_likelihood.h:116
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::unsubscribe
virtual void unsubscribe()
Definition:
polygon_array_angle_likelihood_nodelet.cpp:80
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::mutex_
boost::mutex mutex_
Definition:
polygon_array_angle_likelihood.h:130
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::Ptr
boost::shared_ptr< PolygonArrayAngleLikelihood > Ptr
Definition:
polygon_array_angle_likelihood.h:115
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray >
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::tf_filter_
boost::shared_ptr< tf::MessageFilter< jsk_recognition_msgs::PolygonArray > > tf_filter_
Definition:
polygon_array_angle_likelihood.h:126
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::tf_queue_size_
int tf_queue_size_
Definition:
polygon_array_angle_likelihood.h:129
message_filter.h
subscriber.h
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::target_frame_id_
std::string target_frame_id_
Definition:
polygon_array_angle_likelihood.h:128
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::tf_listener_
tf::TransformListener * tf_listener_
Definition:
polygon_array_angle_likelihood.h:127
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::likelihood
virtual void likelihood(const jsk_recognition_msgs::PolygonArray::ConstPtr &msg)
Definition:
polygon_array_angle_likelihood_nodelet.cpp:85
tf::TransformListener
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::axis_
Eigen::Vector3f axis_
Definition:
polygon_array_angle_likelihood.h:131
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::subscribe
virtual void subscribe()
Definition:
polygon_array_angle_likelihood_nodelet.cpp:68
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::onInit
virtual void onInit()
Definition:
polygon_array_angle_likelihood_nodelet.cpp:46
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::sub_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_
Definition:
polygon_array_angle_likelihood.h:124
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43