include
jsk_pcl_ros
normal_estimation_omp.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_NORMAL_ESTIMATION_OMP_H_
38
#define JSK_PCL_ROS_NORMAL_ESTIMATION_OMP_H_
39
40
#include <jsk_topic_tools/diagnostic_nodelet.h>
41
#include <sensor_msgs/PointCloud2.h>
42
#include <pcl_ros/FeatureConfig.h>
43
#include <dynamic_reconfigure/server.h>
44
#include <
pcl_conversions/pcl_conversions.h
>
45
#include <
jsk_recognition_utils/time_util.h
>
46
#include <std_msgs/Float32.h>
47
48
namespace
jsk_pcl_ros
49
{
50
class
NormalEstimationOMP
:
public
jsk_topic_tools::DiagnosticNodelet
51
{
52
public
:
53
typedef
boost::shared_ptr<NormalEstimationOMP>
Ptr
;
54
typedef
pcl_ros::FeatureConfig
Config
;
55
NormalEstimationOMP
(): DiagnosticNodelet(
"NormalEstimationOMP"
),
timer_
(10) {}
56
57
protected
:
58
59
virtual
void
onInit
();
60
virtual
void
subscribe
();
61
virtual
void
unsubscribe
();
62
virtual
void
estimate
(
63
const
sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
64
virtual
void
configCallback
(
65
Config
& config, uint32_t level);
66
67
boost::mutex
mutex_
;
68
ros::Publisher
pub_
;
69
ros::Publisher
pub_with_xyz_
;
70
ros::Publisher
pub_latest_time_
;
71
ros::Publisher
pub_average_time_
;
72
jsk_recognition_utils::WallDurationTimer
timer_
;
73
ros::Subscriber
sub_
;
74
std::string
sensor_frame_
;
75
boost::shared_ptr <dynamic_reconfigure::Server<Config>
>
srv_
;
76
int
k_
;
77
double
search_radius_
;
78
int
num_of_threads_
;
79
80
private
:
81
82
};
83
}
84
85
#endif
jsk_pcl_ros::NormalEstimationOMP::Ptr
boost::shared_ptr< NormalEstimationOMP > Ptr
Definition:
normal_estimation_omp.h:117
jsk_pcl_ros::NormalEstimationOMP::unsubscribe
virtual void unsubscribe()
Definition:
normal_estimation_omp_nodelet.cpp:67
ros::Publisher
jsk_pcl_ros::NormalEstimationOMP::k_
int k_
Definition:
normal_estimation_omp.h:140
boost::shared_ptr
jsk_pcl_ros::NormalEstimationOMP::pub_with_xyz_
ros::Publisher pub_with_xyz_
Definition:
normal_estimation_omp.h:133
jsk_pcl_ros::NormalEstimationOMP::search_radius_
double search_radius_
Definition:
normal_estimation_omp.h:141
jsk_pcl_ros::NormalEstimationOMP::subscribe
virtual void subscribe()
Definition:
normal_estimation_omp_nodelet.cpp:62
jsk_recognition_utils::WallDurationTimer
jsk_pcl_ros::NormalEstimationOMP::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition:
normal_estimation_omp.h:139
jsk_pcl_ros
Definition:
add_color_from_image.h:51
jsk_pcl_ros::NormalEstimationOMP::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition:
normal_estimation_omp_nodelet.cpp:72
jsk_pcl_ros::NormalEstimationOMP::sensor_frame_
std::string sensor_frame_
Definition:
normal_estimation_omp.h:138
jsk_pcl_ros::NormalEstimationOMP::pub_
ros::Publisher pub_
Definition:
normal_estimation_omp.h:132
jsk_pcl_ros::NormalEstimationOMP::sub_
ros::Subscriber sub_
Definition:
normal_estimation_omp.h:137
jsk_pcl_ros::NormalEstimationOMP::pub_average_time_
ros::Publisher pub_average_time_
Definition:
normal_estimation_omp.h:135
jsk_pcl_ros::NormalEstimationOMP::pub_latest_time_
ros::Publisher pub_latest_time_
Definition:
normal_estimation_omp.h:134
jsk_pcl_ros::NormalEstimationOMP::mutex_
boost::mutex mutex_
Definition:
normal_estimation_omp.h:131
mutex
boost::mutex mutex
global mutex.
Definition:
depth_camera_error_visualization.cpp:86
time_util.h
jsk_pcl_ros::NormalEstimationOMP::num_of_threads_
int num_of_threads_
Definition:
normal_estimation_omp.h:142
jsk_pcl_ros::NormalEstimationOMP::Config
pcl_ros::FeatureConfig Config
Definition:
normal_estimation_omp.h:118
jsk_pcl_ros::NormalEstimationOMP::onInit
virtual void onInit()
Definition:
normal_estimation_omp_nodelet.cpp:43
pcl_ros::NormalEstimationOMP
jsk_pcl_ros::NormalEstimationOMP::NormalEstimationOMP
NormalEstimationOMP()
Definition:
normal_estimation_omp.h:119
jsk_pcl_ros::NormalEstimationOMP::timer_
jsk_recognition_utils::WallDurationTimer timer_
Definition:
normal_estimation_omp.h:136
jsk_pcl_ros::NormalEstimationOMP::estimate
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
Definition:
normal_estimation_omp_nodelet.cpp:80
ros::Subscriber
pcl_conversions.h
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45