Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::Kinfu Class Reference

#include <kinfu.h>

Inheritance diagram for jsk_pcl_ros::Kinfu:
Inheritance graph
[legend]

Public Types

typedef jsk_pcl_ros::KinfuConfig Config
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, sensor_msgs::Image > SyncPolicy
 
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::Image > SyncPolicyWithColor
 

Public Member Functions

 Kinfu ()
 
virtual ~Kinfu ()
 

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
 
pcl::TextureMesh convertToTextureMesh (const pcl::PolygonMesh &triangles, const std::vector< cv::Mat > textures, pcl::texture_mapping::CameraVector cameras)
 
pcl::PolygonMesh createPolygonMesh ()
 
pcl::PolygonMesh createPolygonMesh (const jsk_recognition_msgs::BoundingBox &box_msg, const std::string &ground_frame_id)
 
void initKinfu (const sensor_msgs::CameraInfo::ConstPtr &caminfo_msg)
 
virtual void onInit ()
 
bool resetCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 
bool saveMeshCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 
bool saveMeshWithContextCallback (jsk_recognition_msgs::SaveMesh::Request &req, jsk_recognition_msgs::SaveMesh::Response &res)
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 
void update (const sensor_msgs::CameraInfo::ConstPtr &caminfo_msg, const sensor_msgs::Image::ConstPtr &depth_msg)
 
void update (const sensor_msgs::CameraInfo::ConstPtr &caminfo_msg, const sensor_msgs::Image::ConstPtr &depth_msg, const sensor_msgs::Image::ConstPtr &rgb_msg)
 

Protected Attributes

bool auto_reset_
 
pcl::texture_mapping::CameraVector cameras_
 
pcl::gpu::kinfuLS::KinfuTracker::View colors_device_
 
int device_
 
std::string fixed_frame_id_
 
int frame_idx_
 
bool integrate_color_
 
boost::shared_ptr< pcl::gpu::kinfuLS::KinfuTracker > kinfu_
 
pcl::gpu::kinfuLS::MarchingCubes::Ptr marching_cubes_
 
boost::mutex mutex_
 
int n_textures_
 
Eigen::Affine3f odom_init_to_kinfu_origin_
 
ros::Publisher pub_camera_pose_
 
ros::Publisher pub_cloud_
 
ros::Publisher pub_depth_
 
ros::Publisher pub_rendered_image_
 
ros::Publisher pub_status_
 
pcl::gpu::kinfuLS::RayCaster::Ptr raycaster_
 
std::string save_dir_
 
bool slam_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
ros::ServiceServer srv_reset_
 
ros::ServiceServer srv_save_mesh_
 
ros::ServiceServer srv_save_mesh_with_context_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
 
message_filters::Subscriber< sensor_msgs::Image > sub_color_
 
message_filters::Subscriber< sensor_msgs::Image > sub_depth_
 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicyWithColor > > sync_with_color_
 
std::vector< cv::Mat > textures_
 
tf::TransformBroadcaster tf_broadcaster_
 
boost::shared_ptr< tf::TransformListenertf_listener_
 
float volume_size_
 

Detailed Description

Definition at line 78 of file kinfu.h.

Member Typedef Documentation

◆ Config

typedef jsk_pcl_ros::KinfuConfig jsk_pcl_ros::Kinfu::Config

Definition at line 85 of file kinfu.h.

◆ SyncPolicy

typedef message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, sensor_msgs::Image> jsk_pcl_ros::Kinfu::SyncPolicy

Definition at line 82 of file kinfu.h.

◆ SyncPolicyWithColor

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::Image> jsk_pcl_ros::Kinfu::SyncPolicyWithColor

Definition at line 84 of file kinfu.h.

Constructor & Destructor Documentation

◆ Kinfu()

jsk_pcl_ros::Kinfu::Kinfu ( )
inline

Definition at line 87 of file kinfu.h.

◆ ~Kinfu()

jsk_pcl_ros::Kinfu::~Kinfu ( )
virtual

Definition at line 116 of file kinfu_nodelet.cpp.

Member Function Documentation

