#include <ShapeReconstruction.h>
Public Member Functions | |
ShapeReconstructionPtr | clone () const |
virtual void | generateMesh () |
SRPointCloud::Ptr | getCurrentPointCloud () const |
omip::RB_id_t | getId () const |
SRPointCloud::Ptr | getMovedRigidBodyShapeExtDandC () const |
SRPointCloud::Ptr | getRigidBodyShapeExtDandC () const |
virtual void | getShapeModel (omip_msgs::ShapeModelsPtr shapes) |
virtual void | initialize () |
virtual void | PublishMovedModelAndSegment (const ros::Time current_time, const geometry_msgs::TwistWithCovariance &rb_transformation, rosbag::Bag &bag, bool bagOpen) |
virtual void | RemoveInconsistentPoints (const SRPointCloud::Ptr &pc_msg, const geometry_msgs::TwistWithCovariance &rb_transformation) |
virtual void | setAccumulateChangeCandidates (bool b) |
virtual void | setApproxVoxelGridLeafSize (double leaf_size) |
virtual void | setCameraInfo (const sensor_msgs::CameraInfo &camera_info) |
virtual void | setColorChangesErodeSize (double color_changes_erode_size) |
virtual void | setDepthFilling (bool depth_filling) |
virtual void | setDetectStaticEnvironment (bool b) |
void | setEstimateSV (bool estimate_sv) |
virtual void | setExtendToNeighborSV (bool extend_to_neighbor_sv) |
virtual void | setFullRGBDPCandRBT (const SRPointCloud::Ptr &pc_msg, const geometry_msgs::TwistWithCovariance &rb_transformation) |
virtual void | setInitialFullRGBDPCAndRBT (const SRPointCloud::Ptr &initial_pc_msg, const geometry_msgs::TwistWithCovariance &rb_transformation_initial) |
virtual void | setKNNMinRadius (double knn_min_radius) |
virtual void | setLiveStream (bool live_stream) |
virtual void | setMinColorChange (int min_color_change) |
virtual void | setMinDepthChange (double b) |
virtual void | setRadiusOutRemovalMinNeighbors (int ror_min_neighbors) |
virtual void | setRadiusOutRemovalSearch (double ror_radius_search) |
virtual void | setRBId (omip::RB_id_t rb_id) |
virtual void | setRecordVideos (bool record_videos) |
virtual void | setRemoveInconsistentPoints (double b) |
virtual void | setSimilarityInH (double similarity_in_h) |
virtual void | setSimilarityInNormal (double similarity_in_normal) |
virtual void | setSuperVoxelClustersPtr (std::map< uint32_t, pcl::Supervoxel< SRPoint >::Ptr > &supervoxel_clusters) |
virtual void | setSuperVoxelizerPtr (boost::shared_ptr< pcl::SupervoxelClustering< SRPoint > > &supervoxelizer) |
virtual void | setSupportingFeatures (pcl::PointCloud< pcl::PointXYZL >::Ptr supporting_features) |
virtual void | setSVMinNumberModelPixels (int min_number_model_pixels_in_sv) |
virtual void | setToInitial (bool to_initial) |
ShapeReconstruction () | |
ShapeReconstruction (const ShapeReconstruction &sr) | |
virtual void | useClusteredFeatures (bool use_clustered_features) |
virtual | ~ShapeReconstruction () |
Protected Member Functions | |
virtual void | _DetectImageLocationsWhereColorChanges () |
virtual void | _DetectImageLocationsWhereDepthChanges () |
virtual void | _EstimateTransformations () |
virtual void | _ExtendPointsToRegions () |
virtual void | _ExtendToNeighborSV (std::multimap< uint32_t, uint32_t > &supervoxel_adjacency, std::vector< uint32_t > &labels_extension) |
virtual void | _FilterModel () |
virtual void | _FindCandidatesInCurrentPC (const FrameForSegmentation &_previous_ffs, FrameForSegmentation &_current_ffs, pcl::PointIndices::Ptr &_moving_pts_of_current_idx_depth, Eigen::Matrix4d &_previous_to_current_HTransform, std::vector< std::vector< int > > &_previous_k_indices_depth, std::vector< std::vector< float > > &_previous_sqrt_dist_depth) |
virtual void | _FindCandidatesInPreviousPC (FrameForSegmentation &_previous_ffs, const FrameForSegmentation &_current_ffs, pcl::PointIndices::Ptr &_moving_pts_of_previous_idx_depth, Eigen::Matrix4d &_current_to_previous_HTransform, std::vector< std::vector< int > > &_current_k_indices_depth, std::vector< std::vector< float > > &_current_sqrt_dist_depth) |
virtual void | _FindInconsistentPoints (const omip::SRPointCloud::Ptr &pc_source, const cv::Mat &dm_true, pcl::PointIndicesPtr &indices_to_remove, pcl::PointIndicesPtr &indices_matching_in_true, pcl::PointIndicesPtr &indices_matching_in_dm, const double min_depth_error=0.03) |
virtual void | _GenerateMesh (const omip::SRPointCloud::Ptr &pc_source, std::string shape_file_prefix) |
virtual void | _MergeValidPointsIntoModels () |
virtual void | _MergeValidPointsIntoModels (const std::string &logger_name, omip::SRPointCloud::Ptr &points_of_current_in_origin, omip::SRPointCloud::Ptr &points_of_previous_in_origin, omip::SRPointCloud::Ptr &rb_model, const std::vector< std::vector< int > > ¤t_k_indices, const std::vector< std::vector< int > > &previous_k_indices) |
virtual void | _RemoveInconsistentPointsFromModelsAndExtendToRegions () |
virtual void | _RemoveInconsistentPointsFromRBModel (const std::string method, const Eigen::Matrix4d &HTransform, SRPointCloud::Ptr &rb_shape_depth, cv::Mat ¤t_dm, SRPointCloud::Ptr current_pc, SRPointCloud::Ptr &rb_segment_depth) |
virtual void | _TestMotionCoherencyOfPointsInImageLocationsWhereColorChanged () |
virtual void | _TestMotionCoherencyOfPointsInImageLocationsWhereDepthChanged () |
virtual ShapeReconstruction * | doClone () const |
Clone function. | |
void | growSVRecursively (uint32_t label_sv_seed, std::vector< uint32_t > &labels_extension, std::multimap< uint32_t, uint32_t > &supervoxel_adjacency, std::vector< uint32_t > &sv_containing_supporting_features, int &distance_to_feature_sv, std::map< uint32_t, std::unordered_set< int > > &labels_of_segments_to_extend) |
Protected Attributes | |
cv::Mat | _acc_candidates_of_current |
bool | _accumulate_change_candidates |
pcl::ApproximateVoxelGrid < SRPoint > | _approximate_voxel_grid_filter |
SRPointCloud::Ptr | _candidates |
SRPointCloud::Ptr | _candidates_in_current |
cv::Mat | _candidates_of_current |
cv::Mat | _candidates_of_current_8u |
cv::Mat | _candidates_of_previous |
cv::Mat | _candidates_of_previous_8u |
sensor_msgs::CameraInfo | _ci |
double | _color_changes_erode_size |
cv::Mat | _current_depth_mask |
FrameForSegmentation | _current_ffs |
Eigen::Matrix4d | _current_HTransform |
Eigen::Matrix4d | _current_HTransform_inv |
std::vector< std::vector< int > > | _current_k_indices |
Eigen::Matrix4d | _current_to_previous_HTransform |
Eigen::Twistd | _current_twist |
bool | _depth_filling |
bool | _detect_static_environment |
cv::Mat | _difference_in_depth |
cv::Mat | _difference_in_depth_moved |
bool | _estimate_supervoxels |
bool | _extend_to_neighbor_sv |
pcl::ExtractIndices< SRPoint > | _extractor |
FrameForSegmentation | _initial_ffs |
pcl::search::Search< SRPoint >::Ptr | _knn |
double | _knn_min_radius |
double | _leaf_size |
bool | _live_stream |
int | _min_color_change |
double | _min_depth_change |
int | _min_number_model_pixels_in_sv |
pcl::PointIndices::Ptr | _moving_pts_of_current_idx_color |
pcl::PointIndices::Ptr | _moving_pts_of_current_idx_depth |
pcl::PointIndices::Ptr | _moving_pts_of_previous_idx_color |
pcl::PointIndices::Ptr | _moving_pts_of_previous_idx_depth |
ros::NodeHandle | _node_handle |
pcl::PointIndices::Ptr | _occluded_pts_of_current_idx |
ros::Publisher | _occlusions_pub |
ros::Publisher | _occlusions_transformed_pub |
pcl::PointIndices::Ptr | _out_of_view_pts_of_current_idx |
cv::Mat | _previous_depth_mask |
FrameForSegmentation | _previous_ffs |
Eigen::Matrix4d | _previous_HTransform |
Eigen::Matrix4d | _previous_HTransform_inv |
std::vector< std::vector< int > > | _previous_k_indices |
std::vector< std::vector< int > > | _previous_k_indices_previous |
Eigen::Matrix4d | _previous_to_current_HTransform |
Eigen::Twistd | _previous_twist |
pcl::RadiusOutlierRemoval < SRPoint > | _radius_outlier_removal |
pcl::PointCloud< pcl::Normal >::Ptr | _rb_estimated_normals_pc_ptr |
pcl::GreedyProjectionTriangulation < pcl::PointXYZRGBNormal > ::Ptr | _rb_greedy_projection_triangulator_ptr |
omip::RB_id_t | _rb_id |
pcl::NormalEstimationOMP < omip::SRPoint, pcl::Normal > ::Ptr | _rb_normal_estimator_ptr |
vtkSmartPointer< vtkPolyData > | _rb_polygon_data_ptr |
vtkSmartPointer< vtkSTLWriter > | _rb_polygon_writer_ptr |
pcl::PointCloud < pcl::PointXYZRGBNormal > ::Ptr | _rb_position_color_and_normals_pc_ptr |
SRPointCloud::Ptr | _rb_segment |
ros::Publisher | _rb_segment_pub |
SRPointCloud::Ptr | _rb_shape |
SRPointCloud::Ptr | _rb_shape_in_current_frame |
ros::Publisher | _rb_shape_pub |
pcl::search::KdTree < omip::SRPoint >::Ptr | _rb_tree_for_normal_estimation_ptr |
pcl::search::KdTree < pcl::PointXYZRGBNormal > ::Ptr | _rb_tree_for_triangulation_ptr |
pcl::PolygonMesh::Ptr | _rb_triangulated_mesh_ptr |
bool | _record_videos |
bool | _remove_inconsistent_points |
pcl::RangeImagePlanar::Ptr | _rip_temp |
int | _ror_min_neighbors |
double | _ror_radius_search |
double | _similarity_in_h |
double | _similarity_in_normal |
std::vector< std::vector< float > > | _sqrt_dist |
std::map< uint32_t, pcl::Supervoxel< SRPoint > ::Ptr > * | _supervoxel_clusters_ptr |
boost::shared_ptr < pcl::SupervoxelClustering < SRPoint > > * | _supervoxelizer_ptr_ptr |
pcl::PointCloud < pcl::PointXYZL >::Ptr | _supporting_features |
int | _t |
double | _timestamp_color |
bool | _to_initial |
bool | _use_clustered_features |
rosbag::Bag | _videos |
Definition at line 164 of file ShapeReconstruction.h.
Mesh generation and storage as STL file
For RB shape
Definition at line 47 of file ShapeReconstruction.cpp.
ShapeReconstruction::ShapeReconstruction | ( | const ShapeReconstruction & | sr | ) |
Definition at line 198 of file ShapeReconstruction.cpp.
ShapeReconstruction::~ShapeReconstruction | ( | ) | [virtual] |
Definition at line 220 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_DetectImageLocationsWhereColorChanges | ( | ) | [protected, virtual] |
Definition at line 461 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_DetectImageLocationsWhereDepthChanges | ( | ) | [protected, virtual] |
Definition at line 340 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_EstimateTransformations | ( | ) | [protected, virtual] |
Definition at line 1155 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_ExtendPointsToRegions | ( | ) | [protected, virtual] |
Definition at line 933 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_ExtendToNeighborSV | ( | std::multimap< uint32_t, uint32_t > & | supervoxel_adjacency, |
std::vector< uint32_t > & | labels_extension | ||
) | [protected, virtual] |
Definition at line 1062 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_FilterModel | ( | ) | [protected, virtual] |
Definition at line 740 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_FindCandidatesInCurrentPC | ( | const FrameForSegmentation & | _previous_ffs, |
FrameForSegmentation & | _current_ffs, | ||
pcl::PointIndices::Ptr & | _moving_pts_of_current_idx_depth, | ||
Eigen::Matrix4d & | _previous_to_current_HTransform, | ||
std::vector< std::vector< int > > & | _previous_k_indices_depth, | ||
std::vector< std::vector< float > > & | _previous_sqrt_dist_depth | ||
) | [protected, virtual] |
Definition at line 639 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_FindCandidatesInPreviousPC | ( | FrameForSegmentation & | _previous_ffs, |
const FrameForSegmentation & | _current_ffs, | ||
pcl::PointIndices::Ptr & | _moving_pts_of_previous_idx_depth, | ||
Eigen::Matrix4d & | _current_to_previous_HTransform, | ||
std::vector< std::vector< int > > & | _current_k_indices_depth, | ||
std::vector< std::vector< float > > & | _current_sqrt_dist_depth | ||
) | [protected, virtual] |
Definition at line 608 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_FindInconsistentPoints | ( | const omip::SRPointCloud::Ptr & | pc_source, |
const cv::Mat & | dm_true, | ||
pcl::PointIndicesPtr & | indices_to_remove, | ||
pcl::PointIndicesPtr & | indices_matching_in_true, | ||
pcl::PointIndicesPtr & | indices_matching_in_dm, | ||
const double | min_depth_error = 0.03 |
||
) | [protected, virtual] |
Definition at line 840 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_GenerateMesh | ( | const omip::SRPointCloud::Ptr & | pc_source, |
std::string | shape_file_prefix | ||
) | [protected, virtual] |
Definition at line 1176 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_MergeValidPointsIntoModels | ( | ) | [protected, virtual] |
Definition at line 670 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_MergeValidPointsIntoModels | ( | const std::string & | logger_name, |
omip::SRPointCloud::Ptr & | points_of_current_in_origin, | ||
omip::SRPointCloud::Ptr & | points_of_previous_in_origin, | ||
omip::SRPointCloud::Ptr & | rb_model, | ||
const std::vector< std::vector< int > > & | current_k_indices, | ||
const std::vector< std::vector< int > > & | previous_k_indices | ||
) | [protected, virtual] |
Definition at line 694 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_RemoveInconsistentPointsFromModelsAndExtendToRegions | ( | ) | [protected, virtual] |
Definition at line 724 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_RemoveInconsistentPointsFromRBModel | ( | const std::string | method, |
const Eigen::Matrix4d & | HTransform, | ||
SRPointCloud::Ptr & | rb_shape_depth, | ||
cv::Mat & | current_dm, | ||
SRPointCloud::Ptr | current_pc, | ||
SRPointCloud::Ptr & | rb_segment_depth | ||
) | [protected, virtual] |
Definition at line 759 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_TestMotionCoherencyOfPointsInImageLocationsWhereColorChanged | ( | ) | [protected, virtual] |
Definition at line 586 of file ShapeReconstruction.cpp.
void ShapeReconstruction::_TestMotionCoherencyOfPointsInImageLocationsWhereDepthChanged | ( | ) | [protected, virtual] |
Definition at line 418 of file ShapeReconstruction.cpp.
ShapeReconstructionPtr omip::ShapeReconstruction::clone | ( | ) | const [inline] |
Definition at line 330 of file ShapeReconstruction.h.
virtual ShapeReconstruction* omip::ShapeReconstruction::doClone | ( | ) | const [inline, protected, virtual] |
Clone function.
Definition at line 343 of file ShapeReconstruction.h.
void ShapeReconstruction::generateMesh | ( | ) | [virtual] |
Definition at line 1218 of file ShapeReconstruction.cpp.
SRPointCloud::Ptr omip::ShapeReconstruction::getCurrentPointCloud | ( | ) | const [inline] |
Definition at line 200 of file ShapeReconstruction.h.
omip::RB_id_t omip::ShapeReconstruction::getId | ( | ) | const [inline] |
Definition at line 195 of file ShapeReconstruction.h.
SRPointCloud::Ptr omip::ShapeReconstruction::getMovedRigidBodyShapeExtDandC | ( | ) | const [inline] |
Definition at line 210 of file ShapeReconstruction.h.
SRPointCloud::Ptr omip::ShapeReconstruction::getRigidBodyShapeExtDandC | ( | ) | const [inline] |
Definition at line 205 of file ShapeReconstruction.h.
void ShapeReconstruction::getShapeModel | ( | omip_msgs::ShapeModelsPtr | shapes | ) | [virtual] |
Definition at line 1229 of file ShapeReconstruction.cpp.
void ShapeReconstruction::growSVRecursively | ( | uint32_t | label_sv_seed, |
std::vector< uint32_t > & | labels_extension, | ||
std::multimap< uint32_t, uint32_t > & | supervoxel_adjacency, | ||
std::vector< uint32_t > & | sv_containing_supporting_features, | ||
int & | distance_to_feature_sv, | ||
std::map< uint32_t, std::unordered_set< int > > & | labels_of_segments_to_extend | ||
) | [protected] |
Definition at line 876 of file ShapeReconstruction.cpp.
void ShapeReconstruction::initialize | ( | ) | [virtual] |
Definition at line 140 of file ShapeReconstruction.cpp.
void ShapeReconstruction::PublishMovedModelAndSegment | ( | const ros::Time | current_time, |
const geometry_msgs::TwistWithCovariance & | rb_transformation, | ||
rosbag::Bag & | bag, | ||
bool | bagOpen | ||
) | [virtual] |
Definition at line 1243 of file ShapeReconstruction.cpp.
void ShapeReconstruction::RemoveInconsistentPoints | ( | const SRPointCloud::Ptr & | pc_msg, |
const geometry_msgs::TwistWithCovariance & | rb_transformation | ||
) | [virtual] |
Definition at line 1283 of file ShapeReconstruction.cpp.
virtual void omip::ShapeReconstruction::setAccumulateChangeCandidates | ( | bool | b | ) | [inline, virtual] |
Definition at line 220 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setApproxVoxelGridLeafSize | ( | double | leaf_size | ) | [inline, virtual] |
Definition at line 315 of file ShapeReconstruction.h.
void ShapeReconstruction::setCameraInfo | ( | const sensor_msgs::CameraInfo & | camera_info | ) | [virtual] |
Definition at line 228 of file ShapeReconstruction.cpp.
virtual void omip::ShapeReconstruction::setColorChangesErodeSize | ( | double | color_changes_erode_size | ) | [inline, virtual] |
Definition at line 290 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setDepthFilling | ( | bool | depth_filling | ) | [inline, virtual] |
Definition at line 285 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setDetectStaticEnvironment | ( | bool | b | ) | [inline, virtual] |
Definition at line 215 of file ShapeReconstruction.h.
void omip::ShapeReconstruction::setEstimateSV | ( | bool | estimate_sv | ) | [inline] |
Definition at line 335 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setExtendToNeighborSV | ( | bool | extend_to_neighbor_sv | ) | [inline, virtual] |
Definition at line 260 of file ShapeReconstruction.h.
void ShapeReconstruction::setFullRGBDPCandRBT | ( | const SRPointCloud::Ptr & | pc_msg, |
const geometry_msgs::TwistWithCovariance & | rb_transformation | ||
) | [virtual] |
Definition at line 233 of file ShapeReconstruction.cpp.
void ShapeReconstruction::setInitialFullRGBDPCAndRBT | ( | const SRPointCloud::Ptr & | initial_pc_msg, |
const geometry_msgs::TwistWithCovariance & | rb_transformation_initial | ||
) | [virtual] |
Definition at line 113 of file ShapeReconstruction.cpp.
virtual void omip::ShapeReconstruction::setKNNMinRadius | ( | double | knn_min_radius | ) | [inline, virtual] |
Definition at line 240 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setLiveStream | ( | bool | live_stream | ) | [inline, virtual] |
Definition at line 305 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setMinColorChange | ( | int | min_color_change | ) | [inline, virtual] |
Definition at line 235 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setMinDepthChange | ( | double | b | ) | [inline, virtual] |
Definition at line 225 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setRadiusOutRemovalMinNeighbors | ( | int | ror_min_neighbors | ) | [inline, virtual] |
Definition at line 325 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setRadiusOutRemovalSearch | ( | double | ror_radius_search | ) | [inline, virtual] |
Definition at line 320 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setRBId | ( | omip::RB_id_t | rb_id | ) | [inline, virtual] |
Definition at line 310 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setRecordVideos | ( | bool | record_videos | ) | [inline, virtual] |
Definition at line 300 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setRemoveInconsistentPoints | ( | double | b | ) | [inline, virtual] |
Definition at line 230 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setSimilarityInH | ( | double | similarity_in_h | ) | [inline, virtual] |
Definition at line 265 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setSimilarityInNormal | ( | double | similarity_in_normal | ) | [inline, virtual] |
Definition at line 270 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setSuperVoxelClustersPtr | ( | std::map< uint32_t, pcl::Supervoxel< SRPoint >::Ptr > & | supervoxel_clusters | ) | [inline, virtual] |
Definition at line 255 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setSuperVoxelizerPtr | ( | boost::shared_ptr< pcl::SupervoxelClustering< SRPoint > > & | supervoxelizer | ) | [inline, virtual] |
Definition at line 250 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setSupportingFeatures | ( | pcl::PointCloud< pcl::PointXYZL >::Ptr | supporting_features | ) | [inline, virtual] |
Definition at line 275 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setSVMinNumberModelPixels | ( | int | min_number_model_pixels_in_sv | ) | [inline, virtual] |
Definition at line 245 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::setToInitial | ( | bool | to_initial | ) | [inline, virtual] |
Definition at line 295 of file ShapeReconstruction.h.
virtual void omip::ShapeReconstruction::useClusteredFeatures | ( | bool | use_clustered_features | ) | [inline, virtual] |
Definition at line 280 of file ShapeReconstruction.h.
cv::Mat omip::ShapeReconstruction::_acc_candidates_of_current [protected] |
Definition at line 449 of file ShapeReconstruction.h.
bool omip::ShapeReconstruction::_accumulate_change_candidates [protected] |
Definition at line 425 of file ShapeReconstruction.h.
pcl::ApproximateVoxelGrid<SRPoint> omip::ShapeReconstruction::_approximate_voxel_grid_filter [protected] |
Definition at line 505 of file ShapeReconstruction.h.
SRPointCloud::Ptr omip::ShapeReconstruction::_candidates [protected] |
Definition at line 496 of file ShapeReconstruction.h.
SRPointCloud::Ptr omip::ShapeReconstruction::_candidates_in_current [protected] |
Definition at line 497 of file ShapeReconstruction.h.
cv::Mat omip::ShapeReconstruction::_candidates_of_current [protected] |
Definition at line 451 of file ShapeReconstruction.h.
cv::Mat omip::ShapeReconstruction::_candidates_of_current_8u [protected] |
Definition at line 453 of file ShapeReconstruction.h.
cv::Mat omip::ShapeReconstruction::_candidates_of_previous [protected] |
Definition at line 452 of file ShapeReconstruction.h.
cv::Mat omip::ShapeReconstruction::_candidates_of_previous_8u [protected] |
Definition at line 454 of file ShapeReconstruction.h.
sensor_msgs::CameraInfo omip::ShapeReconstruction::_ci [protected] |
Definition at line 527 of file ShapeReconstruction.h.
double omip::ShapeReconstruction::_color_changes_erode_size [protected] |
Definition at line 437 of file ShapeReconstruction.h.
cv::Mat omip::ShapeReconstruction::_current_depth_mask [protected] |
Definition at line 455 of file ShapeReconstruction.h.
Definition at line 445 of file ShapeReconstruction.h.
Eigen::Matrix4d omip::ShapeReconstruction::_current_HTransform [protected] |
Definition at line 473 of file ShapeReconstruction.h.
Eigen::Matrix4d omip::ShapeReconstruction::_current_HTransform_inv [protected] |
Definition at line 474 of file ShapeReconstruction.h.
std::vector<std::vector<int > > omip::ShapeReconstruction::_current_k_indices [protected] |
Definition at line 479 of file ShapeReconstruction.h.
Eigen::Matrix4d omip::ShapeReconstruction::_current_to_previous_HTransform [protected] |
Definition at line 476 of file ShapeReconstruction.h.
Definition at line 472 of file ShapeReconstruction.h.
bool omip::ShapeReconstruction::_depth_filling [protected] |
Definition at line 423 of file ShapeReconstruction.h.
bool omip::ShapeReconstruction::_detect_static_environment [protected] |
Definition at line 424 of file ShapeReconstruction.h.
cv::Mat omip::ShapeReconstruction::_difference_in_depth [protected] |
Definition at line 450 of file ShapeReconstruction.h.
cv::Mat omip::ShapeReconstruction::_difference_in_depth_moved [protected] |
Definition at line 457 of file ShapeReconstruction.h.
bool omip::ShapeReconstruction::_estimate_supervoxels [protected] |
Definition at line 431 of file ShapeReconstruction.h.
bool omip::ShapeReconstruction::_extend_to_neighbor_sv [protected] |
Definition at line 428 of file ShapeReconstruction.h.
pcl::ExtractIndices<SRPoint> omip::ShapeReconstruction::_extractor [protected] |
Definition at line 485 of file ShapeReconstruction.h.
Definition at line 443 of file ShapeReconstruction.h.
pcl::search::Search<SRPoint>::Ptr omip::ShapeReconstruction::_knn [protected] |
Definition at line 487 of file ShapeReconstruction.h.
double omip::ShapeReconstruction::_knn_min_radius [protected] |
Definition at line 435 of file ShapeReconstruction.h.
double omip::ShapeReconstruction::_leaf_size [protected] |
Definition at line 506 of file ShapeReconstruction.h.
bool omip::ShapeReconstruction::_live_stream [protected] |
Definition at line 430 of file ShapeReconstruction.h.
int omip::ShapeReconstruction::_min_color_change [protected] |
Definition at line 434 of file ShapeReconstruction.h.
double omip::ShapeReconstruction::_min_depth_change [protected] |
Definition at line 433 of file ShapeReconstruction.h.
int omip::ShapeReconstruction::_min_number_model_pixels_in_sv [protected] |
Definition at line 436 of file ShapeReconstruction.h.
pcl::PointIndices::Ptr omip::ShapeReconstruction::_moving_pts_of_current_idx_color [protected] |
Definition at line 462 of file ShapeReconstruction.h.
pcl::PointIndices::Ptr omip::ShapeReconstruction::_moving_pts_of_current_idx_depth [protected] |
Definition at line 459 of file ShapeReconstruction.h.
pcl::PointIndices::Ptr omip::ShapeReconstruction::_moving_pts_of_previous_idx_color [protected] |
Definition at line 463 of file ShapeReconstruction.h.
pcl::PointIndices::Ptr omip::ShapeReconstruction::_moving_pts_of_previous_idx_depth [protected] |
Definition at line 460 of file ShapeReconstruction.h.
Definition at line 494 of file ShapeReconstruction.h.
pcl::PointIndices::Ptr omip::ShapeReconstruction::_occluded_pts_of_current_idx [protected] |
Definition at line 465 of file ShapeReconstruction.h.
Definition at line 490 of file ShapeReconstruction.h.
Definition at line 491 of file ShapeReconstruction.h.
pcl::PointIndices::Ptr omip::ShapeReconstruction::_out_of_view_pts_of_current_idx [protected] |
Definition at line 466 of file ShapeReconstruction.h.
cv::Mat omip::ShapeReconstruction::_previous_depth_mask [protected] |
Definition at line 455 of file ShapeReconstruction.h.
Definition at line 444 of file ShapeReconstruction.h.
Eigen::Matrix4d omip::ShapeReconstruction::_previous_HTransform [protected] |
Definition at line 469 of file ShapeReconstruction.h.
Eigen::Matrix4d omip::ShapeReconstruction::_previous_HTransform_inv [protected] |
Definition at line 470 of file ShapeReconstruction.h.
std::vector<std::vector<int > > omip::ShapeReconstruction::_previous_k_indices [protected] |
Definition at line 480 of file ShapeReconstruction.h.
std::vector<std::vector<int > > omip::ShapeReconstruction::_previous_k_indices_previous [protected] |
Definition at line 481 of file ShapeReconstruction.h.
Eigen::Matrix4d omip::ShapeReconstruction::_previous_to_current_HTransform [protected] |
Definition at line 477 of file ShapeReconstruction.h.
Definition at line 468 of file ShapeReconstruction.h.
pcl::RadiusOutlierRemoval<SRPoint> omip::ShapeReconstruction::_radius_outlier_removal [protected] |
Definition at line 500 of file ShapeReconstruction.h.
pcl::PointCloud<pcl::Normal>::Ptr omip::ShapeReconstruction::_rb_estimated_normals_pc_ptr [protected] |
Definition at line 510 of file ShapeReconstruction.h.
pcl::GreedyProjectionTriangulation<pcl::PointXYZRGBNormal>::Ptr omip::ShapeReconstruction::_rb_greedy_projection_triangulator_ptr [protected] |
Definition at line 514 of file ShapeReconstruction.h.
omip::RB_id_t omip::ShapeReconstruction::_rb_id [protected] |
Definition at line 416 of file ShapeReconstruction.h.
pcl::NormalEstimationOMP<omip::SRPoint, pcl::Normal>::Ptr omip::ShapeReconstruction::_rb_normal_estimator_ptr [protected] |
Definition at line 509 of file ShapeReconstruction.h.
vtkSmartPointer<vtkPolyData> omip::ShapeReconstruction::_rb_polygon_data_ptr [protected] |
Definition at line 516 of file ShapeReconstruction.h.
vtkSmartPointer<vtkSTLWriter> omip::ShapeReconstruction::_rb_polygon_writer_ptr [protected] |
Definition at line 517 of file ShapeReconstruction.h.
pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr omip::ShapeReconstruction::_rb_position_color_and_normals_pc_ptr [protected] |
Definition at line 511 of file ShapeReconstruction.h.
SRPointCloud::Ptr omip::ShapeReconstruction::_rb_segment [protected] |
Definition at line 420 of file ShapeReconstruction.h.
Definition at line 492 of file ShapeReconstruction.h.
SRPointCloud::Ptr omip::ShapeReconstruction::_rb_shape [protected] |
Definition at line 418 of file ShapeReconstruction.h.
SRPointCloud::Ptr omip::ShapeReconstruction::_rb_shape_in_current_frame [protected] |
Definition at line 419 of file ShapeReconstruction.h.
Definition at line 489 of file ShapeReconstruction.h.
pcl::search::KdTree<omip::SRPoint>::Ptr omip::ShapeReconstruction::_rb_tree_for_normal_estimation_ptr [protected] |
Definition at line 512 of file ShapeReconstruction.h.
pcl::search::KdTree<pcl::PointXYZRGBNormal>::Ptr omip::ShapeReconstruction::_rb_tree_for_triangulation_ptr [protected] |
Definition at line 513 of file ShapeReconstruction.h.
pcl::PolygonMesh::Ptr omip::ShapeReconstruction::_rb_triangulated_mesh_ptr [protected] |
Definition at line 515 of file ShapeReconstruction.h.
bool omip::ShapeReconstruction::_record_videos [protected] |
Definition at line 427 of file ShapeReconstruction.h.
bool omip::ShapeReconstruction::_remove_inconsistent_points [protected] |
Definition at line 426 of file ShapeReconstruction.h.
pcl::RangeImagePlanar::Ptr omip::ShapeReconstruction::_rip_temp [protected] |
Definition at line 447 of file ShapeReconstruction.h.
int omip::ShapeReconstruction::_ror_min_neighbors [protected] |
Definition at line 501 of file ShapeReconstruction.h.
double omip::ShapeReconstruction::_ror_radius_search [protected] |
Definition at line 502 of file ShapeReconstruction.h.
double omip::ShapeReconstruction::_similarity_in_h [protected] |
Definition at line 439 of file ShapeReconstruction.h.
double omip::ShapeReconstruction::_similarity_in_normal [protected] |
Definition at line 440 of file ShapeReconstruction.h.
std::vector<std::vector<float > > omip::ShapeReconstruction::_sqrt_dist [protected] |
Definition at line 482 of file ShapeReconstruction.h.
std::map<uint32_t, pcl::Supervoxel<SRPoint>::Ptr >* omip::ShapeReconstruction::_supervoxel_clusters_ptr [protected] |
Definition at line 524 of file ShapeReconstruction.h.
boost::shared_ptr<pcl::SupervoxelClustering<SRPoint> >* omip::ShapeReconstruction::_supervoxelizer_ptr_ptr [protected] |
Definition at line 523 of file ShapeReconstruction.h.
pcl::PointCloud<pcl::PointXYZL>::Ptr omip::ShapeReconstruction::_supporting_features [protected] |
Definition at line 529 of file ShapeReconstruction.h.
int omip::ShapeReconstruction::_t [protected] |
Definition at line 441 of file ShapeReconstruction.h.
double omip::ShapeReconstruction::_timestamp_color [protected] |
Definition at line 438 of file ShapeReconstruction.h.
bool omip::ShapeReconstruction::_to_initial [protected] |
Definition at line 422 of file ShapeReconstruction.h.
bool omip::ShapeReconstruction::_use_clustered_features [protected] |
Definition at line 429 of file ShapeReconstruction.h.
rosbag::Bag omip::ShapeReconstruction::_videos [protected] |
Definition at line 520 of file ShapeReconstruction.h.