Public Member Functions | Protected Member Functions | Protected Attributes | Private Types
omip::ShapeReconstructionNode Class Reference

#include <ShapeReconstructionNode.h>

List of all members.

Public Member Functions

virtual void CameraInfoCallback (const sensor_msgs::CameraInfoConstPtr &ci_msg)
virtual bool generateMeshes (shape_reconstruction::generate_meshes::Request &request, shape_reconstruction::generate_meshes::Response &response)
virtual bool isActive () const
virtual void measurementCallbackWithClusteredFeatures (const sensor_msgs::PointCloud2ConstPtr &pc_msg, const boost::shared_ptr< omip::rbt_state_t const > &poses_and_vels, const sensor_msgs::PointCloud2ConstPtr &features_pc)
virtual void ReadRosBag ()
virtual void setSVColorImportance (double color_importance)
virtual void setSVNormalImportance (double normal_importance)
virtual void setSVSeedResolution (double seed_resolution)
virtual void setSVSpatialImportance (double spatial_importance)
virtual void setSVVisualization (bool visualization_sv)
virtual void setSVVoxelResolution (double voxel_resolution)
 ShapeReconstructionNode ()
virtual void TrackerQuitCallback (const std_msgs::EmptyConstPtr &empty)
virtual ~ShapeReconstructionNode ()

Protected Member Functions

virtual void _AdvanceFeatureTracker ()
virtual void _CollectAndPublishShapeModels ()
omip::ShapeReconstructionPtr _createNewShapeReconstruction ()
virtual void _EstimateSupervoxels ()
virtual void _GenerateMesh (const omip::SRPointCloud::Ptr &pc_source, std::string shape_file_prefix)
virtual void _InitResultRosbag ()
template<class T >
bool getROSParameter (std::string param_name, T &param_container)

Protected Attributes

bool _active
ros::Publisher _advance_feature_tracker_pub
sensor_msgs::CameraInfo _ci
ros::Subscriber _ci_sub
pcl::PointCloud
< pcl::PointXYZL >::Ptr 
_clustered_feats
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
_clustered_feats_subscriber
double _color_importance
ros::Time _current_measurement_time
SRPointCloud::Ptr _current_pc
SRPointCloud::Ptr _current_pc_down
SRPointCloud::Ptr _current_pc_without_nans
bool _detect_static_environment
bool _estimate_sv
pcl::ExtractIndices
< pcl::PointXYZL > 
_extractor_cf
int _frame_ctr
bool _manually_advance_after_processing
int _max_rb
ros::ServiceServer _mesh_generator_srv
ros::NodeHandle _node_handle
ros::Subscriber _node_quit_subscriber
double _normal_importance
std::vector< int > _not_nan_indices
message_filters::Subscriber
< omip::rbt_state_t
_poses_and_vels_subscriber
ros::Time _previous_measurement_time
double _processing_interval
bool _publish_shapes_in_each_frame
std::map< omip::RB_id_t,
omip::ShapeReconstructionPtr > 
_rb_shapes
ros::Publisher _rbshapes_combined_publisher
bool _record_result_bag
bool _refine_shapes_in_each_frame
rosbag::Bag _result_bag
bool _result_bag_open
std::string _result_bag_path
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
_rgbd_pc_subscriber
pcl::PointCloud< pcl::Normal >::Ptr _se_estimated_normals_pc_ptr
pcl::GreedyProjectionTriangulation
< pcl::PointXYZRGBNormal >
::Ptr 
_se_greedy_projection_triangulator_ptr
pcl::NormalEstimationOMP
< omip::SRPoint, pcl::Normal >
::Ptr 
_se_normal_estimator_ptr
vtkSmartPointer< vtkPolyData > _se_polygon_data_ptr
vtkSmartPointer< vtkSTLWriter > _se_polygon_writer_ptr
pcl::PointCloud
< pcl::PointXYZRGBNormal >
::Ptr 
_se_position_color_and_normals_pc_ptr
pcl::search::KdTree
< omip::SRPoint >::Ptr 
_se_tree_for_normal_estimation_ptr
pcl::search::KdTree
< pcl::PointXYZRGBNormal >
::Ptr 
_se_tree_for_triangulation_ptr
pcl::PolygonMesh::Ptr _se_triangulated_mesh_ptr
double _seed_resolution
pcl::search::Search
< omip::SRPoint >::Ptr 
_set_knn_ptr
ros::Publisher _shape_models_ext_d_and_c_pub
double _spatial_importance
SRPointCloud::Ptr _static_env_ext_d_and_c_in_current_frame
ros::Publisher _static_environment_ext_d_and_c_pub
std::map< uint32_t,
pcl::Supervoxel< SRPoint >
::Ptr > 
_supervoxel_clusters
boost::shared_ptr
< pcl::SupervoxelClustering
< SRPoint > > 
_supervoxelizer
bool _sv_estimated
message_filters::Synchronizer
< SRSyncPolicy > * 
_synchronizer
message_filters::Synchronizer
< SRSyncPolicyWithClusteredFeatures > * 
_synchronizer_with_clustered_feats
rosbag::Bag _video_bag
bool _visualization_sv
double _voxel_resolution