◆ configCallback()

void jsk_pcl_ros::Kinfu::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

Definition at line 129 of file kinfu_nodelet.cpp.

◆ convertToTextureMesh()

pcl::TextureMesh jsk_pcl_ros::Kinfu::convertToTextureMesh ( const pcl::PolygonMesh &  triangles,
const std::vector< cv::Mat >  textures,
pcl::texture_mapping::CameraVector  cameras 
)
protected

Definition at line 549 of file kinfu_nodelet.cpp.

◆ createPolygonMesh() [1/2]

pcl::PolygonMesh jsk_pcl_ros::Kinfu::createPolygonMesh ( )
protected

Definition at line 637 of file kinfu_nodelet.cpp.

◆ createPolygonMesh() [2/2]

pcl::PolygonMesh jsk_pcl_ros::Kinfu::createPolygonMesh ( const jsk_recognition_msgs::BoundingBox &  box_msg,
const std::string ground_frame_id 
)
protected

Definition at line 674 of file kinfu_nodelet.cpp.

◆ initKinfu()

void jsk_pcl_ros::Kinfu::initKinfu ( const sensor_msgs::CameraInfo::ConstPtr &  caminfo_msg)
protected

Definition at line 136 of file kinfu_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::Kinfu::onInit ( )
protectedvirtual

Definition at line 83 of file kinfu_nodelet.cpp.

◆ resetCallback()

bool jsk_pcl_ros::Kinfu::resetCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)
protected

Definition at line 467 of file kinfu_nodelet.cpp.

◆ saveMeshCallback()

bool jsk_pcl_ros::Kinfu::saveMeshCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)
protected

Definition at line 514 of file kinfu_nodelet.cpp.

◆ saveMeshWithContextCallback()

bool jsk_pcl_ros::Kinfu::saveMeshWithContextCallback ( jsk_recognition_msgs::SaveMesh::Request &  req,
jsk_recognition_msgs::SaveMesh::Response &  res 
)
protected

Definition at line 478 of file kinfu_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros::Kinfu::subscribe ( )
protectedvirtual

Definition at line 173 of file kinfu_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::Kinfu::unsubscribe ( )
protectedvirtual

Definition at line 196 of file kinfu_nodelet.cpp.

◆ update() [1/2]

void jsk_pcl_ros::Kinfu::update ( const sensor_msgs::CameraInfo::ConstPtr &  caminfo_msg,
const sensor_msgs::Image::ConstPtr &  depth_msg 
)
protected

Definition at line 201 of file kinfu_nodelet.cpp.

◆ update() [2/2]

void jsk_pcl_ros::Kinfu::update ( const sensor_msgs::CameraInfo::ConstPtr &  caminfo_msg,
const sensor_msgs::Image::ConstPtr &  depth_msg,
const sensor_msgs::Image::ConstPtr &  rgb_msg 
)
protected

Definition at line 208 of file kinfu_nodelet.cpp.

Member Data Documentation

◆ auto_reset_

bool jsk_pcl_ros::Kinfu::auto_reset_
protected

Definition at line 123 of file kinfu.h.

◆ cameras_

pcl::texture_mapping::CameraVector jsk_pcl_ros::Kinfu::cameras_
protected

Definition at line 120 of file kinfu.h.

◆ colors_device_

pcl::gpu::kinfuLS::KinfuTracker::View jsk_pcl_ros::Kinfu::colors_device_
protected

Definition at line 117 of file kinfu.h.

◆ device_

int jsk_pcl_ros::Kinfu::device_
protected

Definition at line 122 of file kinfu.h.

◆ fixed_frame_id_

std::string jsk_pcl_ros::Kinfu::fixed_frame_id_
protected

Definition at line 126 of file kinfu.h.

◆ frame_idx_

int jsk_pcl_ros::Kinfu::frame_idx_
protected

Definition at line 130 of file kinfu.h.

◆ integrate_color_

bool jsk_pcl_ros::Kinfu::integrate_color_
protected

Definition at line 124 of file kinfu.h.

◆ kinfu_

