#include <incremental_model_registration.h>
◆ SyncPolicy
◆ IncrementalModelRegistration()
jsk_pcl_ros::IncrementalModelRegistration::IncrementalModelRegistration |
( |
| ) |
|
|
inline |
◆ ~IncrementalModelRegistration()
jsk_pcl_ros::IncrementalModelRegistration::~IncrementalModelRegistration |
( |
| ) |
|
|
virtual |
◆ callICP()
void jsk_pcl_ros::IncrementalModelRegistration::callICP |
( |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr |
reference, |
|
|
pcl::PointCloud< pcl::PointXYZRGB >::Ptr |
target, |
|
|
Eigen::Affine3f & |
output_transform |
|
) |
| |
|
protectedvirtual |
◆ newsampleCallback()
void jsk_pcl_ros::IncrementalModelRegistration::newsampleCallback |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
cloud_msg, |
|
|
const pcl_msgs::PointIndices::ConstPtr & |
indices_msg, |
|
|
const geometry_msgs::PoseStamped::ConstPtr & |
pose_msg |
|
) |
| |
|
protectedvirtual |
◆ onInit()
void jsk_pcl_ros::IncrementalModelRegistration::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ startRegistration()
bool jsk_pcl_ros::IncrementalModelRegistration::startRegistration |
( |
std_srvs::Empty::Request & |
req, |
|
|
std_srvs::Empty::Response & |
res |
|
) |
| |
|
protectedvirtual |
◆ subscribe()
virtual void jsk_pcl_ros::IncrementalModelRegistration::subscribe |
( |
| ) |
|
|
inlineprotectedvirtual |
◆ transformPointCloudRepsectedToPose()
void jsk_pcl_ros::IncrementalModelRegistration::transformPointCloudRepsectedToPose |
( |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr |
input, |
|
|
pcl::PointCloud< pcl::PointXYZRGB >::Ptr |
output, |
|
|
const geometry_msgs::PoseStamped::ConstPtr & |
pose_msg |
|
) |
| |
|
protectedvirtual |
◆ unsubscribe()
virtual void jsk_pcl_ros::IncrementalModelRegistration::unsubscribe |
( |
| ) |
|
|
inlineprotectedvirtual |
◆ updateDiagnostic()
◆ all_cloud_
pcl::PointCloud<pcl::PointXYZRGB> jsk_pcl_ros::IncrementalModelRegistration::all_cloud_ |
|
protected |
◆ frame_id_
std::string jsk_pcl_ros::IncrementalModelRegistration::frame_id_ |
|
protected |
◆ mutex_
boost::mutex jsk_pcl_ros::IncrementalModelRegistration::mutex_ |
|
protected |
◆ origin_
Eigen::Affine3f jsk_pcl_ros::IncrementalModelRegistration::origin_ |
|
protected |
◆ pub_cloud_non_registered_
ros::Publisher jsk_pcl_ros::IncrementalModelRegistration::pub_cloud_non_registered_ |
|
protected |
◆ pub_registered_
ros::Publisher jsk_pcl_ros::IncrementalModelRegistration::pub_registered_ |
|
protected |
◆ samples_
◆ start_registration_srv_
◆ sub_cloud_
◆ sub_indices_
◆ sub_pose_
◆ sync_
◆ viewer_
boost::shared_ptr<pcl::visualization::PCLVisualizer> jsk_pcl_ros::IncrementalModelRegistration::viewer_ |
|
protected |
The documentation for this class was generated from the following files: