#include <kinfu.h>
|
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) |
|
Definition at line 78 of file kinfu.h.
◆ Config
◆ SyncPolicy
◆ SyncPolicyWithColor
◆ Kinfu()
jsk_pcl_ros::Kinfu::Kinfu |
( |
| ) |
|
|
inline |
◆ ~Kinfu()
jsk_pcl_ros::Kinfu::~Kinfu |
( |
| ) |
|
|
virtual |
◆ configCallback()
void jsk_pcl_ros::Kinfu::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ convertToTextureMesh()
pcl::TextureMesh jsk_pcl_ros::Kinfu::convertToTextureMesh |
( |
const pcl::PolygonMesh & |
triangles, |
|
|
const std::vector< cv::Mat > |
textures, |
|
|
pcl::texture_mapping::CameraVector |
cameras |
|
) |
| |
|
protected |
◆ createPolygonMesh() [1/2]
pcl::PolygonMesh jsk_pcl_ros::Kinfu::createPolygonMesh |
( |
| ) |
|
|
protected |
◆ createPolygonMesh() [2/2]
pcl::PolygonMesh jsk_pcl_ros::Kinfu::createPolygonMesh |
( |
const jsk_recognition_msgs::BoundingBox & |
box_msg, |
|
|
const std::string & |
ground_frame_id |
|
) |
| |
|
protected |
◆ initKinfu()
void jsk_pcl_ros::Kinfu::initKinfu |
( |
const sensor_msgs::CameraInfo::ConstPtr & |
caminfo_msg | ) |
|
|
protected |
◆ onInit()
void jsk_pcl_ros::Kinfu::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ resetCallback()
bool jsk_pcl_ros::Kinfu::resetCallback |
( |
std_srvs::Empty::Request & |
req, |
|
|
std_srvs::Empty::Response & |
res |
|
) |
| |
|
protected |
◆ saveMeshCallback()
bool jsk_pcl_ros::Kinfu::saveMeshCallback |
( |
std_srvs::Empty::Request & |
req, |
|
|
std_srvs::Empty::Response & |
res |
|
) |
| |
|
protected |
◆ saveMeshWithContextCallback()
bool jsk_pcl_ros::Kinfu::saveMeshWithContextCallback |
( |
jsk_recognition_msgs::SaveMesh::Request & |
req, |
|
|
jsk_recognition_msgs::SaveMesh::Response & |
res |
|
) |
| |
|
protected |
◆ subscribe()
void jsk_pcl_ros::Kinfu::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::Kinfu::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ update() [1/2]
void jsk_pcl_ros::Kinfu::update |
( |
const sensor_msgs::CameraInfo::ConstPtr & |
caminfo_msg, |
|
|
const sensor_msgs::Image::ConstPtr & |
depth_msg |
|
) |
| |
|
protected |
◆ 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 |
◆ auto_reset_
bool jsk_pcl_ros::Kinfu::auto_reset_ |
|
protected |
◆ cameras_
pcl::texture_mapping::CameraVector jsk_pcl_ros::Kinfu::cameras_ |
|
protected |
◆ colors_device_
pcl::gpu::kinfuLS::KinfuTracker::View jsk_pcl_ros::Kinfu::colors_device_ |
|
protected |
◆ device_
int jsk_pcl_ros::Kinfu::device_ |
|
protected |
◆ fixed_frame_id_
◆ frame_idx_
int jsk_pcl_ros::Kinfu::frame_idx_ |
|
protected |
◆ integrate_color_
bool jsk_pcl_ros::Kinfu::integrate_color_ |
|
protected |
◆ kinfu_
◆ marching_cubes_
pcl::gpu::kinfuLS::MarchingCubes::Ptr jsk_pcl_ros::Kinfu::marching_cubes_ |
|
protected |
◆ mutex_
◆ n_textures_
int jsk_pcl_ros::Kinfu::n_textures_ |
|
protected |
◆ odom_init_to_kinfu_origin_
Eigen::Affine3f jsk_pcl_ros::Kinfu::odom_init_to_kinfu_origin_ |
|
protected |
◆ pub_camera_pose_
◆ pub_cloud_
◆ pub_depth_
◆ pub_rendered_image_
◆ pub_status_
◆ raycaster_
pcl::gpu::kinfuLS::RayCaster::Ptr jsk_pcl_ros::Kinfu::raycaster_ |
|
protected |
◆ save_dir_
◆ slam_
bool jsk_pcl_ros::Kinfu::slam_ |
|
protected |
◆ srv_
◆ srv_reset_
◆ srv_save_mesh_
◆ srv_save_mesh_with_context_
◆ sub_camera_info_
◆ sub_color_
◆ sub_depth_
◆ sync_
◆ sync_with_color_
◆ textures_
◆ tf_broadcaster_
◆ tf_listener_
◆ volume_size_
float jsk_pcl_ros::Kinfu::volume_size_ |
|
protected |
The documentation for this class was generated from the following files: