Defines | Functions | Variables
vosch_tools.h File Reference
#include <sys/time.h>
#include "c3_hlac/c3_hlac.h"
#include "c3_hlac/c3_hlac_tools.h"
#include <pcl_cloud_algos/pcl_cloud_algos_point_types.h>
#include <pcl/point_types.h>
#include <pcl/features/feature.h>
#include <pcl/io/pcd_io.h>
#include <pcl/features/normal_3d.h>
#include <pcl/features/rsd.h>
#include <vosch/vosch_tools.hpp>
Include dependency graph for vosch_tools.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Defines

#define CYLINDER   2
#define EDGE   4
#define EMPTY   5
#define NOISE   0
#define NR_CLASS   5
#define NR_DIV   7
#define PLANE   1
#define SPHERE   3

Functions

template<typename T1 , typename T2 >
void computeNormal (pcl::PointCloud< T1 > input_cloud, pcl::PointCloud< T2 > &output_cloud)
 compute normals
const std::vector< float > concVector (const std::vector< float > v1, const std::vector< float > v2)
 concatenate
template<typename PointT >
Eigen::Vector3i extractConVOSCH (pcl::VoxelGrid< PointT > grid, pcl::PointCloud< PointT > cloud, pcl::PointCloud< PointT > cloud_downsampled, std::vector< std::vector< float > > &feature, int color_threshold_r, int color_threshold_g, int color_threshold_b, const float voxel_size, const int subdivision_size=0, const int offset_x=0, const int offset_y=0, const int offset_z=0, const bool is_normalize=false)
 ConVOSCH.
template<typename PointT >
void extractConVOSCH (pcl::VoxelGrid< PointT > grid, pcl::PointCloud< PointT > cloud, pcl::PointCloud< PointT > cloud_downsampled, std::vector< float > &feature, int color_threshold_r, int color_threshold_g, int color_threshold_b, const float voxel_size, const int subdivision_size=0, const int offset_x=0, const int offset_y=0, const int offset_z=0)
template<typename T >
Eigen::Vector3i extractGRSDSignature21 (pcl::VoxelGrid< T > grid, pcl::PointCloud< T > cloud, pcl::PointCloud< T > cloud_downsampled, std::vector< std::vector< float > > &feature, const float voxel_size, const int subdivision_size=0, const int offset_x=0, const int offset_y=0, const int offset_z=0, const bool is_normalize=false)
 extract - GRSD -
template<typename T >
void extractGRSDSignature21 (pcl::VoxelGrid< T > grid, pcl::PointCloud< T > cloud, pcl::PointCloud< T > cloud_downsampled, std::vector< float > &feature, const float voxel_size, const bool is_normalize=false)
template<typename T >
Eigen::Vector3i extractGRSDSignature325 (pcl::VoxelGrid< T > grid, pcl::PointCloud< T > cloud, pcl::PointCloud< T > cloud_downsampled, std::vector< std::vector< float > > &feature, const float voxel_size, const int subdivision_size=0, const int offset_x=0, const int offset_y=0, const int offset_z=0, const bool is_normalize=false)
 extract - rotation-variant GRSD -
template<typename T >
void extractGRSDSignature325 (pcl::VoxelGrid< T > grid, pcl::PointCloud< T > cloud, pcl::PointCloud< T > cloud_downsampled, std::vector< float > &feature, const float voxel_size, const bool is_normalize=false)
template<typename T >
Eigen::Vector3i extractPlusGRSDSignature110 (pcl::VoxelGrid< T > grid, pcl::PointCloud< T > cloud, pcl::PointCloud< T > cloud_downsampled, std::vector< std::vector< float > > &feature, const float voxel_size, const int subdivision_size=0, const int offset_x=0, const int offset_y=0, const int offset_z=0, const bool is_normalize=false)
 extract - PlusGRSD -
template<typename T >
void extractPlusGRSDSignature110 (pcl::VoxelGrid< T > grid, pcl::PointCloud< T > cloud, pcl::PointCloud< T > cloud_downsampled, std::vector< float > &feature, const float voxel_size, const bool is_normalize=false)
template<typename PointT >
Eigen::Vector3i extractVOSCH (pcl::VoxelGrid< PointT > grid, pcl::PointCloud< PointT > cloud, pcl::PointCloud< PointT > cloud_downsampled, std::vector< std::vector< float > > &feature, int color_threshold_r, int color_threshold_g, int color_threshold_b, const float voxel_size, const int subdivision_size=0, const int offset_x=0, const int offset_y=0, const int offset_z=0, const bool is_normalize=false)
 VOSCH.
