35 #ifndef JSK_PCL_ROS_KINFU_H_ 36 #define JSK_PCL_ROS_KINFU_H_ 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> 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> 62 #include "jsk_pcl_ros/KinfuConfig.h" 71 void paint3DView (
const KinfuTracker::View& rgb24, KinfuTracker::View& view,
float colors_weight = 0.5
f);
85 typedef jsk_pcl_ros::KinfuConfig
Config;
87 Kinfu(): ConnectionBasedNodelet(), frame_idx_(0) {}
90 virtual void onInit();
92 virtual void unsubscribe();
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);
103 virtual void configCallback(Config &config, uint32_t level);
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);
161 #endif // JSK_PCL_ROS_KINFU_H_ ros::Publisher pub_camera_pose_
pcl::texture_mapping::CameraVector cameras_
ros::ServiceServer srv_reset_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicyWithColor > > sync_with_color_
Eigen::Affine3f odom_init_to_kinfu_origin_
std::string fixed_frame_id_
bool update(const T &new_val, T &my_val)
boost::shared_ptr< tf::TransformListener > tf_listener_
void paint3DView(const KinfuTracker::View &rgb24, KinfuTracker::View &view, float colors_weight=0.5f)
pcl::gpu::kinfuLS::KinfuTracker::View colors_device_
std::vector< cv::Mat > textures_
ros::ServiceServer srv_save_mesh_with_context_
jsk_pcl_ros::KinfuConfig Config
message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, sensor_msgs::Image > SyncPolicy
boost::shared_ptr< pcl::gpu::kinfuLS::KinfuTracker > kinfu_
boost::mutex mutex
global mutex.
ros::Publisher pub_cloud_
ros::ServiceServer srv_save_mesh_
ros::Publisher pub_depth_
message_filters::Subscriber< sensor_msgs::Image > sub_color_
ros::Publisher pub_rendered_image_
message_filters::sync_policies::ApproximateTime< sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::Image > SyncPolicyWithColor
pcl::gpu::kinfuLS::MarchingCubes::Ptr marching_cubes_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
pcl::gpu::kinfuLS::RayCaster::Ptr raycaster_
message_filters::Subscriber< sensor_msgs::Image > sub_depth_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
tf::TransformBroadcaster tf_broadcaster_
ros::Publisher pub_status_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_