#include <ShapeReconstructionNode.h>
Definition at line 120 of file ShapeReconstructionNode.h.
typedef std::map<omip::RB_id_t, omip::ShapeReconstructionPtr > omip::ShapeReconstructionNode::shape_reconstructors_map_t [private] |
Definition at line 128 of file ShapeReconstructionNode.h.
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, omip::rbt_state_t> omip::ShapeReconstructionNode::SRSyncPolicy [private] |
Definition at line 123 of file ShapeReconstructionNode.h.
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, omip::rbt_state_t, rbt_measurement_ros_t> omip::ShapeReconstructionNode::SRSyncPolicyWithClusteredFeatures [private] |
Definition at line 126 of file ShapeReconstructionNode.h.
Constructor
For SE shape, defined as PC - RB (it is wrong if there are other RBs)
Definition at line 36 of file ShapeReconstructionNode.cpp.
ShapeReconstructionNode::~ShapeReconstructionNode | ( | ) | [virtual] |
Destructor
Definition at line 171 of file ShapeReconstructionNode.cpp.
void ShapeReconstructionNode::_AdvanceFeatureTracker | ( | ) | [protected, virtual] |
Definition at line 789 of file ShapeReconstructionNode.cpp.
void ShapeReconstructionNode::_CollectAndPublishShapeModels | ( | ) | [protected, virtual] |
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.
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.
void ShapeReconstructionNode::ReadRosBag | ( | ) | [virtual] |
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.
bool omip::ShapeReconstructionNode::_active [protected] |
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.
pcl::PointCloud<pcl::PointXYZL>::Ptr omip::ShapeReconstructionNode::_clustered_feats [protected] |
Definition at line 268 of file ShapeReconstructionNode.h.
message_filters::Subscriber<sensor_msgs::PointCloud2> omip::ShapeReconstructionNode::_clustered_feats_subscriber [protected] |
Definition at line 218 of file ShapeReconstructionNode.h.
double omip::ShapeReconstructionNode::_color_importance [protected] |
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.
SRPointCloud::Ptr omip::ShapeReconstructionNode::_current_pc_without_nans [protected] |
Definition at line 225 of file ShapeReconstructionNode.h.
bool omip::ShapeReconstructionNode::_detect_static_environment [protected] |
Definition at line 205 of file ShapeReconstructionNode.h.
bool omip::ShapeReconstructionNode::_estimate_sv [protected] |
Definition at line 261 of file ShapeReconstructionNode.h.
pcl::ExtractIndices<pcl::PointXYZL> omip::ShapeReconstructionNode::_extractor_cf [protected] |
Definition at line 270 of file ShapeReconstructionNode.h.
int omip::ShapeReconstructionNode::_frame_ctr [protected] |
Definition at line 198 of file ShapeReconstructionNode.h.
bool omip::ShapeReconstructionNode::_manually_advance_after_processing [protected] |
Definition at line 248 of file ShapeReconstructionNode.h.
int omip::ShapeReconstructionNode::_max_rb [protected] |
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.
double omip::ShapeReconstructionNode::_normal_importance [protected] |
Definition at line 255 of file ShapeReconstructionNode.h.
std::vector<int> omip::ShapeReconstructionNode::_not_nan_indices [protected] |
Definition at line 227 of file ShapeReconstructionNode.h.
message_filters::Subscriber<omip::rbt_state_t> omip::ShapeReconstructionNode::_poses_and_vels_subscriber [protected] |
Definition at line 217 of file ShapeReconstructionNode.h.
Definition at line 208 of file ShapeReconstructionNode.h.
double omip::ShapeReconstructionNode::_processing_interval [protected] |
Definition at line 203 of file ShapeReconstructionNode.h.
bool omip::ShapeReconstructionNode::_publish_shapes_in_each_frame [protected] |
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.
bool omip::ShapeReconstructionNode::_record_result_bag [protected] |
Definition at line 242 of file ShapeReconstructionNode.h.
bool omip::ShapeReconstructionNode::_refine_shapes_in_each_frame [protected] |
Definition at line 207 of file ShapeReconstructionNode.h.
Definition at line 244 of file ShapeReconstructionNode.h.
bool omip::ShapeReconstructionNode::_result_bag_open [protected] |
Definition at line 246 of file ShapeReconstructionNode.h.
std::string omip::ShapeReconstructionNode::_result_bag_path [protected] |
Definition at line 243 of file ShapeReconstructionNode.h.
message_filters::Subscriber<sensor_msgs::PointCloud2> omip::ShapeReconstructionNode::_rgbd_pc_subscriber [protected] |
Definition at line 216 of file ShapeReconstructionNode.h.
pcl::PointCloud<pcl::Normal>::Ptr omip::ShapeReconstructionNode::_se_estimated_normals_pc_ptr [protected] |
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.
pcl::NormalEstimationOMP<omip::SRPoint, pcl::Normal>::Ptr omip::ShapeReconstructionNode::_se_normal_estimator_ptr [protected] |
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.
pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr omip::ShapeReconstructionNode::_se_position_color_and_normals_pc_ptr [protected] |
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.
pcl::PolygonMesh::Ptr omip::ShapeReconstructionNode::_se_triangulated_mesh_ptr [protected] |
Definition at line 238 of file ShapeReconstructionNode.h.
double omip::ShapeReconstructionNode::_seed_resolution [protected] |
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.
double omip::ShapeReconstructionNode::_spatial_importance [protected] |
Definition at line 254 of file ShapeReconstructionNode.h.
SRPointCloud::Ptr omip::ShapeReconstructionNode::_static_env_ext_d_and_c_in_current_frame [protected] |
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.
bool omip::ShapeReconstructionNode::_sv_estimated [protected] |
Definition at line 260 of file ShapeReconstructionNode.h.
message_filters::Synchronizer<SRSyncPolicy>* omip::ShapeReconstructionNode::_synchronizer [protected] |
Definition at line 219 of file ShapeReconstructionNode.h.
message_filters::Synchronizer<SRSyncPolicyWithClusteredFeatures>* omip::ShapeReconstructionNode::_synchronizer_with_clustered_feats [protected] |
Definition at line 220 of file ShapeReconstructionNode.h.
rosbag::Bag omip::ShapeReconstructionNode::_video_bag [protected] |
Definition at line 245 of file ShapeReconstructionNode.h.
bool omip::ShapeReconstructionNode::_visualization_sv [protected] |
Definition at line 259 of file ShapeReconstructionNode.h.
double omip::ShapeReconstructionNode::_voxel_resolution [protected] |
Definition at line 251 of file ShapeReconstructionNode.h.