moment_invariants.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id: moment_invariants.h 35361 2011-01-20 04:34:49Z rusu $
35  *
36  */
37 
38 #ifndef PCL_ROS_MOMENT_INVARIANTS_H_
39 #define PCL_ROS_MOMENT_INVARIANTS_H_
40 
41 #include <pcl/features/moment_invariants.h>
43 
44 namespace pcl_ros
45 {
53  {
54  private:
55  pcl::MomentInvariantsEstimation<pcl::PointXYZ, pcl::MomentInvariants> impl_;
56 
57  typedef pcl::PointCloud<pcl::MomentInvariants> PointCloudOut;
58 
60  inline bool
62  {
63  // Create the output publisher
64  pub_output_ = advertise<PointCloudOut> (nh, "output", max_queue_size_);
65  return (true);
66  }
67 
69  void emptyPublish (const PointCloudInConstPtr &cloud);
70 
72  void computePublish (const PointCloudInConstPtr &cloud,
73  const PointCloudInConstPtr &surface,
74  const IndicesPtr &indices);
75 
76  public:
77  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
78  };
79 }
80 
81 #endif //#ifndef PCL_ROS_MOMENT_INVARIANTS_H_
82 
83 
pcl_ros
Definition: boundary.h:46
pcl_ros::MomentInvariantsEstimation
MomentInvariantsEstimation estimates the 3 moment invariants (j1, j2, j3) at each 3D point.
Definition: moment_invariants.h:52
pcl_ros::MomentInvariantsEstimation::PointCloudOut
pcl::PointCloud< pcl::MomentInvariants > PointCloudOut
Definition: moment_invariants.h:57
pcl_ros::Feature::IndicesPtr
pcl::IndicesPtr IndicesPtr
Definition: feature.h:75
pcl_ros::Feature
Feature represents the base feature class. Some generic 3D operations that are applicable to all feat...
Definition: feature.h:65
pcl_ros::MomentInvariantsEstimation::childInit
bool childInit(ros::NodeHandle &nh)
Child initialization routine. Internal method.
Definition: moment_invariants.h:61
feature.h
pcl_ros::PCLNodelet::max_queue_size_
int max_queue_size_
The maximum queue size (default: 3).
Definition: pcl_nodelet.h:128
pcl_ros::PCLNodelet::pub_output_
ros::Publisher pub_output_
The output PointCloud publisher.
Definition: pcl_nodelet.h:125
pcl_ros::MomentInvariantsEstimation::emptyPublish
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type.
Definition: moment_invariants.cpp:42
pcl_ros::MomentInvariantsEstimation::impl_
pcl::MomentInvariantsEstimation< pcl::PointXYZ, pcl::MomentInvariants > impl_
Definition: moment_invariants.h:55
pcl_ros::MomentInvariantsEstimation::computePublish
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.
Definition: moment_invariants.cpp:50
pcl_ros::Feature::PointCloudInConstPtr
boost::shared_ptr< const PointCloudIn > PointCloudInConstPtr
Definition: feature.h:73
ros::NodeHandle


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Fri Jul 12 2024 02:54:40