template<typename PointT >
void extractVOSCH (pcl::VoxelGrid< PointT > grid, pcl::PointCloud< PointT > cloud, pcl::PointCloud< PointT > cloud_downsampled, std::vector< float > &feature, int color_threshold_r, int color_threshold_g, int color_threshold_b, const float voxel_size, const int subdivision_size=0, const int offset_x=0, const int offset_y=0, const int offset_z=0)
int getType (float min_radius, float max_radius)
 function for GRSD
template<typename T >
bool readPoints (const char *name, pcl::PointCloud< T > &cloud)
 read

Variables

const int GRSD_LARGE_DIM = 325
const double max_min_radius_diff_ = 0.02
const double max_radius_noise_ = 0.050
const double min_radius_edge_ = 0.030
const double min_radius_noise_ = 0.030
const double min_radius_plane_ = 0.066
const float NORMALIZE_GRSD = 20.0 / 26
const double normals_radius_search = 0.02
const double rsd_radius_search = 0.01

Define Documentation

#define CYLINDER   2

Definition at line 15 of file vosch_tools.h.

#define EDGE   4

Definition at line 17 of file vosch_tools.h.

#define EMPTY   5

Definition at line 18 of file vosch_tools.h.

#define NOISE   0

Definition at line 13 of file vosch_tools.h.

#define NR_CLASS   5

Definition at line 12 of file vosch_tools.h.

#define NR_DIV   7

Definition at line 20 of file vosch_tools.h.

#define PLANE   1

Definition at line 14 of file vosch_tools.h.

#define SPHERE   3

Definition at line 16 of file vosch_tools.h.


Function Documentation

template<typename T1 , typename T2 >
void computeNormal ( pcl::PointCloud< T1 >  input_cloud,
pcl::PointCloud< T2 > &  output_cloud 
)

compute normals

Definition at line 18 of file vosch_tools.hpp.

const std::vector<float> concVector ( const std::vector< float >  v1,
const std::vector< float >  v2 
)

concatenate

Definition at line 613 of file vosch_tools.hpp.

template<typename PointT >
Eigen::Vector3i extractConVOSCH ( pcl::VoxelGrid< PointT grid,
pcl::PointCloud< PointT cloud,
pcl::PointCloud< PointT cloud_downsampled,
std::vector< std::vector< float > > &  feature,
int  color_threshold_r,
int  color_threshold_g,
int  color_threshold_b,
const float  voxel_size,
const int  subdivision_size = 0,
const int  offset_x = 0,
const int  offset_y = 0,
const int  offset_z = 0,
const bool  is_normalize = false 
)

ConVOSCH.

Definition at line 644 of file vosch_tools.hpp.

template<typename PointT >
void extractConVOSCH ( pcl::VoxelGrid< PointT grid,
pcl::PointCloud< PointT cloud,
pcl::PointCloud< PointT cloud_downsampled,
std::vector< float > &  feature,
int  color_threshold_r,
int  color_threshold_g,
int  color_threshold_b,
const float  voxel_size,
const int  subdivision_size = 0,
const int  offset_x = 0,
const int  offset_y = 0,
const int  offset_z = 0 
)

Definition at line 657 of file vosch_tools.hpp.

template<typename T >
Eigen::Vector3i extractGRSDSignature21 ( pcl::VoxelGrid< T >  grid,
pcl::PointCloud< T >  cloud,
pcl::PointCloud< T >  cloud_downsampled,
std::vector< std::vector< float > > &  feature,
const float  voxel_size,
const int  subdivision_size = 0,
const int  offset_x = 0,
const int  offset_y = 0,
const int  offset_z = 0,
const bool  is_normalize = false 
)

extract - GRSD -

Definition at line 71 of file vosch_tools.hpp.

template<typename T >
void extractGRSDSignature21 ( pcl::VoxelGrid< T >  grid,
pcl::PointCloud< T >  cloud,
pcl::PointCloud< T >  cloud_downsampled,
std::vector< float > &  feature,
const float  voxel_size,
const bool  is_normalize = false 
)

