pose_with_covariance_stamped_to_gaussian_pointcloud.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, 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/o2r 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_UTILS_POSE_WITH_COVARIANCE_STAMPED_TO_GAUSSIAN_POINTCLOUD_H_
38 #define JSK_PCL_ROS_UTILS_POSE_WITH_COVARIANCE_STAMPED_TO_GAUSSIAN_POINTCLOUD_H_
39 
41 #include <geometry_msgs/PoseWithCovarianceStamped.h>
42 #include <jsk_pcl_ros_utils/PoseWithCovarianceStampedToGaussianPointCloudConfig.h>
43 #include <Eigen/Geometry>
44 #include <dynamic_reconfigure/server.h>
45 namespace jsk_pcl_ros_utils
46 {
48  {
49  public:
50  typedef PoseWithCovarianceStampedToGaussianPointCloudConfig Config;
52  DiagnosticNodelet("PoseWithCovarianceStampedToGaussianPointCloud") {}
53  protected:
54  virtual void onInit();
55  virtual void subscribe();
56  virtual void unsubscribe();
57  virtual void convert(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg);
58  virtual void configCallback(Config& config, uint32_t level);
59  virtual float gaussian(const Eigen::Vector2f& input,
60  const Eigen::Vector2f& mean,
61  const Eigen::Matrix2f& S,
62  const Eigen::Matrix2f& S_inv);
63  boost::mutex mutex_;
66  std::string cut_plane_;
67  double threshold_;
68  std::string normalize_method_;
72  };
73 }
74 
75 #endif
msg
virtual float gaussian(const Eigen::Vector2f &input, const Eigen::Vector2f &mean, const Eigen::Matrix2f &S, const Eigen::Matrix2f &S_inv)
config
virtual void convert(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
DiagnosticNodelet(const std::string &name)


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15