Private Types

typedef std::map
< omip::RB_id_t,
omip::ShapeReconstructionPtr > 
shape_reconstructors_map_t
typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::PointCloud2,
omip::rbt_state_t
SRSyncPolicy
typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::PointCloud2,
omip::rbt_state_t,
rbt_measurement_ros_t
SRSyncPolicyWithClusteredFeatures

Detailed Description

Definition at line 120 of file ShapeReconstructionNode.h.


Member Typedef Documentation

typedef std::map<omip::RB_id_t, omip::ShapeReconstructionPtr > omip::ShapeReconstructionNode::shape_reconstructors_map_t [private]

Definition at line 128 of file ShapeReconstructionNode.h.

Definition at line 123 of file ShapeReconstructionNode.h.

Definition at line 126 of file ShapeReconstructionNode.h.


Constructor & Destructor Documentation

Constructor

For SE shape, defined as PC - RB (it is wrong if there are other RBs)

Definition at line 36 of file ShapeReconstructionNode.cpp.

Destructor

Definition at line 171 of file ShapeReconstructionNode.cpp.


Member Function Documentation

void ShapeReconstructionNode::_AdvanceFeatureTracker ( ) [protected, virtual]

Definition at line 789 of file ShapeReconstructionNode.cpp.

Definition at line 527 of file ShapeReconstructionNode.cpp.

omip::ShapeReconstructionPtr ShapeReconstructionNode::_createNewShapeReconstruction ( ) [protected]

Definition at line 193 of file ShapeReconstructionNode.cpp.

void ShapeReconstructionNode::_EstimateSupervoxels ( ) [protected, virtual]

Definition at line 619 of file ShapeReconstructionNode.cpp.

void ShapeReconstructionNode::_GenerateMesh ( const omip::SRPointCloud::Ptr &  pc_source,
std::string  shape_file_prefix 
) [protected, virtual]

Definition at line 683 of file ShapeReconstructionNode.cpp.

void ShapeReconstructionNode::_InitResultRosbag ( ) [protected, virtual]

Definition at line 724 of file ShapeReconstructionNode.cpp.

void ShapeReconstructionNode::CameraInfoCallback ( const sensor_msgs::CameraInfoConstPtr &  ci_msg) [virtual]

Definition at line 179 of file ShapeReconstructionNode.cpp.

bool ShapeReconstructionNode::generateMeshes ( shape_reconstruction::generate_meshes::Request &  request,
shape_reconstruction::generate_meshes::Response &  response 
) [virtual]

Definition at line 660 of file ShapeReconstructionNode.cpp.

template<class T >
bool omip::ShapeReconstructionNode::getROSParameter ( std::string  param_name,
T param_container 
) [inline, protected]

Definition at line 273 of file ShapeReconstructionNode.h.

virtual bool omip::ShapeReconstructionNode::isActive ( ) const [inline, virtual]

Definition at line 176 of file ShapeReconstructionNode.h.

void ShapeReconstructionNode::measurementCallbackWithClusteredFeatures ( const sensor_msgs::PointCloud2ConstPtr &  pc_msg,
const boost::shared_ptr< omip::rbt_state_t const > &  poses_and_vels,
const sensor_msgs::PointCloud2ConstPtr &  features_pc 
) [virtual]

Definition at line 303 of file ShapeReconstructionNode.cpp.

Definition at line 523 of file ShapeReconstructionNode.cpp.

virtual void omip::ShapeReconstructionNode::setSVColorImportance ( double  color_importance) [inline, virtual]

Definition at line 160 of file ShapeReconstructionNode.h.

virtual void omip::ShapeReconstructionNode::setSVNormalImportance ( double  normal_importance) [inline, virtual]

Definition at line 168 of file ShapeReconstructionNode.h.

virtual void omip::ShapeReconstructionNode::setSVSeedResolution ( double  seed_resolution) [inline, virtual]

Definition at line 156 of file ShapeReconstructionNode.h.

virtual void omip::ShapeReconstructionNode::setSVSpatialImportance ( double  spatial_importance) [inline, virtual]

Definition at line 164 of file ShapeReconstructionNode.h.

virtual void omip::ShapeReconstructionNode::setSVVisualization ( bool  visualization_sv) [inline, virtual]

Definition at line 172 of file ShapeReconstructionNode.h.

virtual void omip::ShapeReconstructionNode::setSVVoxelResolution ( double  voxel_resolution) [inline, virtual]

Definition at line 152 of file ShapeReconstructionNode.h.

void ShapeReconstructionNode::TrackerQuitCallback ( const std_msgs::EmptyConstPtr &  empty) [virtual]

Definition at line 797 of file ShapeReconstructionNode.cpp.


Member Data Documentation

Definition at line 196 of file ShapeReconstructionNode.h.

Definition at line 214 of file ShapeReconstructionNode.h.

sensor_msgs::CameraInfo omip::ShapeReconstructionNode::_ci [protected]