Definition at line 235 of file vosch_tools.hpp.

template<typename T >
Eigen::Vector3i extractGRSDSignature325 ( pcl::VoxelGrid< T >  grid,
pcl::PointCloud< T >  cloud,
pcl::PointCloud< T >  cloud_downsampled,
std::vector< std::vector< float > > &  feature,
const float  voxel_size,
const int  subdivision_size = 0,
const int  offset_x = 0,
const int  offset_y = 0,
const int  offset_z = 0,
const bool  is_normalize = false 
)

extract - rotation-variant GRSD -

Definition at line 244 of file vosch_tools.hpp.

template<typename T >
void extractGRSDSignature325 ( pcl::VoxelGrid< T >  grid,
pcl::PointCloud< T >  cloud,
pcl::PointCloud< T >  cloud_downsampled,
std::vector< float > &  feature,
const float  voxel_size,
const bool  is_normalize = false 
)

Definition at line 390 of file vosch_tools.hpp.

template<typename T >
Eigen::Vector3i extractPlusGRSDSignature110 ( pcl::VoxelGrid< T >  grid,
pcl::PointCloud< T >  cloud,
pcl::PointCloud< T >  cloud_downsampled,
std::vector< std::vector< float > > &  feature,
const float  voxel_size,
const int  subdivision_size = 0,
const int  offset_x = 0,
const int  offset_y = 0,
const int  offset_z = 0,
const bool  is_normalize = false 
)

extract - PlusGRSD -

Definition at line 399 of file vosch_tools.hpp.

template<typename T >
void extractPlusGRSDSignature110 ( pcl::VoxelGrid< T >  grid,
pcl::PointCloud< T >  cloud,
pcl::PointCloud< T >  cloud_downsampled,
std::vector< float > &  feature,
const float  voxel_size,
const bool  is_normalize = false 
)

Definition at line 605 of file vosch_tools.hpp.

template<typename PointT >
Eigen::Vector3i extractVOSCH ( pcl::VoxelGrid< PointT grid,
pcl::PointCloud< PointT cloud,
pcl::PointCloud< PointT cloud_downsampled,
std::vector< std::vector< float > > &  feature,
int  color_threshold_r,
int  color_threshold_g,
int  color_threshold_b,
const float  voxel_size,
const int  subdivision_size = 0,
const int  offset_x = 0,
const int  offset_y = 0,
const int  offset_z = 0,
const bool  is_normalize = false 
)

VOSCH.

Definition at line 622 of file vosch_tools.hpp.

template<typename PointT >
void extractVOSCH ( pcl::VoxelGrid< PointT grid,
pcl::PointCloud< PointT cloud,
pcl::PointCloud< PointT cloud_downsampled,
std::vector< float > &  feature,
int  color_threshold_r,
int  color_threshold_g,
int  color_threshold_b,
const float  voxel_size,
const int  subdivision_size = 0,
const int  offset_x = 0,
const int  offset_y = 0,
const int  offset_z = 0 
)

Definition at line 635 of file vosch_tools.hpp.

int getType ( float  min_radius,
float  max_radius 
)

function for GRSD

Definition at line 44 of file vosch_tools.hpp.

template<typename T >
bool readPoints ( const char *  name,
pcl::PointCloud< T > &  cloud 
)

read

Definition at line 4 of file vosch_tools.hpp.


Variable Documentation

const int GRSD_LARGE_DIM = 325

Definition at line 35 of file vosch_tools.h.

const double max_min_radius_diff_ = 0.02

Definition at line 27 of file vosch_tools.h.

const double max_radius_noise_ = 0.050

Definition at line 26 of file vosch_tools.h.

const double min_radius_edge_ = 0.030

Definition at line 28 of file vosch_tools.h.

const double min_radius_noise_ = 0.030

Definition at line 26 of file vosch_tools.h.

const double min_radius_plane_ = 0.066

Definition at line 25 of file vosch_tools.h.

const float NORMALIZE_GRSD = 20.0 / 26

Definition at line 34 of file vosch_tools.h.

const double normals_radius_search = 0.02

Definition at line 30 of file vosch_tools.h.

const double rsd_radius_search = 0.01

Definition at line 29 of file vosch_tools.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


vosch
Author(s): Asako Kanezaki
autogenerated on Sun Oct 6 2013 12:06:15