#include <kinfu.h>
Public Types | |
typedef message_filters::sync_policies::ExactTime < sensor_msgs::Image, sensor_msgs::Image > | SyncPolicy |
Public Member Functions | |
Kinfu () | |
Protected Member Functions | |
virtual void | callback (const sensor_msgs::Image::ConstPtr &depth_image, const sensor_msgs::Image::ConstPtr &rgb_image) |
virtual void | infoCallback (const sensor_msgs::CameraInfo::ConstPtr &info_msg) |
virtual void | onInit () |
virtual void | subscribe () |
virtual void | unsubscribe () |
Protected Attributes | |
std::string | child_frame_id_ |
pcl::gpu::DeviceArray < pcl::PointXYZ > | cloud_buffer_device_ |
pcl::gpu::kinfuLS::KinfuTracker::View | colors_device_ |
pcl::gpu::kinfuLS::KinfuTracker::DepthMap | depth_device_ |
sensor_msgs::CameraInfo::ConstPtr | info_msg_ |
Eigen::Affine3f | initial_camera_pose_ |
bool | initial_camera_pose_acquired_ |
Eigen::Affine3f | initial_kinfu_pose_ |
bool | initialized_ |
pcl::gpu::kinfuLS::KinfuTracker * | kinfu_ |
std::string | kinfu_origin_frame_id_ |
boost::mutex | mutex_ |
std::string | parent_frame_id_ |
ros::Publisher | pub_cloud_ |
ros::Publisher | pub_pose_ |
float | shift_distance_ |
int | snapshot_rate_ |
message_filters::Subscriber < sensor_msgs::Image > | sub_color_image_ |
message_filters::Subscriber < sensor_msgs::Image > | sub_depth_image_ |
ros::Subscriber | sub_info_ |
boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ |
tf::TransformBroadcaster | tf_broadcaster_ |
tf::TransformListener * | tf_listener_ |
float | volume_size_ |
O := odometory origin M := map origin C := camera pose
M(t0) R = I O(t0)
C(t0) R = K(t) : estimated from kinfu C(t)
M(t) O(t0) R = R K(t) C(t) C(t0)
M(t) O(t) O(t0) R R = R K(t) O(t) C(t) C(t0)
M(t) O(t0) O(t) R = R K(t) R^(-1) O(t) C(t0) C(t)
typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image> jsk_pcl_ros::Kinfu::SyncPolicy |
jsk_pcl_ros::Kinfu::Kinfu | ( | ) | [inline] |
void jsk_pcl_ros::Kinfu::callback | ( | const sensor_msgs::Image::ConstPtr & | depth_image, |
const sensor_msgs::Image::ConstPtr & | rgb_image | ||
) | [protected, virtual] |
Definition at line 83 of file kinfu_nodelet.cpp.
void jsk_pcl_ros::Kinfu::infoCallback | ( | const sensor_msgs::CameraInfo::ConstPtr & | info_msg | ) | [protected, virtual] |
Definition at line 77 of file kinfu_nodelet.cpp.
void jsk_pcl_ros::Kinfu::onInit | ( | void | ) | [protected, virtual] |
Reimplemented from jsk_topic_tools::DiagnosticNodelet.
Definition at line 54 of file kinfu_nodelet.cpp.
void jsk_pcl_ros::Kinfu::subscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 44 of file kinfu_nodelet.cpp.
void jsk_pcl_ros::Kinfu::unsubscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 49 of file kinfu_nodelet.cpp.
std::string jsk_pcl_ros::Kinfu::child_frame_id_ [protected] |
pcl::gpu::DeviceArray<pcl::PointXYZ> jsk_pcl_ros::Kinfu::cloud_buffer_device_ [protected] |
pcl::gpu::kinfuLS::KinfuTracker::View jsk_pcl_ros::Kinfu::colors_device_ [protected] |
pcl::gpu::kinfuLS::KinfuTracker::DepthMap jsk_pcl_ros::Kinfu::depth_device_ [protected] |
sensor_msgs::CameraInfo::ConstPtr jsk_pcl_ros::Kinfu::info_msg_ [protected] |
Eigen::Affine3f jsk_pcl_ros::Kinfu::initial_camera_pose_ [protected] |
bool jsk_pcl_ros::Kinfu::initial_camera_pose_acquired_ [protected] |
Eigen::Affine3f jsk_pcl_ros::Kinfu::initial_kinfu_pose_ [protected] |
bool jsk_pcl_ros::Kinfu::initialized_ [protected] |
pcl::gpu::kinfuLS::KinfuTracker* jsk_pcl_ros::Kinfu::kinfu_ [protected] |
boost::mutex jsk_pcl_ros::Kinfu::mutex_ [protected] |
std::string jsk_pcl_ros::Kinfu::parent_frame_id_ [protected] |
ros::Publisher jsk_pcl_ros::Kinfu::pub_cloud_ [protected] |
ros::Publisher jsk_pcl_ros::Kinfu::pub_pose_ [protected] |
float jsk_pcl_ros::Kinfu::shift_distance_ [protected] |
int jsk_pcl_ros::Kinfu::snapshot_rate_ [protected] |
message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros::Kinfu::sub_color_image_ [protected] |
message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros::Kinfu::sub_depth_image_ [protected] |
ros::Subscriber jsk_pcl_ros::Kinfu::sub_info_ [protected] |
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::Kinfu::sync_ [protected] |
tf::TransformListener* jsk_pcl_ros::Kinfu::tf_listener_ [protected] |
float jsk_pcl_ros::Kinfu::volume_size_ [protected] |