Skip to content

Commit

Permalink
Perception: simplify using Eigen
Browse files Browse the repository at this point in the history
  • Loading branch information
jeroldchen authored and storypku committed Jul 21, 2020
1 parent e9346c6 commit 8602c01
Show file tree
Hide file tree
Showing 13 changed files with 62 additions and 97 deletions.
7 changes: 7 additions & 0 deletions modules/common/util/eigen_defs.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,10 @@

#pragma once

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

#include "Eigen/Geometry"

Expand All @@ -28,6 +31,10 @@ namespace common {
template <class EigenType>
using EigenVector = std::vector<EigenType, Eigen::aligned_allocator<EigenType>>;

template <typename T, class EigenType>
using EigenMap = std::map<T, EigenType, std::less<T>,
Eigen::aligned_allocator<std::pair<const T, EigenType>>>;

using EigenVector3dVec = EigenVector<Eigen::Vector3d>;
using EigenAffine3dVec = EigenVector<Eigen::Affine3d>;

Expand Down
3 changes: 3 additions & 0 deletions modules/perception/base/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,9 @@ cc_library(
"sensor_meta.h",
"vehicle_struct.h",
],
deps = [
"//modules/common/util:eigen_defs",
],
)

cc_library(
Expand Down
18 changes: 5 additions & 13 deletions modules/perception/base/hdmap_struct.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,7 @@
#include <memory>
#include <vector>

#include "Eigen/StdVector"

#include "modules/common/util/eigen_defs.h"
#include "modules/perception/base/point_cloud.h"

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

struct alignas(16) HdmapStruct {
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;
apollo::common::EigenVector<RoadBoundary> road_boundary;
apollo::common::EigenVector<PointCloud<PointD>> road_polygons;
apollo::common::EigenVector<PointCloud<PointD>> hole_polygons;
apollo::common::EigenVector<PointCloud<PointD>> junction_polygons;
};

using HdmapStructPtr = std::shared_ptr<HdmapStruct>;
Expand Down
1 change: 1 addition & 0 deletions modules/perception/common/geometry/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ cc_library(
name = "common",
hdrs = ["common.h"],
deps = [
"//modules/common/util:eigen_defs",
"//modules/perception/base:box",
"//modules/perception/base:point_cloud",
],
Expand Down
4 changes: 2 additions & 2 deletions modules/perception/common/geometry/basic_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#include "modules/perception/common/geometry/basic.h"

#include "gtest/gtest.h"
#include "modules/common/util/eigen_defs.h"
#include "modules/perception/base/point_cloud.h"
#include "modules/perception/common/geometry/common.h"

Expand Down Expand Up @@ -347,8 +348,7 @@ TEST(GeometryCommonTest, calculate_dist_and_dir_to_boundary) {
TEST(GeometryCommonTest, calculate_dist_and_dir_to_boundary_lists) {
Eigen::Vector3f pt(0.0, 0.0, 0.0);
PointCloud<PointF> left, right;
std::vector<PointCloud<PointF>, Eigen::aligned_allocator<PointCloud<PointF>>>
left_list, right_list;
apollo::common::EigenVector<PointCloud<PointF>> left_list, right_list;
base::PointF temp;
temp.x = 10.f;
temp.y = 0.f;
Expand Down
11 changes: 5 additions & 6 deletions modules/perception/common/geometry/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,12 @@
#include <vector>

#include "Eigen/Core"
#include "modules/common/util/eigen_defs.h"
#include "modules/perception/base/box.h"
#include "modules/perception/base/point_cloud.h"

using apollo::common::EigenVector;

namespace apollo {
namespace perception {
namespace common {
Expand Down Expand Up @@ -310,12 +313,8 @@ void CalculateDistAndDirToBoundary(
template <typename PointT>
void CalculateDistAndDirToBoundary(
const Eigen::Matrix<typename PointT::Type, 3, 1> &pt,
const std::vector<base::PointCloud<PointT>,
Eigen::aligned_allocator<base::PointCloud<PointT>>>
&left_boundary,
const std::vector<base::PointCloud<PointT>,
Eigen::aligned_allocator<base::PointCloud<PointT>>>
&right_boundary,
const EigenVector<base::PointCloud<PointT>> &left_boundary,
const EigenVector<base::PointCloud<PointT>> &right_boundary,
typename PointT::Type *dist,
Eigen::Matrix<typename PointT::Type, 3, 1> *dir) {
using Type = typename PointT::Type;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ cc_library(
hdrs = ["util.h"],
deps = [
"//cyber",
"//modules/common/util:eigen_defs",
"//modules/perception/base:object",
"@eigen",
],
Expand All @@ -32,6 +33,7 @@ cc_library(
":type_fusion_interface",
":util",
"//cyber",
"//modules/common/util:eigen_defs",
"//modules/perception/base:object",
"//modules/perception/base:point_cloud",
"//modules/perception/lib/config_manager",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,14 +18,15 @@
#include <map>
#include <memory>
#include <string>
#include <utility>
#include <vector>

#include "Eigen/StdVector"

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

using apollo::common::EigenMap;
using apollo::common::EigenVector;

namespace apollo {
namespace perception {
namespace lidar {
Expand All @@ -43,9 +44,7 @@ class CCRFOneShotTypeFusion : public BaseOneShotTypeFusion {
Vectord* log_prob);

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

Expand Down Expand Up @@ -82,9 +81,9 @@ class CCRFSequenceTypeFusion : public BaseSequenceTypeFusion {
Matrixd transition_matrix_;

// data member for window inference version
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_;
EigenVector<Vectord> fused_oneshot_probs_;
EigenVector<Vectord> fused_sequence_probs_;
EigenVector<Vectori> state_back_trace_;

protected:
double s_alpha_ = 1.8;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -104,9 +104,7 @@ bool LoadSingleMatrixFile(const std::string& filename, Matrixd* matrix) {

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) {
EigenMap<std::string, Matrixd>* matrices) {
if (matrices == nullptr) {
return false;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,15 @@
#include <functional>
#include <map>
#include <string>
#include <utility>
#include <vector>

#include "Eigen/Dense"

#include "modules/common/util/eigen_defs.h"
#include "modules/perception/base/object_types.h"

using apollo::common::EigenMap;

namespace apollo {
namespace perception {
namespace lidar {
Expand Down Expand Up @@ -59,10 +61,7 @@ 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, std::less<std::string>,
Eigen::aligned_allocator<std::pair<const std::string, Matrixd> > >*
matrices);
const std::string& filename, EigenMap<std::string, Matrixd>* matrices);

} // namespace util
} // namespace lidar
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,8 +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_ = original_cloud_; // TODO(chenjiahao): for emergency use
cur_cloud_ptr_ = std::shared_ptr<base::PointFCloud>(
new base::PointFCloud(*original_cloud_));

// down sample the point cloud through filtering beams
if (FLAGS_enable_downsample_beams) {
Expand Down
42 changes: 11 additions & 31 deletions modules/perception/map/hdmap/hdmap_input.cc
Original file line number Diff line number Diff line change
Expand Up @@ -130,8 +130,7 @@ bool HDMapInput::GetRoiHDMapStruct(
hdmap_struct_ptr->road_polygons.clear();

// Merge boundary and junction
std::vector<base::RoadBoundary, Eigen::aligned_allocator<base::RoadBoundary> >
road_boundaries;
EigenVector<base::RoadBoundary> road_boundaries;
MergeBoundaryJunction(road_boundary_vec, junctions_vec, &road_boundaries,
&(hdmap_struct_ptr->road_polygons),
&(hdmap_struct_ptr->junction_polygons));
Expand All @@ -145,14 +144,9 @@ bool HDMapInput::GetRoiHDMapStruct(
void HDMapInput::MergeBoundaryJunction(
const std::vector<apollo::hdmap::RoadRoiPtr>& boundary,
const std::vector<apollo::hdmap::JunctionInfoConstPtr>& junctions,
std::vector<RoadBoundary, Eigen::aligned_allocator<RoadBoundary> >*
road_boundaries_ptr,
std::vector<base::PointCloud<base::PointD>,
Eigen::aligned_allocator<base::PointCloud<base::PointD> > >*
road_polygons_ptr,
std::vector<base::PointCloud<base::PointD>,
Eigen::aligned_allocator<base::PointCloud<base::PointD> > >*
junction_polygons_ptr) {
EigenVector<base::RoadBoundary>* road_boundaries_ptr,
EigenVector<base::PointCloud<base::PointD>>* road_polygons_ptr,
EigenVector<base::PointCloud<base::PointD>>* junction_polygons_ptr) {
const int boundary_size = static_cast<int>(boundary.size());
const int junctions_size = static_cast<int>(junctions.size());
const int polygon_size = boundary_size;
Expand Down Expand Up @@ -234,23 +228,13 @@ void HDMapInput::MergeBoundaryJunction(
}

bool HDMapInput::GetRoadBoundaryFilteredByJunctions(
const std::vector<base::RoadBoundary,
Eigen::aligned_allocator<base::RoadBoundary> >&
road_boundaries,
const std::vector<
base::PointCloud<base::PointD>,
Eigen::aligned_allocator<base::PointCloud<base::PointD> > >& junctions,
std::vector<base::RoadBoundary,
Eigen::aligned_allocator<base::RoadBoundary> >*
flt_road_boundaries_ptr) {
const EigenVector<base::RoadBoundary>& road_boundaries,
const EigenVector<base::PointCloud<base::PointD>>& junctions,
EigenVector<base::RoadBoundary>* flt_road_boundaries_ptr) {
for (size_t n_rd = 0; n_rd < road_boundaries.size(); ++n_rd) {
const base::RoadBoundary& temp_road_boundary = road_boundaries[n_rd];
std::vector<base::PointCloud<base::PointD>,
Eigen::aligned_allocator<base::PointCloud<base::PointD> > >
temp_left_boundary_vec;
std::vector<base::PointCloud<base::PointD>,
Eigen::aligned_allocator<base::PointCloud<base::PointD> > >
temp_right_boundary_vec;
EigenVector<base::PointCloud<base::PointD>> temp_left_boundary_vec;
EigenVector<base::PointCloud<base::PointD>> temp_right_boundary_vec;
// Filter left boundary points
this->SplitBoundary(temp_road_boundary.left_boundary, junctions,
&temp_left_boundary_vec);
Expand Down Expand Up @@ -324,12 +308,8 @@ void HDMapInput::DownsamplePoints(const base::PointDCloudPtr& raw_cloud_ptr,

void HDMapInput::SplitBoundary(
const base::PointCloud<base::PointD>& boundary_line,
const std::vector<
base::PointCloud<base::PointD>,
Eigen::aligned_allocator<base::PointCloud<base::PointD> > >& junctions,
std::vector<base::PointCloud<base::PointD>,
Eigen::aligned_allocator<base::PointCloud<base::PointD> > >*
boundary_line_vec_ptr) {
const EigenVector<base::PointCloud<base::PointD>>& junctions,
EigenVector<base::PointCloud<base::PointD>>* boundary_line_vec_ptr) {
std::vector<bool> boundary_flag(boundary_line.size());
for (size_t npt = 0; npt < boundary_line.size(); ++npt) {
const PointD& pointd = boundary_line[npt];
Expand Down
37 changes: 11 additions & 26 deletions modules/perception/map/hdmap/hdmap_input.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,11 +21,14 @@
#include <vector>

#include "cyber/common/macros.h"
#include "modules/common/util/eigen_defs.h"
#include "modules/map/hdmap/hdmap.h"
#include "modules/map/hdmap/hdmap_common.h"
#include "modules/perception/base/hdmap_struct.h"
#include "modules/perception/lib/thread/mutex.h"

using apollo::common::EigenVector;

namespace apollo {
namespace perception {
namespace map {
Expand All @@ -49,41 +52,23 @@ class HDMapInput {
void MergeBoundaryJunction(
const std::vector<apollo::hdmap::RoadRoiPtr>& boundary,
const std::vector<apollo::hdmap::JunctionInfoConstPtr>& junctions,
std::vector<base::RoadBoundary,
Eigen::aligned_allocator<base::RoadBoundary> >*
road_boundaries_ptr,
std::vector<base::PointCloud<base::PointD>,
Eigen::aligned_allocator<base::PointCloud<base::PointD> > >*
road_polygons_ptr,
std::vector<base::PointCloud<base::PointD>,
Eigen::aligned_allocator<base::PointCloud<base::PointD> > >*
junction_polygons_ptr);
EigenVector<base::RoadBoundary>* road_boundaries_ptr,
EigenVector<base::PointCloud<base::PointD>>* road_polygons_ptr,
EigenVector<base::PointCloud<base::PointD>>* junction_polygons_ptr);

bool GetRoadBoundaryFilteredByJunctions(
const std::vector<base::RoadBoundary,
Eigen::aligned_allocator<base::RoadBoundary> >&
road_boundaries,
const std::vector<
base::PointCloud<base::PointD>,
Eigen::aligned_allocator<base::PointCloud<base::PointD> > >&
junctions,
std::vector<base::RoadBoundary,
Eigen::aligned_allocator<base::RoadBoundary> >*
flt_road_boundaries_ptr);
const EigenVector<base::RoadBoundary>& road_boundaries,
const EigenVector<base::PointCloud<base::PointD>>& junctions,
EigenVector<base::RoadBoundary>* flt_road_boundaries_ptr);

void DownsamplePoints(const base::PointDCloudPtr& raw_cloud_ptr,
base::PointCloud<base::PointD>* polygon_ptr,
size_t min_points_num_for_sample = 15) const;

void SplitBoundary(
const base::PointCloud<base::PointD>& boundary_line,
const std::vector<
base::PointCloud<base::PointD>,
Eigen::aligned_allocator<base::PointCloud<base::PointD> > >&
junctions,
std::vector<base::PointCloud<base::PointD>,
Eigen::aligned_allocator<base::PointCloud<base::PointD> > >*
boundary_line_vec_ptr);
const EigenVector<base::PointCloud<base::PointD>>& junctions,
EigenVector<base::PointCloud<base::PointD>>* boundary_line_vec_ptr);

bool GetSignalsFromHDMap(const Eigen::Vector3d& pointd,
double forward_distance,
Expand Down

0 comments on commit 8602c01

Please sign in to comment.