heightmap_converter.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_HEIGHTMAP_CONVERTER_H_
37 #define JSK_PCL_ROS_HEIGHTMAP_CONVERTER_H_
38 
39 #include <jsk_topic_tools/diagnostic_nodelet.h>
40 
41 #include <sensor_msgs/PointCloud2.h>
42 #include <jsk_pcl_ros/HeightmapConverterConfig.h>
43 #include <dynamic_reconfigure/server.h>
44 #include <opencv2/opencv.hpp>
45 #include <pcl/point_types.h>
46 #include <pcl/point_cloud.h>
47 #include <jsk_recognition_msgs/HeightmapConfig.h>
48 #include <tf/transform_listener.h>
50 
51 namespace jsk_pcl_ros
52 {
53 
54  class HeightmapConverter: public jsk_topic_tools::DiagnosticNodelet
55  {
56  public:
58  typedef HeightmapConverterConfig Config;
59  HeightmapConverter(): DiagnosticNodelet("HeightmapConverter") {}
60  protected:
61  virtual void onInit();
62  virtual void subscribe();
63  virtual void unsubscribe();
64  virtual void configCallback(Config &config, uint32_t level);
65  virtual void convert(const sensor_msgs::PointCloud2::ConstPtr& msg);
66  inline cv::Point toIndex(const pcl::PointXYZ& p) const
67  {
68  if (p.x > max_x_ || p.x < min_x_ ||
69  p.y > max_y_ || p.y < min_y_) {
70  return cv::Point(-1, -1);
71  }
72  const float offsetted_x = p.x - min_x_;
73  const float offsetted_y = p.y - min_y_;
74  const float dx = (max_x_ - min_x_) / resolution_x_;
75  const float dy = (max_y_ - min_y_) / resolution_y_;
76  return cv::Point(std::floor(offsetted_x / dx),
77  std::floor(offsetted_y / dy));
78  }
79 
86  double min_x_;
87  double max_x_;
88  double min_y_;
89  double max_y_;
90  double min_z_;
91  double max_z_;
92  int resolution_x_;
93  int resolution_y_;
94  int max_queue_size_;
95  std::string fixed_frame_id_;
96  std::string center_frame_id_;
97  std::string projected_center_frame_id_;
99  double initial_probability_;
100 
103  };
104 }
105 
106 #endif
jsk_pcl_ros::HeightmapConverter::center_frame_id_
std::string center_frame_id_
Definition: heightmap_converter.h:160
jsk_pcl_ros::HeightmapConverter::fixed_frame_id_
std::string fixed_frame_id_
Definition: heightmap_converter.h:159
jsk_pcl_ros::HeightmapConverter::pub_
ros::Publisher pub_
Definition: heightmap_converter.h:145
ros::Publisher
boost::shared_ptr
p
p
jsk_pcl_ros::HeightmapConverter::onInit
virtual void onInit()
Definition: heightmap_converter_nodelet.cpp:47
jsk_pcl_ros::HeightmapConverter::pub_config_
ros::Publisher pub_config_
Definition: heightmap_converter.h:146
jsk_pcl_ros::HeightmapConverter::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: heightmap_converter.h:148
jsk_pcl_ros::HeightmapConverter::tf_broadcaster_
tf::TransformBroadcaster tf_broadcaster_
Definition: heightmap_converter.h:166
jsk_pcl_ros::HeightmapConverter::initial_probability_
double initial_probability_
Definition: heightmap_converter.h:163
transform_broadcaster.h
jsk_pcl_ros::HeightmapConverter::max_x_
double max_x_
Definition: heightmap_converter.h:151
jsk_pcl_ros::HeightmapConverter::projected_center_frame_id_
std::string projected_center_frame_id_
Definition: heightmap_converter.h:161
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::HeightmapConverter::convert
virtual void convert(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: heightmap_converter_nodelet.cpp:82
jsk_pcl_ros::HeightmapConverter::resolution_x_
int resolution_x_
Definition: heightmap_converter.h:156
tf::TransformBroadcaster
jsk_pcl_ros::HeightmapConverter::Ptr
boost::shared_ptr< HeightmapConverter > Ptr
Definition: heightmap_converter.h:121
jsk_pcl_ros::HeightmapConverter::mutex_
boost::mutex mutex_
Definition: heightmap_converter.h:144
jsk_pcl_ros::HeightmapConverter::toIndex
cv::Point toIndex(const pcl::PointXYZ &p) const
Definition: heightmap_converter.h:130
jsk_pcl_ros::HeightmapConverter::sub_
ros::Subscriber sub_
Definition: heightmap_converter.h:147
jsk_pcl_ros::HeightmapConverter::use_projected_center_
bool use_projected_center_
Definition: heightmap_converter.h:162
jsk_pcl_ros::HeightmapConverter::HeightmapConverter
HeightmapConverter()
Definition: heightmap_converter.h:123
jsk_pcl_ros::HeightmapConverter::resolution_y_
int resolution_y_
Definition: heightmap_converter.h:157
jsk_pcl_ros::HeightmapConverter::min_z_
double min_z_
Definition: heightmap_converter.h:154
jsk_pcl_ros::HeightmapConverter::subscribe
virtual void subscribe()
Definition: heightmap_converter_nodelet.cpp:72
jsk_pcl_ros::HeightmapConverter::Config
HeightmapConverterConfig Config
Definition: heightmap_converter.h:122
jsk_pcl_ros::HeightmapConverter::min_x_
double min_x_
Definition: heightmap_converter.h:150
transform_listener.h
jsk_pcl_ros::HeightmapConverter::duration_transform_timeout_
double duration_transform_timeout_
Definition: heightmap_converter.h:149
jsk_pcl_ros::HeightmapConverter::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: heightmap_converter_nodelet.cpp:170
jsk_pcl_ros::HeightmapConverter::min_y_
double min_y_
Definition: heightmap_converter.h:152
tf::TransformListener
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::HeightmapConverter::max_z_
double max_z_
Definition: heightmap_converter.h:155
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
jsk_pcl_ros::HeightmapConverter::max_y_
double max_y_
Definition: heightmap_converter.h:153
ros::Subscriber
jsk_pcl_ros::HeightmapConverter::max_queue_size_
int max_queue_size_
Definition: heightmap_converter.h:158
jsk_pcl_ros::HeightmapConverter::unsubscribe
virtual void unsubscribe()
Definition: heightmap_converter_nodelet.cpp:77
jsk_pcl_ros::HeightmapConverter::tf_
tf::TransformListener * tf_
Definition: heightmap_converter.h:165


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