提交 ab50808a 编写于 作者: W wanghao0711 提交者: FangzhenLi-hust

Lib test dev (#1455)

* Update lib-base tests

* Fix code style
上级 739e3d1e
...@@ -20,7 +20,7 @@ DEFINE_int32(perception_loop_rate, 10, "Loop rate for perception node, in Hz."); ...@@ -20,7 +20,7 @@ DEFINE_int32(perception_loop_rate, 10, "Loop rate for perception node, in Hz.");
DEFINE_string(node_name, "perception", "The perception module name in proto"); DEFINE_string(node_name, "perception", "The perception module name in proto");
/// lib/config_manager/config_manager.cc /// lib/config_manager/config_manager.cc
DEFINE_string(config_manager_path, "./conf/config_manager.config", DEFINE_string(config_manager_path, "./conf/config_manager.config",
"The ModelConfig config paths file."); "The ModelConfig config paths file.");
DEFINE_string(work_root, "modules/perception", "Project work root direcotry."); DEFINE_string(work_root, "modules/perception", "Project work root direcotry.");
......
...@@ -21,7 +21,7 @@ ...@@ -21,7 +21,7 @@
DECLARE_int32(perception_loop_rate); DECLARE_int32(perception_loop_rate);
/// lib/config_manager/config_manager.cc /// lib/config_manager/config_manager.cc
DECLARE_string(config_manager_path); DECLARE_string(config_manager_path);
DECLARE_string(work_root); DECLARE_string(work_root);
......
...@@ -16,11 +16,10 @@ ...@@ -16,11 +16,10 @@
#ifndef MODULES_PERCEPTION_OBSTACLE_BASE_HDMAP_STRUCT_H_ #ifndef MODULES_PERCEPTION_OBSTACLE_BASE_HDMAP_STRUCT_H_
#define MODULES_PERCEPTION_OBSTACLE_BASE_HDMAP_STRUCT_H_ #define MODULES_PERCEPTION_OBSTACLE_BASE_HDMAP_STRUCT_H_
#include "modules/perception/obstacle/base/types.h"
#include <memory> #include <memory>
#include <vector> #include <vector>
#include "modules/perception/obstacle/base/types.h"
namespace apollo { namespace apollo {
namespace perception { namespace perception {
......
...@@ -59,16 +59,16 @@ void TransformPoint(const PointType& point_in, PointType* point_out, ...@@ -59,16 +59,16 @@ void TransformPoint(const PointType& point_in, PointType* point_out,
template <typename PointType> template <typename PointType>
void TransformPointCloud(const pcl::PointCloud<PointType>& cloud_in, void TransformPointCloud(const pcl::PointCloud<PointType>& cloud_in,
pcl::PointCloud<PointType>& cloud_out, pcl::PointCloud<PointType>* cloud_out,
const Eigen::Matrix4d& trans_mat) { const Eigen::Matrix4d& trans_mat) {
if (cloud_out.points.size() < cloud_in.points.size()) { if (cloud_out->points.size() < cloud_in.points.size()) {
cloud_out.points.resize(cloud_in.points.size()); cloud_out->points.resize(cloud_in.points.size());
} }
for (int i = 0; i < cloud_in.size(); ++i) { for (int i = 0; i < cloud_in.size(); ++i) {
const PointType& p = cloud_in.at(i); const PointType& p = cloud_in.at(i);
Eigen::Vector4d v(p.x, p.y, p.z, 1); Eigen::Vector4d v(p.x, p.y, p.z, 1);
v = trans_mat * v; v = trans_mat * v;
PointType& pd = cloud_out.points[i]; PointType& pd = cloud_out->points[i];
pd.x = v.x(); pd.x = v.x();
pd.y = v.y(); pd.y = v.y();
pd.z = v.z(); pd.z = v.z();
......
...@@ -106,7 +106,7 @@ TEST_F(GeometryUtilTest, TransformPointCloud2) { ...@@ -106,7 +106,7 @@ TEST_F(GeometryUtilTest, TransformPointCloud2) {
EXPECT_NEAR(1.715922, in_out_cloud->at(0).z, EPSILON); EXPECT_NEAR(1.715922, in_out_cloud->at(0).z, EPSILON);
pcl_util::PointCloudPtr out_cloud(new pcl_util::PointCloud); pcl_util::PointCloudPtr out_cloud(new pcl_util::PointCloud);
TransformPointCloud(*_clouds[0], *out_cloud, _trans_matrix); TransformPointCloud(*_clouds[0], out_cloud.get(), _trans_matrix);
EXPECT_NEAR(64.184380, out_cloud->at(0).x, EPSILON); EXPECT_NEAR(64.184380, out_cloud->at(0).x, EPSILON);
EXPECT_NEAR(13.708398, out_cloud->at(0).y, EPSILON); EXPECT_NEAR(13.708398, out_cloud->at(0).y, EPSILON);
EXPECT_NEAR(1.715922, out_cloud->at(0).z, EPSILON); EXPECT_NEAR(1.715922, out_cloud->at(0).z, EPSILON);
......
...@@ -34,8 +34,11 @@ bool ReadPoseFile(const std::string& filename, ...@@ -34,8 +34,11 @@ bool ReadPoseFile(const std::string& filename,
double time_samp = 0; double time_samp = 0;
double quat[4]; double quat[4];
double matrix3x3[9]; double matrix3x3[9];
double& pose03 = (*pose)(0, 3);
double& pose13 = (*pose)(1, 3);
double& pose23 = (*pose)(2, 3);
sscanf(buffer, "%d %lf %lf %lf %lf %lf %lf %lf %lf", &id, &(time_samp), sscanf(buffer, "%d %lf %lf %lf %lf %lf %lf %lf %lf", &id, &(time_samp),
&((*pose)(0, 3)), &((*pose)(1, 3)), &((*pose)(2, 3)), &pose03, &pose13, &pose23,
&(quat[0]), &(quat[1]), &(quat[2]), &(quat[3])); &(quat[0]), &(quat[1]), &(quat[2]), &(quat[3]));
QuaternionToRotationMatrix<double>(quat, matrix3x3); QuaternionToRotationMatrix<double>(quat, matrix3x3);
......
...@@ -62,7 +62,7 @@ void DummyObjectBuilder::BuildObject(const ObjectBuilderOptions &options, ...@@ -62,7 +62,7 @@ void DummyObjectBuilder::BuildObject(const ObjectBuilderOptions &options,
Eigen::Vector4f min_pt; Eigen::Vector4f min_pt;
Eigen::Vector4f max_pt; Eigen::Vector4f max_pt;
PointCloudPtr cloud = obj->cloud; PointCloudPtr cloud = obj->cloud;
SetDefaultValue(cloud, obj, min_pt, max_pt); SetDefaultValue(cloud, obj, &min_pt, &max_pt);
if (cloud->points.size() < 4u) { if (cloud->points.size() < 4u) {
return; return;
} }
......
...@@ -84,26 +84,26 @@ class BaseObjectBuilder { ...@@ -84,26 +84,26 @@ class BaseObjectBuilder {
protected: protected:
virtual void SetDefaultValue(pcl_util::PointCloudPtr cloud, ObjectPtr obj, virtual void SetDefaultValue(pcl_util::PointCloudPtr cloud, ObjectPtr obj,
Eigen::Vector4f &min_pt, Eigen::Vector4f* min_pt,
Eigen::Vector4f &max_pt) { Eigen::Vector4f* max_pt) {
GetCloudMinMax3D<pcl_util::Point>(cloud, &min_pt, &max_pt); GetCloudMinMax3D<pcl_util::Point>(cloud, min_pt, max_pt);
Eigen::Vector3f center((min_pt[0] + max_pt[0]) / 2, Eigen::Vector3f center(((*min_pt)[0] + (*max_pt)[0]) / 2,
(min_pt[1] + max_pt[1]) / 2, ((*min_pt)[1] + (*max_pt)[1]) / 2,
(min_pt[2] + max_pt[2]) / 2); ((*min_pt)[2] + (*max_pt)[2]) / 2);
// handle degeneration case // handle degeneration case
float epslin = 1e-3; float epslin = 1e-3;
for (int i = 0; i < 3; i++) { for (int i = 0; i < 3; i++) {
if (max_pt[i] - min_pt[i] < epslin) { if ((*max_pt)[i] - (*min_pt)[i] < epslin) {
max_pt[i] = center[i] + epslin / 2; (*max_pt)[i] = center[i] + epslin / 2;
min_pt[i] = center[i] - epslin / 2; (*min_pt)[i] = center[i] - epslin / 2;
} }
} }
// length // length
obj->length = max_pt[0] - min_pt[0]; obj->length = (*max_pt)[0] - (*min_pt)[0];
// width // width
obj->width = max_pt[1] - min_pt[1]; obj->width = (*max_pt)[1] - (*min_pt)[1];
if (obj->length - obj->width < 0) { if (obj->length - obj->width < 0) {
float tmp = obj->length; float tmp = obj->length;
obj->length = obj->width; obj->length = obj->width;
...@@ -113,29 +113,29 @@ class BaseObjectBuilder { ...@@ -113,29 +113,29 @@ class BaseObjectBuilder {
obj->direction = Eigen::Vector3d(1.0, 0.0, 0.0); obj->direction = Eigen::Vector3d(1.0, 0.0, 0.0);
} }
// height // height
obj->height = max_pt[2] - min_pt[2]; obj->height = (*max_pt)[2] - (*min_pt)[2];
// center // center
obj->center = Eigen::Vector3d((max_pt[0] + min_pt[0]) / 2, obj->center = Eigen::Vector3d(((*max_pt)[0] + (*min_pt)[0]) / 2,
(max_pt[1] + min_pt[1]) / 2, ((*max_pt)[1] + (*min_pt)[1]) / 2,
(max_pt[2] + min_pt[2]) / 2); ((*max_pt)[2] + (*min_pt)[2]) / 2);
// polygon // polygon
if (cloud->size() < 4) { if (cloud->size() < 4) {
obj->polygon.points.resize(4); obj->polygon.points.resize(4);
obj->polygon.points[0].x = static_cast<double>(min_pt[0]); obj->polygon.points[0].x = static_cast<double>((*min_pt)[0]);
obj->polygon.points[0].y = static_cast<double>(min_pt[1]); obj->polygon.points[0].y = static_cast<double>((*min_pt)[1]);
obj->polygon.points[0].z = static_cast<double>(min_pt[2]); obj->polygon.points[0].z = static_cast<double>((*min_pt)[2]);
obj->polygon.points[1].x = static_cast<double>(max_pt[0]); obj->polygon.points[1].x = static_cast<double>((*max_pt)[0]);
obj->polygon.points[1].y = static_cast<double>(min_pt[1]); obj->polygon.points[1].y = static_cast<double>((*min_pt)[1]);
obj->polygon.points[1].z = static_cast<double>(min_pt[2]); obj->polygon.points[1].z = static_cast<double>((*min_pt)[2]);
obj->polygon.points[2].x = static_cast<double>(max_pt[0]); obj->polygon.points[2].x = static_cast<double>((*max_pt)[0]);
obj->polygon.points[2].y = static_cast<double>(max_pt[1]); obj->polygon.points[2].y = static_cast<double>((*max_pt)[1]);
obj->polygon.points[2].z = static_cast<double>(min_pt[2]); obj->polygon.points[2].z = static_cast<double>((*min_pt)[2]);
obj->polygon.points[3].x = static_cast<double>(min_pt[0]); obj->polygon.points[3].x = static_cast<double>((*min_pt)[0]);
obj->polygon.points[3].y = static_cast<double>(max_pt[1]); obj->polygon.points[3].y = static_cast<double>((*max_pt)[1]);
obj->polygon.points[3].z = static_cast<double>(min_pt[2]); obj->polygon.points[3].z = static_cast<double>((*min_pt)[2]);
} }
} }
......
...@@ -52,6 +52,7 @@ ...@@ -52,6 +52,7 @@
// using roi_filter to do somethings. // using roi_filter to do somethings.
// //////////////////////////////////////////////////// // ////////////////////////////////////////////////////
#include <memory>
#include <string> #include <string>
#include <vector> #include <vector>
......
...@@ -52,6 +52,7 @@ ...@@ -52,6 +52,7 @@
// using roi_filter to do somethings. // using roi_filter to do somethings.
// //////////////////////////////////////////////////// // ////////////////////////////////////////////////////
#include <memory>
#include <string> #include <string>
#include <vector> #include <vector>
......
...@@ -53,6 +53,7 @@ ...@@ -53,6 +53,7 @@
// using tracker to do somethings. // using tracker to do somethings.
// //////////////////////////////////////////////////// // ////////////////////////////////////////////////////
#include <memory>
#include <string> #include <string>
#include <vector> #include <vector>
......
...@@ -322,7 +322,7 @@ void MinBoxObjectBuilder::ComputePolygon2dxy(ObjectPtr obj) { ...@@ -322,7 +322,7 @@ void MinBoxObjectBuilder::ComputePolygon2dxy(ObjectPtr obj) {
Eigen::Vector4f min_pt; Eigen::Vector4f min_pt;
Eigen::Vector4f max_pt; Eigen::Vector4f max_pt;
pcl_util::PointCloudPtr cloud = obj->cloud; pcl_util::PointCloudPtr cloud = obj->cloud;
SetDefaultValue(cloud, obj, min_pt, max_pt); SetDefaultValue(cloud, obj, &min_pt, &max_pt);
if (cloud->points.size() < 4u) { if (cloud->points.size() < 4u) {
return; return;
} }
......
...@@ -14,14 +14,12 @@ ...@@ -14,14 +14,12 @@
* limitations under the License. * limitations under the License.
*****************************************************************************/ *****************************************************************************/
#include <opencv2/opencv.hpp>
#include <fstream> #include <fstream>
#include <iostream> #include <iostream>
#include <opencv2/opencv.hpp>
#include <string> #include <string>
#include "gflags/gflags.h" #include "gflags/gflags.h"
using namespace std;
DEFINE_string(test_dir, "/apollo/modules/perception/data/cnnseg_test/", DEFINE_string(test_dir, "/apollo/modules/perception/data/cnnseg_test/",
"test data directory"); "test data directory");
DEFINE_string(pcd_name, "uscar_12_1470770225_1470770492_1349", DEFINE_string(pcd_name, "uscar_12_1470770225_1470770492_1349",
...@@ -30,22 +28,22 @@ DEFINE_string(pcd_name, "uscar_12_1470770225_1470770492_1349", ...@@ -30,22 +28,22 @@ DEFINE_string(pcd_name, "uscar_12_1470770225_1470770492_1349",
int main(int argc, char** argv) { int main(int argc, char** argv) {
google::ParseCommandLineFlags(&argc, &argv, true); google::ParseCommandLineFlags(&argc, &argv, true);
string test_dir(FLAGS_test_dir); std::string test_dir(FLAGS_test_dir);
string det_res_file = test_dir + FLAGS_pcd_name + "-detection.txt"; std::string det_res_file = test_dir + FLAGS_pcd_name + "-detection.txt";
ifstream f_res(det_res_file.c_str(), std::ifstream::in); std::ifstream f_res(det_res_file.c_str(), std::ifstream::in);
string line; std::string line;
getline(f_res, line); std::getline(f_res, line);
int rows, cols; int rows, cols;
istringstream iss(line); std::istringstream iss(line);
iss >> rows >> cols; iss >> rows >> cols;
cout << "#rows = " << rows << ", #cols = " << cols << endl; std::cout << "#rows = " << rows << ", #cols = " << cols << endl;
cv::Mat img(rows, cols, CV_8UC3, cv::Scalar(0.0)); cv::Mat img(rows, cols, CV_8UC3, cv::Scalar(0.0));
int grid = 0; int grid = 0;
while (getline(f_res, line)) { while (std::getline(f_res, line)) {
istringstream iss(line); std::istringstream iss(line);
int blue, green, red; int blue, green, red;
iss >> blue >> green >> red; iss >> blue >> green >> red;
img.at<cv::Vec3b>(grid / cols, grid % cols) = cv::Vec3b(blue, green, red); img.at<cv::Vec3b>(grid / cols, grid % cols) = cv::Vec3b(blue, green, red);
...@@ -56,11 +54,12 @@ int main(int argc, char** argv) { ...@@ -56,11 +54,12 @@ int main(int argc, char** argv) {
} }
f_res.close(); f_res.close();
string res_img_file = test_dir + FLAGS_pcd_name + "-detection.png"; std::string res_img_file = test_dir + FLAGS_pcd_name + "-detection.png";
if (!cv::imwrite(res_img_file, img)) { if (!cv::imwrite(res_img_file, img)) {
return -1; return -1;
} }
google::ShutDownCommandLineFlags(); google::ShutDownCommandLineFlags();
return 0; return 0;
} }
\ No newline at end of file
...@@ -131,7 +131,7 @@ void OpenglVisualizer::UpdateCameraSystem(FrameContent *content) { ...@@ -131,7 +131,7 @@ void OpenglVisualizer::UpdateCameraSystem(FrameContent *content) {
&view_point_world_, pose_v2w); &view_point_world_, pose_v2w);
TransformPointCloud<pcl_util::Point>(main_car_points_velodyne_, TransformPointCloud<pcl_util::Point>(main_car_points_velodyne_,
main_car_points_world_, pose_v2w); &main_car_points_world_, pose_v2w);
Eigen::Vector4d up_w(up_velodyne_.x, up_velodyne_.y, up_velodyne_.z, 0); Eigen::Vector4d up_w(up_velodyne_.x, up_velodyne_.y, up_velodyne_.z, 0);
......
...@@ -99,7 +99,8 @@ bool HDMapInput::GetNearestLaneDirection(const pcl_util::PointD& pointd, ...@@ -99,7 +99,8 @@ bool HDMapInput::GetNearestLaneDirection(const pcl_util::PointD& pointd,
double nearest_s; double nearest_s;
double nearest_l; double nearest_l;
int status = hdmap->GetNearestLane(point, &nearest_lane, &nearest_s, &nearest_l); int status = hdmap->GetNearestLane(point,
&nearest_lane, &nearest_s, &nearest_l);
if (status != SUCC) { if (status != SUCC) {
AERROR << "Failed to get nearest lane for point " << point.DebugString(); AERROR << "Failed to get nearest lane for point " << point.DebugString();
return false; return false;
......
...@@ -17,6 +17,8 @@ ...@@ -17,6 +17,8 @@
#ifndef MODEULES_PERCEPTION_OBSTACLE_ONBOARD_LIDAR_PROCESS_H_ #ifndef MODEULES_PERCEPTION_OBSTACLE_ONBOARD_LIDAR_PROCESS_H_
#define MODEULES_PERCEPTION_OBSTACLE_ONBOARD_LIDAR_PROCESS_H_ #define MODEULES_PERCEPTION_OBSTACLE_ONBOARD_LIDAR_PROCESS_H_
#include <memory>
#include <vector>
#include "Eigen/Core" #include "Eigen/Core"
#include "gtest/gtest_prod.h" #include "gtest/gtest_prod.h"
......
...@@ -14,6 +14,7 @@ ...@@ -14,6 +14,7 @@
* limitations under the License. * limitations under the License.
*****************************************************************************/ *****************************************************************************/
#include <pcl/io/pcd_io.h> #include <pcl/io/pcd_io.h>
#include <string>
#include <vector> #include <vector>
#include "gtest/gtest.h" #include "gtest/gtest.h"
......
...@@ -22,6 +22,7 @@ ...@@ -22,6 +22,7 @@
#define MODEULES_PERCEPTION_PERCEPTION_H_ #define MODEULES_PERCEPTION_PERCEPTION_H_
#include <string> #include <string>
#include <memory>
#include "modules/common/apollo_app.h" #include "modules/common/apollo_app.h"
#include "modules/common/macro.h" #include "modules/common/macro.h"
......
...@@ -14,13 +14,13 @@ ...@@ -14,13 +14,13 @@
* limitations under the License. * limitations under the License.
*****************************************************************************/ *****************************************************************************/
#include <pcl/io/pcd_io.h>
#include <cstddef> #include <cstddef>
#include <fstream> #include <fstream>
#include <iomanip> #include <iomanip>
#include <sstream> #include <sstream>
#include <vector> #include <vector>
#include <string> #include <string>
#include <pcl/io/pcd_io.h>
#include "modules/perception/common/perception_gflags.h" #include "modules/perception/common/perception_gflags.h"
#include "modules/perception/lib/config_manager/config_manager.h" #include "modules/perception/lib/config_manager/config_manager.h"
...@@ -132,13 +132,13 @@ class OfflineLidarPerceptionTool { ...@@ -132,13 +132,13 @@ class OfflineLidarPerceptionTool {
if (FLAGS_save_obstacles) { if (FLAGS_save_obstacles) {
oss << std::setfill('0') << std::setw(6) << i; oss << std::setfill('0') << std::setw(6) << i;
std::string filename = FLAGS_output_path + oss.str() + ".txt"; std::string filename = FLAGS_output_path + oss.str() + ".txt";
SaveTrackingInformation(result_objects, pose, frame_id, cloud, SaveTrackingInformation(&result_objects, pose, frame_id, cloud,
filename); filename);
} }
} }
} }
void SaveTrackingInformation(std::vector<ObjectPtr>& objects, void SaveTrackingInformation(std::vector<ObjectPtr>* objects,
const Eigen::Matrix4d& pose_v2w, const Eigen::Matrix4d& pose_v2w,
const int& frame_id, const int& frame_id,
const pcl_util::PointCloudPtr& cloud, const pcl_util::PointCloudPtr& cloud,
...@@ -149,7 +149,7 @@ class OfflineLidarPerceptionTool { ...@@ -149,7 +149,7 @@ class OfflineLidarPerceptionTool {
return; return;
} }
// write frame id & number of objects at the beignning // write frame id & number of objects at the beignning
fout << frame_id << " " << objects.size() << std::endl; fout << frame_id << " " << objects->size() << std::endl;
typename pcl::PointCloud<pcl_util::Point>::Ptr trans_cloud( typename pcl::PointCloud<pcl_util::Point>::Ptr trans_cloud(
new pcl::PointCloud<pcl_util::Point>()); new pcl::PointCloud<pcl_util::Point>());
...@@ -163,7 +163,7 @@ class OfflineLidarPerceptionTool { ...@@ -163,7 +163,7 @@ class OfflineLidarPerceptionTool {
std::vector<float> k_sqrt_dist; std::vector<float> k_sqrt_dist;
Eigen::Matrix4d pose_tw2velo = pose_velo2tw.inverse(); Eigen::Matrix4d pose_tw2velo = pose_velo2tw.inverse();
for (const auto& obj : objects) { for (const auto& obj : *objects) {
Eigen::Vector3f coord_dir(0.0, 1.0, 0.0); Eigen::Vector3f coord_dir(0.0, 1.0, 0.0);
Eigen::Vector4d dir_velo = pose_tw2velo * Eigen::Vector4d( Eigen::Vector4d dir_velo = pose_tw2velo * Eigen::Vector4d(
obj->direction[0], obj->direction[1], obj->direction[2], 0); obj->direction[0], obj->direction[1], obj->direction[2], 0);
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册