提交 87d6f77f 编写于 作者: F FangzhenLi-hust 提交者: weidezhang

add timer for perception,and modify hdmap_roi_config file path (#385)

* add timer for perception

* merge conflict
上级 e99f504c
......@@ -12,6 +12,5 @@ filegroup(
srcs = [
"config_manager.config",
"perception.conf",
"hdmap_roi_filter.conf",
],
)
model_config_path: "model/tracker.config"
model_config_path: "model/cnn_segmentation.config"
#model_config_path: "conf/hdmap_roi_filter.conf"
model_config_path: "model/hdmap_roi_filter.config"
model_configs {
# HdmapROIFilter model.
name: "HdmapROIFilter"
version: "1.0.0"
# @name: range
# @brief: create a bitmap mask which represents [-range, range]*[-range, range]
# square area around the car.
# @required: range > 0.0 && range - (-range) > cell_size
double_params {
name: "range"
value: 70.0
}
# @name: cell_size
# @brief: discretize the area using small cells.
# @required: cell_size > 0.0
double_params {
name: "cell_size"
value: 0.25
}
# @name: extend_dist
# @brief: extend the intervals returned by polygon scans conversion algorithm
# @required: none
double_params {
name: "extend_dist"
value: 0.0
}
}
......@@ -7,11 +7,13 @@ cc_library(
srcs = [
"file_util.cc",
"registerer.cc",
"timer.cc",
],
hdrs = [
"file_util.h",
"registerer.h",
"singleton.h",
"timer.h",
],
linkopts = [
"-lboost_filesystem",
......
/******************************************************************************
* 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 "modules/perception/lib/base/timer.h"
#include <sys/time.h>
#include "modules/common/log.h"
namespace apollo {
namespace perception {
using std::string;
using std::chrono::duration_cast;
using std::chrono::milliseconds;
void Timer::start() {
_start_time = std::chrono::system_clock::now();
}
uint64_t Timer::end(const string& msg) {
_end_time = std::chrono::system_clock::now();
uint64_t elapsed_time =
duration_cast<milliseconds>(_end_time - _start_time).count();
AINFO << "TIMER " << msg << " elapsed_time: " << elapsed_time << " ms";
// start new timer.
_start_time = _end_time;
return elapsed_time;
}
} // namespace perception
} // namespace apollo
/******************************************************************************
* 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.
*****************************************************************************/
#ifndef MODULES_PERCEPTION_LIB_BASE_TIMER_H_
#define MODULES_PERCEPTION_LIB_BASE_TIMER_H_
#include <stdint.h>
#include <chrono>
#include <string>
#include "modules/common/macro.h"
namespace apollo {
namespace perception {
using TimePoint = std::chrono::system_clock::time_point;
class Timer {
public:
Timer() = default;
// no-thread safe.
void start();
// return the elapsed time,
// also output msg and time in glog.
// automatically start a new timer.
// no-thread safe.
uint64_t end(const std::string& msg);
private:
DISALLOW_COPY_AND_ASSIGN(Timer);
// in ms.
TimePoint _start_time;
TimePoint _end_time;
};
class TimerWrapper {
public:
explicit TimerWrapper(const std::string& msg) : _msg(msg) {
_timer.start();
}
~TimerWrapper() {
_timer.end(_msg);
}
private:
DISALLOW_COPY_AND_ASSIGN(TimerWrapper);
Timer _timer;
std::string _msg;
};
} // namespace perception
} // namespace apollo
#define PERF_FUNCTION(function_name) \
apollo::perception::TimerWrapper _timer_wrapper_(function_name)
#define PERF_BLOCK_START() \
apollo::perception::Timer _timer_; \
_timer_.start()
#define PERF_BLOCK_END(msg) _timer_.end(msg)
#endif // MODULES_PERCEPTION_LIB_BASE_TIMER_H_
......@@ -40,7 +40,7 @@ class ConfigManagerTest : public testing::Test {
TEST_F(ConfigManagerTest, test_Init) {
EXPECT_TRUE(config_manager_->Init());
EXPECT_EQ(config_manager_->NumModels(), 2u);
EXPECT_EQ(config_manager_->NumModels(), 3u);
}
TEST_F(ConfigManagerTest, test_GetModelConfig) {
......@@ -59,7 +59,7 @@ TEST_F(ConfigManagerTest, test_GetModelConfig) {
TEST_F(ConfigManagerTest, test_ModelConfig) {
std::string model_name = "ROIFilterTest";
ASSERT_TRUE(config_manager_->Init());
ASSERT_EQ(config_manager_->NumModels(), 2u);
ASSERT_EQ(config_manager_->NumModels(), 3u);
const ModelConfig* model_config = NULL;
ASSERT_TRUE(config_manager_->GetModelConfig(model_name, &model_config));
ASSERT_EQ(model_config->name(), model_name);
......
......@@ -9,7 +9,7 @@ model_configs {
# @required: range > 0.0 && range - (-range) > cell_size
double_params {
name: "range"
value: 120.0
value: 70.0
}
# @name: cell_size
......
......@@ -27,6 +27,7 @@
#include "modules/common/log.h"
#include "modules/perception/common/perception_gflags.h"
#include "modules/perception/lib/base/timer.h"
#include "modules/perception/lib/config_manager/config_manager.h"
#include "modules/perception/obstacle/lidar/dummy/dummy_algorithms.h"
#include "modules/perception/obstacle/lidar/roi_filter/hdmap_roi_filter/hdmap_roi_filter.h"
......@@ -69,6 +70,7 @@ bool LidarProcess::Init() {
}
bool LidarProcess::Process(const sensor_msgs::PointCloud2& message) {
PERF_FUNCTION("LidarProcess");
objects_.clear();
const double kTimeStamp = message.header.stamp.toSec();
timestamp_ = kTimeStamp;
......@@ -76,6 +78,7 @@ bool LidarProcess::Process(const sensor_msgs::PointCloud2& message) {
AINFO << "process the " << seq_num_ << " frame. timestamp: " << timestamp_;
PERF_BLOCK_START();
/// get velodyne2world transfrom
std::shared_ptr<Matrix4d> velodyne_trans = std::make_shared<Matrix4d>();
if (!GetVelodyneTrans(kTimeStamp, velodyne_trans.get())) {
......@@ -84,11 +87,13 @@ bool LidarProcess::Process(const sensor_msgs::PointCloud2& message) {
return false;
}
ADEBUG << "get trans pose succ.";
PERF_BLOCK_END("lidar_get_velodyne2world_transfrom");
PointCloudPtr point_cloud(new PointCloud);
TransPointCloudToPCL(message, &point_cloud);
ADEBUG << "transform pointcloud success. points num is: "
<< point_cloud->points.size();
PERF_BLOCK_END("lidar_transform_poindcloud");
if (!Process(timestamp_, point_cloud, velodyne_trans)) {
AERROR << "faile to process msg at timestamp: " << kTimeStamp;
......@@ -99,6 +104,7 @@ bool LidarProcess::Process(const sensor_msgs::PointCloud2& message) {
bool LidarProcess::Process(double timestamp, PointCloudPtr point_cloud,
std::shared_ptr<Matrix4d> velodyne_trans) {
PERF_BLOCK_START();
/// call hdmap to get ROI
HdmapStructPtr hdmap = nullptr;
if (hdmap_input_) {
......@@ -107,6 +113,7 @@ bool LidarProcess::Process(double timestamp, PointCloudPtr point_cloud,
PointD velodyne_pose_world = pcl::transformPoint(velodyne_pose, temp_trans);
hdmap.reset(new HdmapStruct);
hdmap_input_->GetROI(velodyne_pose_world, &hdmap);
PERF_BLOCK_END("lidar_get_roi_from_hdmap");
}
/// call roi_filter
......@@ -125,9 +132,9 @@ bool LidarProcess::Process(double timestamp, PointCloudPtr point_cloud,
return false;
}
}
ADEBUG << "call roi_filter succ. The num of roi_cloud is: "
<< roi_cloud->points.size();
PERF_BLOCK_END("lidar_roi_filter");
/// call segmentor
std::vector<ObjectPtr> objects;
......@@ -145,6 +152,7 @@ bool LidarProcess::Process(double timestamp, PointCloudPtr point_cloud,
}
}
ADEBUG << "call segmentation succ. The num of objects is: " << objects.size();
PERF_BLOCK_END("lidar_segmentation");
/// call object builder
if (object_builder_ != nullptr) {
......@@ -156,6 +164,7 @@ bool LidarProcess::Process(double timestamp, PointCloudPtr point_cloud,
}
}
ADEBUG << "call object_builder succ.";
PERF_BLOCK_END("lidar_object_builder");
/// call tracker
if (tracker_ != nullptr) {
......@@ -168,7 +177,8 @@ bool LidarProcess::Process(double timestamp, PointCloudPtr point_cloud,
return false;
}
}
ADEBUG << "lidar process succ, there are " << objects_.size()
PERF_BLOCK_END("lidar_tracker");
AINFO << "lidar process succ, there are " << objects_.size()
<< " tracked objects.";
return true;
}
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册