提交 a2cc6eea 编写于 作者: K kimifly06 提交者: weidezhang

(previous test problem has been fixed, please cr) perception: removed PCD...

(previous test problem has been fixed, please cr) perception: removed PCD files & modified true poses as fake ones (#1666)

* replace NULL as nullptr

* removed pcds & modifed true pose

* removed unused include

* fixed file system util test

* fixed pose util test
上级 484abad9
*.pcd filter=lfs diff=lfs merge=lfs -text
\ No newline at end of file
11989 1160300588.419051 428033.330463 4435145.010161 40.746964 -0.002165 -0.010956 -0.639926 0.768355
11989 588.419051 33.330463 45.010161 40.746964 -0.002165 -0.010956 -0.639926 0.768355
11990 1160300588.519102 428033.330382 4435145.010216 40.747129 -0.002152 -0.010966 -0.639940 0.768343
11990 588.519102 33.330382 45.010216 40.747129 -0.002152 -0.010966 -0.639940 0.768343
11991 1160300588.619153 428033.330347 4435145.010282 40.747194 -0.002133 -0.010945 -0.639944 0.768341
11991 588.619153 33.330347 45.010282 40.747194 -0.002133 -0.010945 -0.639944 0.768341
11992 1160300588.719204 428033.330361 4435145.010357 40.747331 -0.002134 -0.010937 -0.639935 0.768348
11992 588.719204 33.330361 45.010357 40.747331 -0.002134 -0.010937 -0.639935 0.768348
11993 1160300588.819255 428033.330328 4435145.010420 40.747546 -0.002154 -0.010940 -0.639938 0.768346
11993 588.819255 33.330328 45.010420 40.747546 -0.002154 -0.010940 -0.639938 0.768346
11994 1160300588.919307 428033.330290 4435145.010480 40.747756 -0.002180 -0.010939 -0.639941 0.768343
11994 588.919307 33.330290 45.010480 40.747756 -0.002180 -0.010939 -0.639941 0.768343
11995 1160300589.019364 428033.330300 4435145.010551 40.747892 -0.002173 -0.010936 -0.639935 0.768348
11995 589.019364 33.330300 45.010551 40.747892 -0.002173 -0.010936 -0.639935 0.768348
11996 1160300589.119415 428033.330241 4435145.010605 40.748109 -0.002156 -0.010970 -0.639944 0.768340
11996 589.119415 33.330241 45.010605 40.748109 -0.002156 -0.010970 -0.639944 0.768340
......@@ -24,15 +24,12 @@ namespace perception {
TEST(FileSystemUtilTest, GetFileNamesInFolderById) {
std::string data_path = "modules/perception/data/hm_tracker_test/";
std::vector<std::string> pcd_filenames;
GetFileNamesInFolderById(data_path, ".pcd", &pcd_filenames);
std::vector<std::string> seg_filenames;
GetFileNamesInFolderById(data_path, ".seg", &seg_filenames);
std::vector<std::string> pose_filenames;
GetFileNamesInFolderById(data_path, ".pose", &pose_filenames);
EXPECT_GT(pcd_filenames.size(), 0);
EXPECT_EQ(pcd_filenames.size(), seg_filenames.size());
EXPECT_EQ(pcd_filenames.size(), pose_filenames.size());
EXPECT_EQ(seg_filenames.size(), 8);
EXPECT_EQ(pose_filenames.size(), 8);
}
} // namespace perception
......
......@@ -39,9 +39,9 @@ TEST_F(PoseUtilTest, ReadPoseFile) {
double time_stamp;
EXPECT_TRUE(ReadPoseFile(test_file, &pose, &frame_id, &time_stamp));
EXPECT_EQ(frame_id, 11989);
EXPECT_EQ(time_stamp, 1160300588.419051);
EXPECT_EQ(pose(0, 3), 428033.330463);
EXPECT_EQ(pose(1, 3), 4435145.010161);
EXPECT_EQ(time_stamp, 588.419051);
EXPECT_EQ(pose(0, 3), 33.330463);
EXPECT_EQ(pose(1, 3), 45.010161);
EXPECT_EQ(pose(2, 3), 40.746964);
}
......
......@@ -33,7 +33,7 @@ HmObjectTracker::HmObjectTracker(): matcher_method_(HUNGARIAN_MATCHER),
filter_method_(KALMAN_FILTER),
use_histogram_for_match_(false),
histogram_bin_size_(10),
matcher_(NULL),
matcher_(nullptr),
time_stamp_(0.0),
valid_(false) {
}
......@@ -41,7 +41,7 @@ HmObjectTracker::HmObjectTracker(): matcher_method_(HUNGARIAN_MATCHER),
HmObjectTracker::~HmObjectTracker() {
if (matcher_) {
delete matcher_;
matcher_ = NULL;
matcher_ = nullptr;
}
}
......@@ -50,7 +50,7 @@ bool HmObjectTracker::Init() {
using apollo::perception::ConfigManager;
using apollo::perception::ModelConfig;
const ModelConfig* model_config = NULL;
const ModelConfig* model_config = nullptr;
if (!ConfigManager::instance()->GetModelConfig(name(), &model_config)) {
AERROR << "not found model config: " << name();
return false;
......@@ -371,14 +371,14 @@ bool HmObjectTracker::Track(const std::vector<ObjectPtr>& objects,
const TrackerOptions& options,
std::vector<ObjectPtr>* tracked_objects) {
// A. track setup
if (tracked_objects == NULL)
if (tracked_objects == nullptr)
return false;
if (!valid_) {
valid_ = true;
return Initialize(objects, timestamp, options, tracked_objects);
}
Eigen::Matrix4d velo2world_pose = Eigen::Matrix4d::Identity();
if (options.velodyne_trans != NULL) {
if (options.velodyne_trans != nullptr) {
velo2world_pose = *(options.velodyne_trans);
} else {
AERROR << "Input velodyne_trans is null";
......@@ -419,7 +419,7 @@ bool HmObjectTracker::Track(const std::vector<ObjectPtr>& objects,
UpdateUnassignedTracks(tracks_predict, unassigned_tracks, time_diff);
DeleteLostTracks();
// E.3 create new tracks for objects without associated tracks
CreateNewTracks(transformed_objects, unassigned_objects, time_diff);
CreateNewTracks(transformed_objects, unassigned_objects);
// F. collect tracked results
CollectTrackedResults(tracked_objects);
......@@ -432,7 +432,7 @@ bool HmObjectTracker::Initialize(const std::vector<ObjectPtr>& objects,
std::vector<ObjectPtr>* tracked_objects) {
// A. track setup
Eigen::Matrix4d velo2world_pose = Eigen::Matrix4d::Identity();
if (options.velodyne_trans != NULL) {
if (options.velodyne_trans != nullptr) {
velo2world_pose = *(options.velodyne_trans);
} else {
AERROR << "Input velodyne_trans is null";
......@@ -454,11 +454,9 @@ bool HmObjectTracker::Initialize(const std::vector<ObjectPtr>& objects,
// C. create tracks
std::vector<int> unassigned_objects;
unassigned_objects.resize(transformed_objects.size());
for (size_t i = 0; i < transformed_objects.size(); i++) {
unassigned_objects[i] = i;
}
std::iota(unassigned_objects.begin(), unassigned_objects.end(), 0);
double time_diff = 0.1;
CreateNewTracks(transformed_objects, unassigned_objects, time_diff);
CreateNewTracks(transformed_objects, unassigned_objects);
time_stamp_ = timestamp;
// D. collect tracked results
......@@ -588,8 +586,7 @@ void HmObjectTracker::UpdateUnassignedTracks(
void HmObjectTracker::CreateNewTracks(
const std::vector<TrackedObjectPtr>& new_objects,
const std::vector<int>& unassigned_objects,
const double& time_diff) {
const std::vector<int>& unassigned_objects) {
// Create new tracks for objects without matched tracks
for (size_t i = 0; i < unassigned_objects.size(); i++) {
int obj_id = unassigned_objects[i];
......
......@@ -176,12 +176,10 @@ class HmObjectTracker : public BaseTracker{
// @brief create new tracks for objects without matched track
// @params[IN] new_objects: recently detected objects
// @params[IN] unassigned_objects: index of unassigned objects
// @params[IN] time_diff: time interval for updating
// @return nothing
void CreateNewTracks(
const std::vector<TrackedObjectPtr>& new_objects,
const std::vector<int>& unassigned_objects,
const double& time_diff);
const std::vector<int>& unassigned_objects);
// @brief delete lost tracks
// @return nothing
......
......@@ -16,9 +16,6 @@
#include "modules/perception/obstacle/lidar/tracker/hm_tracker/hm_tracker.h"
#include <pcl/io/pcd_io.h>
#include <pcl/kdtree/kdtree.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <fstream>
#include <iomanip>
#include <map>
......@@ -57,9 +54,9 @@ class HmObjectTrackerTest : public testing::Test {
}
void TearDown() {
delete hm_tracker_;
hm_tracker_ = NULL;
hm_tracker_ = nullptr;
delete object_builder_;
object_builder_ = NULL;
object_builder_ = nullptr;
}
protected:
......@@ -92,47 +89,21 @@ bool ConstructObjects(const std::string& filename,
return true;
}
bool LoadPclPcds(const std::string filename,
pcl_util::PointCloudPtr* cloud_out) {
pcl::PointCloud<pcl_util::PointXYZIT> org_cloud;
if (pcl::io::loadPCDFile(filename, org_cloud) < 0) {
AERROR << "failed to load pcd file: " << filename;
return false;
}
(*cloud_out)->points.reserve(org_cloud.points.size());
for (size_t i = 0; i < org_cloud.points.size(); ++i) {
pcl_util::Point pt;
pt.x = org_cloud.points[i].x;
pt.y = org_cloud.points[i].y;
pt.z = org_cloud.points[i].z;
pt.intensity = org_cloud.points[i].intensity;
if (isnan(org_cloud.points[i].x)) continue;
(*cloud_out)->push_back(pt);
}
return true;
}
TEST_F(HmObjectTrackerTest, Track) {
// test initialization of hm tracker
EXPECT_TRUE(hm_tracker_->Init());
// test tracking via hm tracker
std::string data_path = "modules/perception/data/hm_tracker_test/";
std::vector<std::string> pcd_filenames;
GetFileNamesInFolderById(data_path, ".pcd", &pcd_filenames);
std::vector<std::string> seg_filenames;
GetFileNamesInFolderById(data_path, ".seg", &seg_filenames);
std::vector<std::string> pose_filenames;
GetFileNamesInFolderById(data_path, ".pose", &pose_filenames);
int frame_id = -1;
double time_stamp = 0.0;
EXPECT_GT(pcd_filenames.size(), 0);
EXPECT_EQ(pcd_filenames.size(), seg_filenames.size());
EXPECT_EQ(pcd_filenames.size(), pose_filenames.size());
EXPECT_GT(seg_filenames.size(), 0);
EXPECT_EQ(seg_filenames.size(), pose_filenames.size());
Eigen::Vector3d global_offset(0, 0, 0);
for (size_t i = 0; i < seg_filenames.size(); ++i) {
// load frame clouds
pcl_util::PointCloudPtr cloud(new pcl_util::PointCloud);
EXPECT_TRUE(LoadPclPcds(data_path + pcd_filenames[i], &cloud));
// read pose
Eigen::Matrix4d pose = Eigen::Matrix4d::Identity();
if (!ReadPoseFile(data_path + pose_filenames[i], &pose, &frame_id,
......
......@@ -129,7 +129,7 @@ ObjectTrack::ObjectTrack(TrackedObjectPtr obj) {
ObjectTrack::~ObjectTrack() {
if (filter_) {
delete filter_;
filter_ = NULL;
filter_ = nullptr;
}
}
......@@ -415,7 +415,7 @@ void ObjectTrackSet::Clear() {
for (size_t i = 0; i < tracks_.size(); i++) {
if (tracks_[i]) {
delete (tracks_[i]);
tracks_[i] = NULL;
tracks_[i] = nullptr;
}
}
tracks_.clear();
......@@ -448,9 +448,9 @@ int ObjectTrackSet::RemoveLostTracks() {
// remove lost tracks
int no_removed = tracks_.size() - track_num;
for (size_t i = track_num; i < tracks_.size(); ++i) {
if (tracks_[i] != NULL) {
if (tracks_[i] != nullptr) {
delete (tracks_[i]);
tracks_[i] = NULL;
tracks_[i] = nullptr;
}
}
tracks_.resize(track_num);
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册