boost::shared_ptr<pcl::gpu::kinfuLS::KinfuTracker> jsk_pcl_ros::Kinfu::kinfu_
protected

Definition at line 115 of file kinfu.h.

◆ marching_cubes_

pcl::gpu::kinfuLS::MarchingCubes::Ptr jsk_pcl_ros::Kinfu::marching_cubes_
protected

Definition at line 116 of file kinfu.h.

◆ mutex_

boost::mutex jsk_pcl_ros::Kinfu::mutex_
protected

Definition at line 133 of file kinfu.h.

◆ n_textures_

int jsk_pcl_ros::Kinfu::n_textures_
protected

Definition at line 127 of file kinfu.h.

◆ odom_init_to_kinfu_origin_

Eigen::Affine3f jsk_pcl_ros::Kinfu::odom_init_to_kinfu_origin_
protected

Definition at line 136 of file kinfu.h.

◆ pub_camera_pose_

ros::Publisher jsk_pcl_ros::Kinfu::pub_camera_pose_
protected

Definition at line 144 of file kinfu.h.

◆ pub_cloud_

ros::Publisher jsk_pcl_ros::Kinfu::pub_cloud_
protected

Definition at line 145 of file kinfu.h.

◆ pub_depth_

ros::Publisher jsk_pcl_ros::Kinfu::pub_depth_
protected

Definition at line 146 of file kinfu.h.

◆ pub_rendered_image_

ros::Publisher jsk_pcl_ros::Kinfu::pub_rendered_image_
protected

Definition at line 147 of file kinfu.h.

◆ pub_status_

ros::Publisher jsk_pcl_ros::Kinfu::pub_status_
protected

Definition at line 148 of file kinfu.h.

◆ raycaster_

pcl::gpu::kinfuLS::RayCaster::Ptr jsk_pcl_ros::Kinfu::raycaster_
protected

Definition at line 118 of file kinfu.h.

◆ save_dir_

std::string jsk_pcl_ros::Kinfu::save_dir_
protected

Definition at line 131 of file kinfu.h.

◆ slam_

bool jsk_pcl_ros::Kinfu::slam_
protected

Definition at line 125 of file kinfu.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::Kinfu::srv_
protected

Definition at line 102 of file kinfu.h.

◆ srv_reset_

ros::ServiceServer jsk_pcl_ros::Kinfu::srv_reset_
protected

Definition at line 152 of file kinfu.h.

◆ srv_save_mesh_

ros::ServiceServer jsk_pcl_ros::Kinfu::srv_save_mesh_
protected

Definition at line 153 of file kinfu.h.

◆ srv_save_mesh_with_context_

ros::ServiceServer jsk_pcl_ros::Kinfu::srv_save_mesh_with_context_
protected

Definition at line 154 of file kinfu.h.

◆ sub_camera_info_

message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_pcl_ros::Kinfu::sub_camera_info_
protected

Definition at line 138 of file kinfu.h.

◆ sub_color_

message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros::Kinfu::sub_color_
protected

Definition at line 140 of file kinfu.h.

◆ sub_depth_

message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros::Kinfu::sub_depth_
protected

Definition at line 139 of file kinfu.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::Kinfu::sync_
protected

Definition at line 141 of file kinfu.h.

◆ sync_with_color_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicyWithColor> > jsk_pcl_ros::Kinfu::sync_with_color_
protected

Definition at line 142 of file kinfu.h.

◆ textures_

std::vector<cv::Mat> jsk_pcl_ros::Kinfu::textures_
protected

Definition at line 119 of file kinfu.h.

◆ tf_broadcaster_

tf::TransformBroadcaster jsk_pcl_ros::Kinfu::tf_broadcaster_
protected

Definition at line 150 of file kinfu.h.

◆ tf_listener_

boost::shared_ptr<tf::TransformListener> jsk_pcl_ros::Kinfu::tf_listener_
protected

Definition at line 135 of file kinfu.h.

◆ volume_size_

float jsk_pcl_ros::Kinfu::volume_size_
protected

Definition at line 128 of file kinfu.h.


The documentation for this class was generated from the following files:


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