35 #include <gtest/gtest.h> 40 #include <eigen3/Eigen/Eigen> 44 using namespace Eigen;
46 using namespace boost;
50 template <
typename Type>
53 return Type(min + (max - min) *
double(rand()) /
double(RAND_MAX));
56 template <
typename Type>
60 static const GLushort FILTER_GL_TYPE = GL_ZERO;
67 static const GLushort FILTER_GL_TYPE = GL_UNSIGNED_SHORT;
68 static constexpr
double ToMetricScale = 0.001;
75 static const GLushort FILTER_GL_TYPE = GL_FLOAT;
76 static constexpr
double ToMetricScale = 1.0f;
79 template <
typename Type>
86 MeshFilterTest(
unsigned width = 500,
unsigned height = 500,
double near = 0.5,
double far = 5.0,
double shadow = 0.1,
96 bool transform_callback(
MeshHandle handle, Affine3d& transform)
const;
97 void getGroundTruth(
unsigned int* labels,
float* depth)
const;
111 template <
typename Type>
120 , sensor_parameters_(width, height, near_, far_, width >> 1, height >> 1, width >> 1, height >> 1, 0.1, 0.1)
122 , sensor_data_(width_ * height_)
144 }
while (*sIt == t_near || *sIt == t_far);
148 template <
typename Type>
203 template <
typename Type>
206 transform = Affine3d::Identity();
208 transform.translation() = Vector3d(0, 0,
distance_);
212 template <
typename Type>
220 vector<unsigned int> gt_labels(
width_ * height_);
223 vector<float> filtered_depth(
width_ * height_);
224 vector<unsigned int> filtered_labels(
width_ * height_);
234 ASSERT_FLOAT_EQ(filtered_depth[idx], gt_depth[idx]);
235 ASSERT_EQ(filtered_labels[idx], gt_labels[idx]);
241 template <
typename Type>
245 if (distance_ <= near_ || distance_ >=
far_)
248 for (
unsigned yIdx = 0, idx = 0; yIdx <
height_; ++yIdx)
250 for (
unsigned xIdx = 0; xIdx <
width_; ++xIdx, ++idx)
253 if (depth[idx] <
near_)
254 labels[idx] = MeshFilterBase::NearClip;
255 else if (depth[idx] >=
far_)
256 labels[idx] = MeshFilterBase::FarClip;
258 labels[idx] = MeshFilterBase::Background;
260 if (depth[idx] <=
near_ || depth[idx] >=
far_)
267 for (
unsigned yIdx = 0, idx = 0; yIdx <
height_; ++yIdx)
269 for (
unsigned xIdx = 0; xIdx <
width_; ++xIdx, ++idx)
273 if (depth[idx] <
near_)
275 labels[idx] = MeshFilterBase::NearClip;
281 if (diff < 0 && depth[idx] <
far_)
282 labels[idx] = MeshFilterBase::Background;
284 labels[idx] = MeshFilterBase::Shadow;
285 else if (depth[idx] >=
far_)
286 labels[idx] = MeshFilterBase::FarClip;
289 labels[idx] = MeshFilterBase::FirstLabel;
293 if (depth[idx] >=
far_)
319 int main(
int argc,
char** argv)
321 testing::InitGoogleTest(&argc, argv);
324 return RUN_ALL_TESTS();
void setPaddingScale(float scale)
set the scale component of padding used to multiply with sensor-specific padding coefficients to get ...
mesh_filter_test::MeshFilterTest< float > MeshFilterTestFloat
mesh_filter_test::MeshFilterTest< unsigned short > MeshFilterTestUnsignedShort
const unsigned int height_
MeshFilter< StereoCameraModel > filter_
void getFilteredDepth(float *depth) const
retrieves the filtered depth values
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
int main(int argc, char **argv)
void getGroundTruth(unsigned int *labels, float *depth) const
void setMeshDistance(double distance)
MeshHandle addMesh(const shapes::Mesh &mesh)
adds a mesh to the filter object.
const Type getRandomNumber(const Type &min, const Type &max)
void removeMesh(MeshHandle mesh_handle)
removes a mesh given by its handle
vector< Type > sensor_data_
INSTANTIATE_TEST_CASE_P(float_test, MeshFilterTestFloat,::testing::Range< double >(0.0f, 6.0f, 0.5f))
Parameters for Stereo-like devices.
bool transform_callback(MeshHandle handle, Affine3d &transform) const
void getFilteredLabels(LabelType *labels) const
retrieves the labels of the input data
StereoCameraModel::Parameters sensor_parameters_
TEST_P(MeshFilterTestFloat, float)
void setPaddingOffset(float offset)
set the offset component of padding. This value is added to the scaled sensor-specific constant compo...
void setShadowThreshold(float threshold)
set the shadow threshold. points that are further away than the rendered model are filtered out...
const unsigned int width_
shapes::Mesh createMesh(double z) const
void filter(const void *sensor_data, GLushort type, bool wait=false) const
label/remove pixels from input depth-image