提交 a086bb18 编写于 作者: W weidezhang 提交者: FangzhenLi-hust

adding min_box_test (#194)

上级 009038e5
......@@ -94,17 +94,18 @@ function generate_build_targets() {
fi
}
function generate_test_targets() {
TEST_TARGETS=$(bazel query //... | grep "_test$" | grep -v "third_party" | grep -v "kernel")
if [ $? -ne 0 ]; then
fail 'Test failed!'
fi
function generate_test_targets_dbg() {
#because of pcl seg fault of 1.7.2 exclude perception on debug build of test
TEST_TARGETS=$(bazel query //... | grep "_test$" | grep -v "third_party" | grep -v "kernel" | grep -v "perception")
if ! $USE_ESD_CAN; then
TEST_TARGETS=$(echo $TEST_TARGETS| tr ' ' '\n' | grep -v "hwmonitor" | grep -v "esd")
fi
}
function generate_test_targets_opt() {
TEST_TARGETS=$(bazel query //... | grep "_test$" | grep "perception")
}
#=================================================
# Build functions
#=================================================
......@@ -231,11 +232,18 @@ function release() {
function gen_coverage() {
bazel clean
generate_test_targets
generate_test_targets_dbg
echo "$TEST_TARGETS" | xargs bazel test --define ARCH="$(uname -m)" --define CAN_CARD=${CAN_CARD} --cxxopt=-DUSE_ESD_CAN=${USE_ESD_CAN} -c dbg --config=coverage
if [ $? -ne 0 ]; then
fail 'run test failed!'
fi
generate_test_targets_opt
echo "$TEST_TARGETS" | xargs bazel test --define ARCH="$(uname -m)" --define CAN_CARD=${CAN_CARD} --cxxopt=-DUSE_ESD_CAN=${USE_ESD_CAN} -c opt --config=coverage
if [ $? -ne 0 ]; then
fail 'run test failed!'
fi
COV_DIR=data/cov
rm -rf $COV_DIR
files=$(find bazel-out/local-dbg/bin/modules/ -iname "*.gcda" -o -iname "*.gcno" | grep -v external)
......@@ -262,9 +270,16 @@ function gen_coverage() {
function run_test() {
START_TIME=$(get_now)
generate_test_targets
# FIXME(all): when all unit test passed, switch back.
# bazel test --config=unit_test -c dbg //...
generate_test_targets_dbg
echo "$TEST_TARGETS" | xargs bazel test --define "ARCH=$MACHINE_ARCH" --define CAN_CARD=${CAN_CARD} --config=unit_test --cxxopt=-DUSE_ESD_CAN=${USE_ESD_CAN} -c dbg --test_verbose_timeout_warnings
if [ $? -eq 0 ]; then
RES1=$?
generate_test_targets_opt
echo "$TEST_TARGETS" | xargs bazel test --define "ARCH=$MACHINE_ARCH" --define CAN_CARD=${CAN_CARD} --config=unit_test --cxxopt=-DUSE_ESD_CAN=${USE_ESD_CAN} -c opt --test_verbose_timeout_warnings
RES2=$?
if [ $RES1 -eq 0 ] && [ $RES2 -eq 0 ]; then
success 'Test passed!'
return 0
else
......
......@@ -31,4 +31,11 @@ cc_binary(
],
)
filegroup(
name = "perception_testdata",
srcs = glob([
"testdata/**",
]),
)
cpplint()
......@@ -6,6 +6,10 @@ cc_library(
name = "base",
srcs = glob(["*.cc"]),
hdrs = glob(["*.h"]),
linkopts = [
"-lboost_filesystem",
"-lboost_system",
],
deps = [
"//modules/common:common",
"//modules/common:log",
......
......@@ -18,4 +18,24 @@ cc_library(
],
)
cc_test(
name = "min_box_test",
size = "small",
srcs = [
"min_box_test.cc",
],
data = ["//modules/perception:perception_testdata"],
linkopts = [
"-lqhull",
],
deps = [
":perception_obstacle_lidar_object_builder_min_box",
"//modules/perception/lib/pcl_util:pcl_util",
"//modules/perception/common:perception_common",
"//modules/perception/obstacle/common:perception_obstacle_common",
"@gtest//:main",
],
)
cpplint()
/******************************************************************************
* Copyright 2017 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include <fstream>
#include <gtest/gtest.h>
#include "modules/perception/obstacle/lidar/object_builder/min_box/min_box.h"
namespace apollo {
namespace perception {
class MinBoxObjectBuilderTest : public testing::Test {
protected:
MinBoxObjectBuilderTest() {
}
~MinBoxObjectBuilderTest() {
}
void SetUp() {
_min_box_object_builder = new MinBoxObjectBuilder();
}
void TearDown() {
delete _min_box_object_builder;
_min_box_object_builder = NULL;
}
protected:
MinBoxObjectBuilder* _min_box_object_builder;
};
bool ConstructPointCloud(std::vector<ObjectPtr>* objects) {
std::string pcd_data("modules/perception/testdata/min_box_object_builder_test/QB9178_3_1461381834_1461382134_30651.pcd");
std::ifstream cluster_ifs(pcd_data.c_str(), std::ifstream::in);
std::string point_buf;
while (cluster_ifs.good()) {
getline(cluster_ifs, point_buf);
std::stringstream ss;
ss << point_buf;
int point_num = 0;
ss >> point_num;
if (point_num <= 0) {
continue;
}
uint64_t intensity;
pcl_util::PointCloudPtr cluster_cloud(new pcl_util::PointCloud);
for (int i = 0; i < point_num; ++i) {
pcl_util::Point p;
ss >> p.x >> p.y >> p.z >> intensity;
p.intensity = static_cast<uint8_t>(intensity);
cluster_cloud->points.push_back(p);
}
ObjectPtr object(new Object);
object->cloud = cluster_cloud;
objects->push_back(object);
}
return true;
}
TEST_F(MinBoxObjectBuilderTest, build) {
std::vector<ObjectPtr> objects;
ConstructPointCloud(&objects);
EXPECT_EQ(5, objects.size());
ObjectBuilderOptions options;
EXPECT_TRUE(_min_box_object_builder->Build(options, &objects));
const double EPSILON = 1e-6;
// obj 1
EXPECT_EQ(3, objects[0]->cloud->points.size());
EXPECT_NEAR(0.1499978, objects[0]->length, EPSILON);
EXPECT_NEAR(0.0560999, objects[0]->width, EPSILON);
EXPECT_NEAR(0.7320720, objects[0]->height, EPSILON);
EXPECT_NEAR(0.0, objects[0]->direction[0], EPSILON);
EXPECT_NEAR(1.0, objects[0]->direction[1], EPSILON);
EXPECT_NEAR(0.0, objects[0]->direction[2], EPSILON);
// obj 2
EXPECT_EQ(76, objects[1]->cloud->points.size());
EXPECT_NEAR(3.740892, objects[1]->length, EPSILON);
EXPECT_NEAR(0.387848, objects[1]->width, EPSILON);
EXPECT_NEAR(1.855707, objects[1]->height, EPSILON);
EXPECT_NEAR(-0.9987907, objects[1]->direction[0], EPSILON);
EXPECT_NEAR(-0.0491651, objects[1]->direction[1], EPSILON);
EXPECT_NEAR(0.0, objects[1]->direction[2], EPSILON);
// obj 3
EXPECT_EQ(4, objects[2]->cloud->points.size());
EXPECT_NEAR(0.693386, objects[2]->length, EPSILON);
EXPECT_NEAR(0.278326, objects[2]->width, EPSILON);
EXPECT_NEAR(0.0199099, objects[2]->height, EPSILON);
EXPECT_NEAR(0.743031, objects[2]->direction[0], EPSILON);
EXPECT_NEAR(-0.669257, objects[2]->direction[1], EPSILON);
EXPECT_NEAR(0.0, objects[2]->direction[2], EPSILON);
// obj 4
EXPECT_EQ(7, objects[3]->cloud->points.size());
EXPECT_NEAR(0.688922, objects[3]->length, EPSILON);
EXPECT_NEAR(0.356031, objects[3]->width, EPSILON);
EXPECT_NEAR(0.311353, objects[3]->height, EPSILON);
EXPECT_NEAR(0.992437, objects[3]->direction[0], EPSILON);
EXPECT_NEAR(0.122754, objects[3]->direction[1], EPSILON);
EXPECT_NEAR(0.0, objects[3]->direction[2], EPSILON);
// obj 5
EXPECT_EQ(11, objects[4]->cloud->points.size());
EXPECT_NEAR(1.147774, objects[4]->length, EPSILON);
EXPECT_NEAR(0.326984, objects[4]->width, EPSILON);
EXPECT_NEAR(0.977219, objects[4]->height, EPSILON);
EXPECT_NEAR(0.979983, objects[4]->direction[0], EPSILON);
EXPECT_NEAR(-0.199081, objects[4]->direction[1], EPSILON);
EXPECT_NEAR(0.0, objects[4]->direction[2], EPSILON);
}
} // namespace perception
} // namespace apollo
......@@ -15,7 +15,7 @@
*****************************************************************************/
#include "modules/perception/obstacle/onboard/lidar_process.h"
// #include <pcl/ros/conversions.h>
#include <pcl_conversions/pcl_conversions.h>
#include <sensor_msgs/PointCloud2.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
......@@ -247,7 +247,6 @@ bool LidarProcess::InitAlgorithmPlugin() {
void LidarProcess::TransPointCloudToPCL(
const sensor_msgs::PointCloud2& in_msg, PointCloudPtr* out_cloud) {
/*
// transform from ros to pcl
pcl::PointCloud<pcl_util::PointXYZIT> in_cloud;
pcl::fromROSMsg(in_msg, in_cloud);
......@@ -266,7 +265,6 @@ void LidarProcess::TransPointCloudToPCL(
cloud->points[idx].z = in_cloud.points[idx].z;
cloud->points[idx].intensity = in_cloud.points[idx].intensity;
}
*/
}
bool LidarProcess::GetVelodyneTrans(const double query_time, Matrix4d* trans) {
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册