Definition at line 266 of file ShapeReconstructionNode.h.

Definition at line 265 of file ShapeReconstructionNode.h.

Definition at line 268 of file ShapeReconstructionNode.h.

Definition at line 218 of file ShapeReconstructionNode.h.

Definition at line 253 of file ShapeReconstructionNode.h.

Definition at line 209 of file ShapeReconstructionNode.h.

SRPointCloud::Ptr omip::ShapeReconstructionNode::_current_pc [protected]

Definition at line 223 of file ShapeReconstructionNode.h.

SRPointCloud::Ptr omip::ShapeReconstructionNode::_current_pc_down [protected]

Definition at line 224 of file ShapeReconstructionNode.h.

Definition at line 225 of file ShapeReconstructionNode.h.

Definition at line 205 of file ShapeReconstructionNode.h.

Definition at line 261 of file ShapeReconstructionNode.h.

Definition at line 270 of file ShapeReconstructionNode.h.

Definition at line 198 of file ShapeReconstructionNode.h.

Definition at line 248 of file ShapeReconstructionNode.h.

Definition at line 201 of file ShapeReconstructionNode.h.

Definition at line 221 of file ShapeReconstructionNode.h.

Definition at line 210 of file ShapeReconstructionNode.h.

Definition at line 215 of file ShapeReconstructionNode.h.

Definition at line 255 of file ShapeReconstructionNode.h.

Definition at line 227 of file ShapeReconstructionNode.h.

Definition at line 217 of file ShapeReconstructionNode.h.

Definition at line 208 of file ShapeReconstructionNode.h.

Definition at line 203 of file ShapeReconstructionNode.h.

Definition at line 206 of file ShapeReconstructionNode.h.

std::map<omip::RB_id_t,omip::ShapeReconstructionPtr > omip::ShapeReconstructionNode::_rb_shapes [protected]

Definition at line 199 of file ShapeReconstructionNode.h.

Definition at line 211 of file ShapeReconstructionNode.h.

Definition at line 242 of file ShapeReconstructionNode.h.

Definition at line 207 of file ShapeReconstructionNode.h.

Definition at line 244 of file ShapeReconstructionNode.h.

Definition at line 246 of file ShapeReconstructionNode.h.

Definition at line 243 of file ShapeReconstructionNode.h.

Definition at line 216 of file ShapeReconstructionNode.h.

Definition at line 233 of file ShapeReconstructionNode.h.

pcl::GreedyProjectionTriangulation<pcl::PointXYZRGBNormal>::Ptr omip::ShapeReconstructionNode::_se_greedy_projection_triangulator_ptr [protected]

Definition at line 237 of file ShapeReconstructionNode.h.

Definition at line 232 of file ShapeReconstructionNode.h.

vtkSmartPointer<vtkPolyData> omip::ShapeReconstructionNode::_se_polygon_data_ptr [protected]

Definition at line 239 of file ShapeReconstructionNode.h.

vtkSmartPointer<vtkSTLWriter> omip::ShapeReconstructionNode::_se_polygon_writer_ptr [protected]

Definition at line 240 of file ShapeReconstructionNode.h.

Definition at line 234 of file ShapeReconstructionNode.h.

pcl::search::KdTree<omip::SRPoint>::Ptr omip::ShapeReconstructionNode::_se_tree_for_normal_estimation_ptr [protected]

Definition at line 235 of file ShapeReconstructionNode.h.

pcl::search::KdTree<pcl::PointXYZRGBNormal>::Ptr omip::ShapeReconstructionNode::_se_tree_for_triangulation_ptr [protected]

Definition at line 236 of file ShapeReconstructionNode.h.

Definition at line 238 of file ShapeReconstructionNode.h.

Definition at line 252 of file ShapeReconstructionNode.h.

pcl::search::Search<omip::SRPoint>::Ptr omip::ShapeReconstructionNode::_set_knn_ptr [protected]

Definition at line 230 of file ShapeReconstructionNode.h.

Definition at line 263 of file ShapeReconstructionNode.h.

Definition at line 254 of file ShapeReconstructionNode.h.

Definition at line 229 of file ShapeReconstructionNode.h.

Definition at line 213 of file ShapeReconstructionNode.h.

std::map<uint32_t, pcl::Supervoxel<SRPoint>::Ptr > omip::ShapeReconstructionNode::_supervoxel_clusters [protected]

Definition at line 257 of file ShapeReconstructionNode.h.

boost::shared_ptr<pcl::SupervoxelClustering<SRPoint> > omip::ShapeReconstructionNode::_supervoxelizer [protected]

Definition at line 256 of file ShapeReconstructionNode.h.

Definition at line 260 of file ShapeReconstructionNode.h.

Definition at line 219 of file ShapeReconstructionNode.h.

Definition at line 220 of file ShapeReconstructionNode.h.

Definition at line 245 of file ShapeReconstructionNode.h.

Definition at line 259 of file ShapeReconstructionNode.h.

Definition at line 251 of file ShapeReconstructionNode.h.


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


shape_reconstruction
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:41:09