Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
jsk_pcl_ros::Kinfu Class Reference

#include <kinfu.h>

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

List of all members.

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 ()
 ~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::TransformListener
tf_listener_

Detailed Description

Definition at line 78 of file kinfu.h.


Member Typedef Documentation

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

Definition at line 85 of file kinfu.h.

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.

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

Definition at line 87 of file kinfu.h.

Definition at line 88 of file kinfu.h.


Member Function Documentation

void jsk_pcl_ros::Kinfu::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]

Definition at line 116 of file kinfu_nodelet.cpp.

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 528 of file kinfu_nodelet.cpp.

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

Definition at line 616 of file kinfu_nodelet.cpp.

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

Definition at line 653 of file kinfu_nodelet.cpp.

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

Definition at line 123 of file kinfu_nodelet.cpp.

void jsk_pcl_ros::Kinfu::onInit ( void  ) [protected, virtual]

Reimplemented from jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 83 of file kinfu_nodelet.cpp.

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

Definition at line 446 of file kinfu_nodelet.cpp.

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

Definition at line 493 of file kinfu_nodelet.cpp.

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

Definition at line 457 of file kinfu_nodelet.cpp.

void jsk_pcl_ros::Kinfu::subscribe ( ) [protected, virtual]

Implements jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 161 of file kinfu_nodelet.cpp.

void jsk_pcl_ros::Kinfu::unsubscribe ( ) [protected, virtual]

Implements jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 184 of file kinfu_nodelet.cpp.

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

Definition at line 189 of file kinfu_nodelet.cpp.

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 196 of file kinfu_nodelet.cpp.


Member Data Documentation

Definition at line 123 of file kinfu.h.

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

Definition at line 120 of file kinfu.h.

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

Definition at line 117 of file kinfu.h.

int jsk_pcl_ros::Kinfu::device_ [protected]

Definition at line 122 of file kinfu.h.

std::string jsk_pcl_ros::Kinfu::fixed_frame_id_ [protected]

Definition at line 126 of file kinfu.h.

Definition at line 129 of file kinfu.h.

Definition at line 124 of file kinfu.h.

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

Definition at line 115 of file kinfu.h.

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

Definition at line 116 of file kinfu.h.

Definition at line 132 of file kinfu.h.

Definition at line 127 of file kinfu.h.

Definition at line 135 of file kinfu.h.

Definition at line 143 of file kinfu.h.

Definition at line 144 of file kinfu.h.

Definition at line 145 of file kinfu.h.

Definition at line 146 of file kinfu.h.

Definition at line 147 of file kinfu.h.

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

Definition at line 118 of file kinfu.h.

std::string jsk_pcl_ros::Kinfu::save_dir_ [protected]

Definition at line 130 of file kinfu.h.

bool jsk_pcl_ros::Kinfu::slam_ [protected]

Definition at line 125 of file kinfu.h.

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

Definition at line 102 of file kinfu.h.

Definition at line 151 of file kinfu.h.

Definition at line 152 of file kinfu.h.

Definition at line 153 of file kinfu.h.

Definition at line 137 of file kinfu.h.

Definition at line 139 of file kinfu.h.

Definition at line 138 of file kinfu.h.

Definition at line 140 of file kinfu.h.

Definition at line 141 of file kinfu.h.

Definition at line 119 of file kinfu.h.

Definition at line 149 of file kinfu.h.

Definition at line 134 of file kinfu.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:51