kinfu.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Kentaro Wada and JSK Lab
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/o2r other materials provided
16  * with the distribution.
17  * * Neither the name of Kentaro Wada and JSK Lab 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 
35 #ifndef JSK_PCL_ROS_KINFU_H_
36 #define JSK_PCL_ROS_KINFU_H_
37 
38 #include <pcl/console/parse.h>
39 #include <pcl/gpu/kinfu_large_scale/kinfu.h>
40 #include <pcl/gpu/kinfu_large_scale/marching_cubes.h>
41 #include <pcl/gpu/kinfu_large_scale/raycaster.h>
42 #include <pcl/gpu/containers/initialization.h>
43 #include <pcl/surface/texture_mapping.h>
44 #include <pcl/point_cloud.h>
45 #include <pcl/point_types.h>
46 #include <pcl/common/angles.h>
47 
48 #include <dynamic_reconfigure/server.h>
55 #include <std_srvs/Empty.h>
56 #include <sensor_msgs/Image.h>
57 #include <sensor_msgs/PointCloud2.h>
58 #include <jsk_rviz_plugins/OverlayText.h>
61 
62 #include "jsk_pcl_ros/KinfuConfig.h"
63 
64 // defined in pcl/gpu/kinfu_large_scale/src/kinfu.cpp
65 namespace pcl
66 {
67  namespace gpu
68  {
69  namespace kinfuLS
70  {
71  void paint3DView (const KinfuTracker::View& rgb24, KinfuTracker::View& view, float colors_weight = 0.5f);
72  }
73  }
74 }
75 
76 namespace jsk_pcl_ros
77 {
79  {
80  public:
82  sensor_msgs::CameraInfo, sensor_msgs::Image> SyncPolicy;
84  sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::Image> SyncPolicyWithColor;
85  typedef jsk_pcl_ros::KinfuConfig Config;
86 
87  Kinfu(): ConnectionBasedNodelet(), frame_idx_(0) {}
88  ~Kinfu() {}
89  protected:
90  virtual void onInit();
91  virtual void subscribe();
92  virtual void unsubscribe();
93 
94  void initKinfu(const sensor_msgs::CameraInfo::ConstPtr& caminfo_msg);
95  void update(const sensor_msgs::CameraInfo::ConstPtr& caminfo_msg,
96  const sensor_msgs::Image::ConstPtr& depth_msg);
97  void update(const sensor_msgs::CameraInfo::ConstPtr& caminfo_msg,
98  const sensor_msgs::Image::ConstPtr& depth_msg,
99  const sensor_msgs::Image::ConstPtr& rgb_msg);
100  bool resetCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
101 
103  virtual void configCallback(Config &config, uint32_t level);
104 
105  pcl::PolygonMesh createPolygonMesh();
106  pcl::PolygonMesh createPolygonMesh(const jsk_recognition_msgs::BoundingBox& box_msg,
107  const std::string& ground_frame_id);
108  pcl::TextureMesh convertToTextureMesh(const pcl::PolygonMesh& triangles,
109  const std::vector<cv::Mat> textures,
110  pcl::texture_mapping::CameraVector cameras);
111  bool saveMeshCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
112  bool saveMeshWithContextCallback(
113  jsk_recognition_msgs::SaveMesh::Request& req, jsk_recognition_msgs::SaveMesh::Response& res);
114 
116  pcl::gpu::kinfuLS::MarchingCubes::Ptr marching_cubes_;
117  pcl::gpu::kinfuLS::KinfuTracker::View colors_device_;
118  pcl::gpu::kinfuLS::RayCaster::Ptr raycaster_;
119  std::vector<cv::Mat> textures_;
120  pcl::texture_mapping::CameraVector cameras_;
121 
122  int device_;
125  bool slam_;
126  std::string fixed_frame_id_;
129 
131  std::string save_dir_;
132 
134 
136  Eigen::Affine3f odom_init_to_kinfu_origin_;
137 
143 
149 
151 
155 
156  private:
157  };
158 
159 } // namespace jsk_pcl_ros
160 
161 #endif // JSK_PCL_ROS_KINFU_H_
ros::Publisher pub_camera_pose_
Definition: kinfu.h:144
pcl::texture_mapping::CameraVector cameras_
Definition: kinfu.h:120
ros::ServiceServer srv_reset_
Definition: kinfu.h:152
boost::shared_ptr< message_filters::Synchronizer< SyncPolicyWithColor > > sync_with_color_
Definition: kinfu.h:142
Eigen::Affine3f odom_init_to_kinfu_origin_
Definition: kinfu.h:136
boost::mutex mutex_
Definition: kinfu.h:133
std::string fixed_frame_id_
Definition: kinfu.h:126
bool update(const T &new_val, T &my_val)
boost::shared_ptr< tf::TransformListener > tf_listener_
Definition: kinfu.h:135
std::string save_dir_
Definition: kinfu.h:131
bool integrate_color_
Definition: kinfu.h:124
void paint3DView(const KinfuTracker::View &rgb24, KinfuTracker::View &view, float colors_weight=0.5f)
void subscribe()
pcl::gpu::kinfuLS::KinfuTracker::View colors_device_
Definition: kinfu.h:117
std::vector< cv::Mat > textures_
Definition: kinfu.h:119
ros::ServiceServer srv_save_mesh_with_context_
Definition: kinfu.h:154
jsk_pcl_ros::KinfuConfig Config
Definition: kinfu.h:85
message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, sensor_msgs::Image > SyncPolicy
Definition: kinfu.h:82
boost::shared_ptr< pcl::gpu::kinfuLS::KinfuTracker > kinfu_
Definition: kinfu.h:115
boost::mutex mutex
global mutex.
ros::Publisher pub_cloud_
Definition: kinfu.h:145
ros::ServiceServer srv_save_mesh_
Definition: kinfu.h:153
ros::Publisher pub_depth_
Definition: kinfu.h:146
message_filters::Subscriber< sensor_msgs::Image > sub_color_
Definition: kinfu.h:140
ros::Publisher pub_rendered_image_
Definition: kinfu.h:147
message_filters::sync_policies::ApproximateTime< sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::Image > SyncPolicyWithColor
Definition: kinfu.h:84
pcl::gpu::kinfuLS::MarchingCubes::Ptr marching_cubes_
Definition: kinfu.h:116
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: kinfu.h:102
pcl::gpu::kinfuLS::RayCaster::Ptr raycaster_
Definition: kinfu.h:118
message_filters::Subscriber< sensor_msgs::Image > sub_depth_
Definition: kinfu.h:139
bool auto_reset_
Definition: kinfu.h:123
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: kinfu.h:141
float volume_size_
Definition: kinfu.h:128
tf::TransformBroadcaster tf_broadcaster_
Definition: kinfu.h:150
ros::Publisher pub_status_
Definition: kinfu.h:148
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
Definition: kinfu.h:138


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47