Skip to content

Commit

Permalink
Perception: update build and launch for lidar perception only
Browse files Browse the repository at this point in the history
  • Loading branch information
jeroldchen authored and jinghaomiao committed Jul 14, 2020
1 parent d186801 commit 1ab73b5
Show file tree
Hide file tree
Showing 55 changed files with 368 additions and 84 deletions.
File renamed without changes.
17 changes: 13 additions & 4 deletions modules/perception/base/hdmap_struct.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
#include <memory>
#include <vector>

#include "Eigen/StdVector"

#include "modules/perception/base/point_cloud.h"

namespace apollo {
Expand All @@ -35,10 +37,17 @@ struct alignas(16) LaneBoundary {
};

struct alignas(16) HdmapStruct {
std::vector<RoadBoundary> road_boundary;
std::vector<PointCloud<PointD>> road_polygons;
std::vector<PointCloud<PointD>> hole_polygons;
std::vector<PointCloud<PointD>> junction_polygons;
std::vector<RoadBoundary, Eigen::aligned_allocator<RoadBoundary> >
road_boundary;
std::vector<PointCloud<PointD>,
Eigen::aligned_allocator<PointCloud<PointD> > >
road_polygons;
std::vector<PointCloud<PointD>,
Eigen::aligned_allocator<PointCloud<PointD> > >
hole_polygons;
std::vector<PointCloud<PointD>,
Eigen::aligned_allocator<PointCloud<PointD> > >
junction_polygons;
};

using HdmapStructPtr = std::shared_ptr<HdmapStruct>;
Expand Down
File renamed without changes.
File renamed without changes.
36 changes: 36 additions & 0 deletions modules/perception/common/io/BUILD
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test")
load("//tools:cpplint.bzl", "cpplint")

package(default_visibility = ["//visibility:public"])

cc_library(
name = "io_util",
srcs = ["io_util.cc"],
hdrs = ["io_util.h"],
deps = [
"//cyber",
"//modules/perception/base:camera",
"//modules/perception/base:distortion_model",
"//modules/perception/base:omnidirectional_model",
"//modules/perception/common/geometry:basic",
"@boost",
"@com_github_jbeder_yaml_cpp//:yaml-cpp",
"@com_google_absl//absl/strings",
"@eigen",
],
)

cc_test(
name = "io_util_test",
size = "small",
srcs = ["io_util_test.cc"],
data = [
"//modules/perception:perception_testdata",
],
deps = [
":io_util",
"@com_google_googletest//:gtest_main",
],
)

cpplint()
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
50 changes: 50 additions & 0 deletions modules/perception/lidar/app/BUILD
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test")
load("//tools:cpplint.bzl", "cpplint")

package(default_visibility = ["//visibility:public"])

cc_library(
name = "app",
deps = [
":lidar_obstacle_detection",
":lidar_obstacle_tracking",
],
)

cc_library(
name = "lidar_obstacle_detection",
srcs = ["lidar_obstacle_detection.cc"],
hdrs = ["lidar_obstacle_detection.h"],
deps = [
"//cyber",
"//modules/perception/lib/utils",
"//modules/perception/lidar/app/proto:lidar_obstacle_detection_config_cc_proto",
"//modules/perception/lidar/lib/detection/lidar_point_pillars:point_pillars_detection",
# "//modules/perception/lidar/lib/map_manager",
# "//modules/perception/lidar/lib/object_builder",
# "//modules/perception/lidar/lib/object_filter_bank",
"//modules/perception/lidar/lib/pointcloud_preprocessor",
# "//modules/perception/lidar/lib/scene_manager",
"@eigen",
],
)

cc_library(
name = "lidar_obstacle_tracking",
srcs = ["lidar_obstacle_tracking.cc"],
hdrs = ["lidar_obstacle_tracking.h"],
deps = [
"//cyber",
"//modules/common/util",
"//modules/perception/base",
"//modules/perception/lib/config_manager",
"//modules/perception/lib/utils",
"//modules/perception/lidar/app/proto:lidar_obstacle_tracking_config_cc_proto",
"//modules/perception/lidar/common",
"//modules/perception/lidar/lib/interface:base_classifier",
"//modules/perception/lidar/lib/interface:base_multi_target_tracker",
"@eigen",
],
)

cpplint()
25 changes: 0 additions & 25 deletions modules/perception/lidar/app/lidar_obstacle_detection.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#include "modules/perception/lib/utils/perf.h"
#include "modules/perception/lidar/app/proto/lidar_obstacle_detection_config.pb.h"
#include "modules/perception/lidar/common/lidar_log.h"
#include "modules/perception/lidar/lib/scene_manager/scene_manager.h"

namespace apollo {
namespace perception {
Expand All @@ -45,26 +44,11 @@ bool LidarObstacleDetection::Init(
LidarObstacleDetectionConfig config;
ACHECK(cyber::common::GetProtoFromFile(config_file, &config));
detector_name_ = config.detector();
use_map_manager_ = config.use_map_manager();
use_object_filter_bank_ = config.use_object_filter_bank();

use_map_manager_ = use_map_manager_ && options.enable_hdmap_input;

SceneManagerInitOptions scene_manager_init_options;
ACHECK(SceneManager::Instance().Init(scene_manager_init_options));

PointCloudPreprocessorInitOptions preprocessor_init_options;
preprocessor_init_options.sensor_name = sensor_name;
ACHECK(cloud_preprocessor_.Init(preprocessor_init_options));

if (use_map_manager_) {
MapManagerInitOptions map_manager_init_options;
if (!map_manager_.Init(map_manager_init_options)) {
AINFO << "Failed to init map manager.";
use_map_manager_ = false;
}
}

detector_.reset(new PointPillarsDetection);
// detector_.reset(
// BaseSegmentationRegisterer::GetInstanceByName(segmentor_name_));
Expand Down Expand Up @@ -113,15 +97,6 @@ LidarProcessResult LidarObstacleDetection::ProcessCommon(
const auto& sensor_name = options.sensor_name;

PERCEPTION_PERF_BLOCK_START();
if (use_map_manager_) {
MapManagerOptions map_manager_options;
if (!map_manager_.Update(map_manager_options, frame)) {
return LidarProcessResult(LidarErrorCode::MapManagerError,
"Failed to update map structure.");
}
}
PERCEPTION_PERF_BLOCK_END_WITH_INDICATOR(sensor_name, "map_manager");

DetectionOptions detection_options;
if (!detector_->Detect(detection_options, frame)) {
return LidarProcessResult(LidarErrorCode::DetectionError,
Expand Down
10 changes: 0 additions & 10 deletions modules/perception/lidar/app/lidar_obstacle_detection.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,6 @@

#include "modules/perception/lidar/common/lidar_error_code.h"
#include "modules/perception/lidar/lib/detection/lidar_point_pillars/point_pillars_detection.h"
#include "modules/perception/lidar/lib/interface/base_classifier.h"
#include "modules/perception/lidar/lib/map_manager/map_manager.h"
#include "modules/perception/lidar/lib/object_builder/object_builder.h"
#include "modules/perception/lidar/lib/object_filter_bank/object_filter_bank.h"
#include "modules/perception/lidar/lib/pointcloud_preprocessor/pointcloud_preprocessor.h"

namespace apollo {
Expand All @@ -34,7 +30,6 @@ namespace lidar {

struct LidarObstacleDetectionInitOptions {
std::string sensor_name = "velodyne64";
bool enable_hdmap_input = true;
};

struct LidarObstacleDetectionOptions {
Expand Down Expand Up @@ -68,14 +63,9 @@ class LidarObstacleDetection {

private:
PointCloudPreprocessor cloud_preprocessor_;
MapManager map_manager_;
std::unique_ptr<PointPillarsDetection> detector_;
ObjectBuilder builder_;
ObjectFilterBank filter_bank_;
// params
std::string detector_name_;
bool use_map_manager_ = true;
bool use_object_filter_bank_ = true;
}; // class LidarObstacleDetection

} // namespace lidar
Expand Down
5 changes: 2 additions & 3 deletions modules/perception/lidar/common/pcl_util.h
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,5 @@ POINT_CLOUD_REGISTER_POINT_STRUCT(apollo::perception::lidar::PCLPointXYZIT,
intensity)(double, timestamp, timestamp))

POINT_CLOUD_REGISTER_POINT_STRUCT(apollo::perception::lidar::PCLPointXYZL,
(float, x, x)(float, y, y)(float, z,
z)(uint32_t, label,
label))
(float, x, x)(float, y, y)(float, z, z)(
std::uint32_t, label, label))
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,15 @@
* limitations under the License.
*****************************************************************************/
#pragma once
#include <functional>
#include <map>
#include <memory>
#include <string>
#include <utility>
#include <vector>

#include "Eigen/StdVector"

#include "modules/perception/lidar/lib/classifier/fused_classifier/type_fusion_interface.h"
#include "modules/perception/lidar/lib/classifier/fused_classifier/util.h"

Expand All @@ -28,6 +32,8 @@ namespace lidar {

class CCRFOneShotTypeFusion : public BaseOneShotTypeFusion {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

bool Init(const TypeFusionInitOption& option) override;
bool TypeFusion(const TypeFusionOption& option,
std::shared_ptr<perception::base::Object> object) override;
Expand All @@ -37,12 +43,16 @@ class CCRFOneShotTypeFusion : public BaseOneShotTypeFusion {
Vectord* log_prob);

protected:
std::map<std::string, Matrixd> smooth_matrices_;
std::map<std::string, Matrixd, std::less<std::string>,
Eigen::aligned_allocator<std::pair<const std::string, Matrixd>>>
smooth_matrices_;
Matrixd confidence_smooth_matrix_;
};

class CCRFSequenceTypeFusion : public BaseSequenceTypeFusion {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

bool Init(const TypeFusionInitOption& option) override;
bool TypeFusion(const TypeFusionOption& option,
TrackedObjects* tracked_objects) override;
Expand Down Expand Up @@ -72,9 +82,9 @@ class CCRFSequenceTypeFusion : public BaseSequenceTypeFusion {
Matrixd transition_matrix_;

// data member for window inference version
std::vector<Vectord> fused_oneshot_probs_;
std::vector<Vectord> fused_sequence_probs_;
std::vector<Vectori> state_back_trace_;
std::vector<Vectord, Eigen::aligned_allocator<Vectord>> fused_oneshot_probs_;
std::vector<Vectord, Eigen::aligned_allocator<Vectord>> fused_sequence_probs_;
std::vector<Vectori, Eigen::aligned_allocator<Vectori>> state_back_trace_;

protected:
double s_alpha_ = 1.8;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -102,8 +102,11 @@ bool LoadSingleMatrixFile(const std::string& filename, Matrixd* matrix) {
return true;
}

bool LoadMultipleMatricesFile(const std::string& filename,
std::map<std::string, Matrixd>* matrices) {
bool LoadMultipleMatricesFile(
const std::string& filename,
std::map<std::string, Matrixd, std::less<std::string>,
Eigen::aligned_allocator<std::pair<const std::string, Matrixd> > >*
matrices) {
if (matrices == nullptr) {
return false;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,10 @@
#pragma once

#include <fstream>
#include <functional>
#include <map>
#include <string>
#include <utility>
#include <vector>

#include "Eigen/Dense"
Expand Down Expand Up @@ -56,8 +58,11 @@ bool LoadSingleMatrix(std::ifstream& fin, Matrixd* matrix);

bool LoadSingleMatrixFile(const std::string& filename, Matrixd* matrix);

bool LoadMultipleMatricesFile(const std::string& filename,
std::map<std::string, Matrixd>* matrices);
bool LoadMultipleMatricesFile(
const std::string& filename,
std::map<std::string, Matrixd, std::less<std::string>,
Eigen::aligned_allocator<std::pair<const std::string, Matrixd> > >*
matrices);

} // namespace util
} // namespace lidar
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,8 @@ bool PointPillarsDetection::Detect(const DetectionOptions& options,
Timer timer;

int num_points;
cur_cloud_ptr_ = std::make_shared<base::PointFCloud>(*original_cloud_);
// cur_cloud_ptr_ = std::make_shared<base::PointFCloud>(*original_cloud_);
cur_cloud_ptr_ = original_cloud_; // TODO(chenjiahao): for emergency use

// down sample the point cloud through filtering beams
if (FLAGS_enable_downsample_beams) {
Expand Down
43 changes: 43 additions & 0 deletions modules/perception/lidar/lib/interface/BUILD
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
load("@rules_cc//cc:defs.bzl", "cc_library")
load("//tools:cpplint.bzl", "cpplint")

package(default_visibility = ["//visibility:public"])

cc_library(
name = "interface",
deps = [
":base_bipartite_graph_matcher",
":base_classifier",
":base_multi_target_tracker",
],
)

cc_library(
name = "base_bipartite_graph_matcher",
hdrs = ["base_bipartite_graph_matcher.h"],
deps = [
"//modules/perception/common/graph:secure_matrix",
"//modules/perception/lib/registerer",
"@eigen",
],
)

cc_library(
name = "base_classifier",
hdrs = ["base_classifier.h"],
deps = [
"//modules/perception/lib/registerer",
"//modules/perception/lidar/common:lidar_frame",
],
)

cc_library(
name = "base_multi_target_tracker",
hdrs = ["base_multi_target_tracker.h"],
deps = [
"//modules/perception/lib/registerer",
"//modules/perception/lidar/common:lidar_frame",
],
)

cpplint()
4 changes: 4 additions & 0 deletions modules/perception/lidar/lib/tracker/common/mlf_track_data.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,8 @@ namespace perception {
namespace lidar {

struct MlfPredict {
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Eigen::VectorXf state;
base::PolygonDType polygon;
base::PointDCloud cloud;
Expand All @@ -43,6 +45,8 @@ struct MlfPredict {

class MlfTrackData : public TrackData {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

MlfTrackData() = default;
~MlfTrackData() = default;

Expand Down
File renamed without changes.
Loading

0 comments on commit 1ab73b5

Please sign in to comment.