heightmap_to_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/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_HEIGHTMAP_TO_POINTCLOUD_H_
38 #define JSK_PCL_ROS_HEIGHTMAP_TO_POINTCLOUD_H_
39 
40 
41 #include <jsk_topic_tools/diagnostic_nodelet.h>
42 #include <dynamic_reconfigure/server.h>
43 #include <sensor_msgs/PointCloud2.h>
44 #include <sensor_msgs/Image.h>
46 
47 namespace jsk_pcl_ros
48 {
49  class HeightmapToPointCloud: public jsk_topic_tools::DiagnosticNodelet
50  {
51  public:
53  HeightmapToPointCloud(): DiagnosticNodelet("HeightmapToPointCloud") {}
54 
55  protected:
56  virtual void onInit();
57  virtual void subscribe();
58  virtual void unsubscribe();
59  virtual void convert(const sensor_msgs::Image::ConstPtr& msg);
60  virtual void configCallback(
61  const jsk_recognition_msgs::HeightmapConfig::ConstPtr& msg);
62  jsk_recognition_msgs::HeightmapConfig::ConstPtr config_msg_;
68  double min_x_;
69  double max_x_;
70  double min_y_;
71  double max_y_;
72  };
73 }
74 
75 
76 #endif
jsk_pcl_ros::HeightmapToPointCloud::max_y_
double max_y_
Definition: heightmap_to_pointcloud.h:135
jsk_pcl_ros::HeightmapToPointCloud::min_y_
double min_y_
Definition: heightmap_to_pointcloud.h:134
ros::Publisher
boost::shared_ptr
jsk_pcl_ros::HeightmapToPointCloud::mutex_
boost::mutex mutex_
Definition: heightmap_to_pointcloud.h:127
jsk_pcl_ros::HeightmapToPointCloud::sub_
ros::Subscriber sub_
Definition: heightmap_to_pointcloud.h:130
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::HeightmapToPointCloud::config_msg_
jsk_recognition_msgs::HeightmapConfig::ConstPtr config_msg_
Definition: heightmap_to_pointcloud.h:126
jsk_pcl_ros::HeightmapToPointCloud::onInit
virtual void onInit()
Definition: heightmap_to_pointcloud_nodelet.cpp:47
jsk_pcl_ros::HeightmapToPointCloud::pub_config_
ros::Publisher pub_config_
Definition: heightmap_to_pointcloud.h:129
jsk_pcl_ros::HeightmapToPointCloud::min_x_
double min_x_
Definition: heightmap_to_pointcloud.h:132
jsk_pcl_ros::HeightmapToPointCloud::convert
virtual void convert(const sensor_msgs::Image::ConstPtr &msg)
Definition: heightmap_to_pointcloud_nodelet.cpp:81
jsk_pcl_ros::HeightmapToPointCloud::subscribe
virtual void subscribe()
Definition: heightmap_to_pointcloud_nodelet.cpp:59
heightmap_utils.h
jsk_pcl_ros::HeightmapToPointCloud::configCallback
virtual void configCallback(const jsk_recognition_msgs::HeightmapConfig::ConstPtr &msg)
Definition: heightmap_to_pointcloud_nodelet.cpp:69
jsk_pcl_ros::HeightmapToPointCloud::Ptr
boost::shared_ptr< HeightmapToPointCloud > Ptr
Definition: heightmap_to_pointcloud.h:116
jsk_pcl_ros::HeightmapToPointCloud::HeightmapToPointCloud
HeightmapToPointCloud()
Definition: heightmap_to_pointcloud.h:117
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::HeightmapToPointCloud::sub_config_
ros::Subscriber sub_config_
Definition: heightmap_to_pointcloud.h:131
jsk_pcl_ros::HeightmapToPointCloud::unsubscribe
virtual void unsubscribe()
Definition: heightmap_to_pointcloud_nodelet.cpp:64
jsk_pcl_ros::HeightmapToPointCloud::pub_
ros::Publisher pub_
Definition: heightmap_to_pointcloud.h:128
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
jsk_pcl_ros::HeightmapToPointCloud::max_x_
double max_x_
Definition: heightmap_to_pointcloud.h:133
ros::Subscriber


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