提交 84602d92 编写于 作者: L Liangliang Zhang 提交者: Jiangtao Hu

All: added -Werror for certain warnings and fixed existing warnings.

上级 dbf94f12
......@@ -88,3 +88,6 @@ modules/calibration/data/mkz056
# Data bag
docs/demo_guide/*.bag
# Cybertron
framework/cybertron/log/*
......@@ -28,6 +28,14 @@ jobs:
- ./apollo_docker.sh ${JOB}
- rm -rf "${HOME}/.cache/bazel/_bazel_${USER}/install"
- rm -rf "/apollo/data/core"
- # stage: stage-02
env:
- JOB=cibuild_extended
script:
- ./docker/scripts/dev_start.sh -t dev-x86_64-20181001_1754-ci
- ./apollo_docker.sh ${JOB}
- rm -rf "${HOME}/.cache/bazel/_bazel_${USER}/install"
- rm -rf "/apollo/data/core"
- # stage: stage-02
env:
- JOB=citest_basic
......
......@@ -178,11 +178,9 @@ function build() {
fi
}
function cibuild() {
function cibuild_extended() {
info "Building framework ..."
build_proto
#cd /apollo/framework
#bash cybertron.sh build_fast
cd /apollo
info "Building modules ..."
......@@ -195,9 +193,7 @@ function cibuild() {
info "Building with $JOB_ARG for $MACHINE_ARCH"
BUILD_TARGETS="
//framework/...
//modules/canbus/...
//modules/common/...
//modules/control/...
//modules/perception/...
//modules/dreamview/...
//modules/drivers/radar/conti_radar/...
//modules/drivers/radar/racobit_radar/...
......@@ -208,12 +204,38 @@ function cibuild() {
//modules/guardian/...
//modules/localization/...
//modules/map/...
//modules/perception/...
//modules/third_party_perception/...
"
bazel build $JOB_ARG $DEFINES $@ $BUILD_TARGETS
if [ $? -eq 0 ]; then
success 'Build passed!'
else
fail 'Build failed!'
fi
}
function cibuild() {
info "Building framework ..."
build_proto
cd /apollo
info "Building modules ..."
JOB_ARG="--jobs=$(nproc)"
if [ "$MACHINE_ARCH" == 'aarch64' ]; then
JOB_ARG="--jobs=3"
fi
info "Building with $JOB_ARG for $MACHINE_ARCH"
BUILD_TARGETS="
//framework/...
//modules/canbus/...
//modules/common/...
//modules/control/...
//modules/planning/...
//modules/prediction/...
//modules/routing/...
//modules/transform/...
//modules/third_party_perception/...
//modules/transform/..."
bazel build $JOB_ARG $DEFINES $@ $BUILD_TARGETS
......@@ -795,6 +817,10 @@ function main() {
DEFINES="${DEFINES} --cxxopt=-DCPU_ONLY"
cibuild $@
;;
cibuild_extended)
DEFINES="${DEFINES} --cxxopt=-DCPU_ONLY"
cibuild_extended $@
;;
build_opt)
DEFINES="${DEFINES} --cxxopt=-DCPU_ONLY --copt=-fpic"
apollo_build_opt $@
......
......@@ -141,7 +141,7 @@ std::shared_ptr<ProcessorContext> Scheduler::FindProc(
}
if (cr->processor_id() != -1 && cr->processor_id() != cur_proc_ &&
cr->processor_id() < proc_ctxs_.size()) {
cr->processor_id() < static_cast<int>(proc_ctxs_.size())) {
cr->set_processor_id(proc_ctxs_[cr->processor_id()]->id());
return proc_ctxs_[cr->processor_id()];
}
......@@ -171,7 +171,7 @@ std::shared_ptr<ProcessorContext> Scheduler::FindProc(
bool Scheduler::DispatchTask(const std::shared_ptr<CRoutine>& croutine) {
auto ctx = FindProc(croutine);
if (croutine->processor_id() >= proc_num_ ||
if (croutine->processor_id() >= static_cast<int>(proc_num_) ||
(croutine->processor_id() < 0 && ctx)) {
AERROR << GlobalData::GetTaskNameById(croutine->id())
<< "push failed, get processor failed, "
......
......@@ -55,6 +55,7 @@ class ChannelMessage : public GeneralMessageBase {
case ChannelMessage::ErrorCode::MessageTypeIsEmptr:
return "Message Type is Empty";
}
return "";
}
static bool isErrorCode(void* ptr) {
......
......@@ -81,7 +81,7 @@ void GeneralChannelMessage::RenderInfo(const Screen* s, int key,
auto iter = vec->cbegin();
int y = page_index_ * page_item_count_;
if (y < vec->size()) {
if (y < static_cast<int>(vec->size())) {
y = 0;
while (y < page_index_ * page_item_count_) {
++iter;
......
......@@ -62,12 +62,15 @@ int GeneralMessageBase::lineCountOfField(
break;
}
case google::protobuf::FieldDescriptor::CPPTYPE_MESSAGE:
case google::protobuf::FieldDescriptor::CPPTYPE_MESSAGE: {
const google::protobuf::Message& childMsg =
reflection->GetMessage(msg, field);
ret += lineCount(childMsg, screenWidth);
break;
}
default:
break;
} // end switch
}
......@@ -88,8 +91,8 @@ void GeneralMessageBase::PrintMessage(GeneralMessageBase* baseMsg,
reflection->ListFields(msg, &fields);
}
for (std::size_t i = 0; i < fields.size(); ++i) {
if (lineNo > s->Height()) {
for (size_t i = 0; i < fields.size(); ++i) {
if (lineNo > static_cast<unsigned>(s->Height())) {
break;
}
const google::protobuf::FieldDescriptor* field = fields[i];
......
......@@ -311,7 +311,7 @@ int main(int argc, char** argv) {
::apollo::cybertron::Init(argv[0]);
// TODO @baownayu order input record file
bool play_result = true;
for (auto& opt_file : opt_file_vec) {
for (size_t i = 0; i < opt_file_vec.size(); ++i) {
Player player(opt_file_vec[0], opt_white_channels.empty(),
opt_white_channels, opt_loop, opt_rate, opt_begin, opt_end,
opt_start, opt_delay);
......
......@@ -13,13 +13,13 @@
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include <iostream>
#include "modules/perception/common/i_lib/pc/i_ground.h"
#include <algorithm>
#include <cassert>
#include <cfloat>
#include <cmath>
#include <algorithm>
#include <iostream>
#include <utility>
#include "modules/perception/common/i_lib/pc/i_ground.h"
namespace apollo {
namespace perception {
......@@ -122,9 +122,9 @@ void PlaneFitGroundDetector::InitOrderTable(const VoxelGridXY<float> *vg,
map_dist.push_back(std::pair<float, int>(dist2, i));
}
sort(map_dist.begin(), map_dist.end(),
[](const std::pair<float, int> & a, const std::pair<float, int> & b) {
return a.first < b.first;
});
[](const std::pair<float, int> &a, const std::pair<float, int> &b) {
return a.first < b.first;
});
for (i = 0; i < map_dist.size(); ++i) {
id = map_dist[i].second;
const auto &voxel = vg->GetConstVoxels()[id];
......@@ -365,7 +365,8 @@ void PlaneFitGroundDetector::ComputeAdaptiveThreshold() {
&max_dist);
if (max_dist - min_dist < Constant<float>::EPSILON()) {
thre = (param_.planefit_dist_threshold_near +
param_.planefit_dist_threshold_far) / 2;
param_.planefit_dist_threshold_far) /
2;
for (r = 0; r < param_.nr_grids_coarse; ++r) {
for (c = 0; c < param_.nr_grids_coarse; ++c) {
pf_thresholds_[r][c] = thre;
......@@ -421,8 +422,8 @@ void PlaneFitGroundDetector::ComputeSignedGroundHeightLine(
int pos = 0;
char label = 0;
const float *cptr = nullptr;
float dist[] = { 0, 0, 0, 0, 0 };
const float *plane[] = { nullptr, nullptr, nullptr, nullptr, nullptr };
float dist[] = {0, 0, 0, 0, 0};
const float *plane[] = {nullptr, nullptr, nullptr, nullptr, nullptr};
float min_abs_dist = 0;
unsigned int nm1 = param_.nr_grids_coarse - 1;
assert(param_.nr_grids_coarse >= 2);
......@@ -635,7 +636,7 @@ int PlaneFitGroundDetector::FitGrid(const float *point_cloud,
int i = 0;
int j = 0;
int rseed = I_DEFAULT_SEED;
int indices_trial[] = { 0, 0, 0 };
int indices_trial[] = {0, 0, 0};
int nr_samples = candi->Prune(param_.nr_samples_min_threshold,
param_.nr_samples_max_threshold);
int nr_inliers_termi =
......@@ -835,10 +836,9 @@ int PlaneFitGroundDetector::FitGridWithNeighbors(
int nr_inliers = 0;
int nr_inliers_best = -1;
float angle_best = FLT_MAX;
int i = 0;
int j = 0;
int rseed = I_DEFAULT_SEED;
int indices_trial[] = { 0, 0, 0 };
int indices_trial[] = {0, 0, 0};
int nr_samples = candi.Prune(param_.nr_samples_min_threshold,
param_.nr_samples_max_threshold);
int nr_inliers_termi =
......@@ -851,13 +851,13 @@ int PlaneFitGroundDetector::FitGridWithNeighbors(
int r_n = 0;
int c_n = 0;
float angle = -1.f;
for (i = 0; i < nr_samples; ++i) {
for (int i = 0; i < nr_samples; ++i) {
assert(candi[i] < static_cast<int>(nr_points));
ICopy3(point_cloud + (nr_point_element * candi[i]), pdst);
pdst += dim_point_;
}
// generate plane hypothesis and vote
for (i = 0; i < param_.nr_ransac_iter_threshold; ++i) {
for (int i = 0; i < param_.nr_ransac_iter_threshold; ++i) {
IRandomSample(indices_trial, 3, nr_samples, &rseed);
IScale3(indices_trial, dim_point_);
ICopy3(pf_threeds_ + indices_trial[0], samples);
......@@ -872,7 +872,7 @@ int PlaneFitGroundDetector::FitGridWithNeighbors(
// threshold
psrc = pf_threeds_;
nr_inliers = 0;
for (j = 0; j < nr_samples; ++j) {
for (int j = 0; j < nr_samples; ++j) {
ptp_dist = IPlaneToPointDistanceWUnitNorm(hypothesis[i].params, psrc);
if (ptp_dist < dist_thre) {
nr_inliers++;
......@@ -887,7 +887,7 @@ int PlaneFitGroundDetector::FitGridWithNeighbors(
}
}
for (i = 0; i < neighbors.size(); ++i) {
for (size_t i = 0; i < neighbors.size(); ++i) {
r_n = neighbors[i].first;
c_n = neighbors[i].second;
if (ground_planes_[r_n][c_n].IsValid()) {
......@@ -895,7 +895,7 @@ int PlaneFitGroundDetector::FitGridWithNeighbors(
ground_planes_[r_n][c_n];
psrc = pf_threeds_;
nr_inliers = 0;
for (j = 0; j < nr_samples; ++j) {
for (int j = 0; j < nr_samples; ++j) {
ptp_dist = IPlaneToPointDistanceWUnitNorm(
hypothesis[i + param_.nr_ransac_iter_threshold].params, psrc);
if (ptp_dist < dist_thre) {
......@@ -912,7 +912,7 @@ int PlaneFitGroundDetector::FitGridWithNeighbors(
}
nr_inliers_best = -1;
for (i = 0; i < kNr_iter; ++i) {
for (int i = 0; i < kNr_iter; ++i) {
if (!(hypothesis[i].IsValid())) {
continue;
}
......@@ -948,7 +948,7 @@ int PlaneFitGroundDetector::FitGridWithNeighbors(
nr_inliers = 0;
psrc = pf_threeds_;
pdst = pf_threeds_;
for (i = 0; i < nr_samples; ++i) {
for (int i = 0; i < nr_samples; ++i) {
ptp_dist = IPlaneToPointDistanceWUnitNorm(groundplane->params, psrc);
if (ptp_dist < dist_thre) {
ICopy3(psrc, pdst);
......@@ -976,7 +976,8 @@ int PlaneFitGroundDetector::FitGridWithNeighbors(
float cx = voxel_cur.v_[0] + radius;
float cy = voxel_cur.v_[1] + radius;
float cz = -(groundplane->params[0] * cx + groundplane->params[1] * cy +
groundplane->params[3]) / groundplane->params[2];
groundplane->params[3]) /
groundplane->params[2];
ground_z_[r][c].first = cz;
ground_z_[r][c].second = true;
......@@ -1116,8 +1117,8 @@ int PlaneFitGroundDetector::CompleteGrid(const GroundPlaneSpherical &lt,
const GroundPlaneSpherical &up,
const GroundPlaneSpherical &dn,
GroundPlaneSpherical *gp) {
int supports[] = { 0, 0, 0, 0 };
float weights[] = { 0.f, 0.f, 0.f, 0.f };
int supports[] = {0, 0, 0, 0};
float weights[] = {0.f, 0.f, 0.f, 0.f};
gp->ForceInvalid();
supports[0] = lt.GetNrSupport();
supports[1] = rt.GetNrSupport();
......@@ -1150,8 +1151,8 @@ int PlaneFitGroundDetector::SmoothGrid(const GroundPlaneSpherical &g,
const GroundPlaneSpherical &up,
const GroundPlaneSpherical &dn,
GroundPlaneSpherical *gp) {
int supports[] = { 0, 0, 0, 0, 0 };
float weights[] = { 0.f, 0.f, 0.f, 0.f, 0.f };
int supports[] = {0, 0, 0, 0, 0};
float weights[] = {0.f, 0.f, 0.f, 0.f, 0.f};
gp->ForceInvalid();
if (!g.IsValid()) {
return 0;
......@@ -1185,9 +1186,9 @@ int PlaneFitGroundDetector::SmoothGrid(const GroundPlaneSpherical &g,
weights[3] = static_cast<float>(supports[3]) / support_sum;
weights[4] = static_cast<float>(supports[4]) / support_sum;
// weighted average:
gp->theta =
weights[0] * lt.theta + weights[1] * rt.theta + weights[2] * up.theta +
weights[3] * dn.theta + weights[4] * g.theta;
gp->theta = weights[0] * lt.theta + weights[1] * rt.theta +
weights[2] * up.theta + weights[3] * dn.theta +
weights[4] * g.theta;
gp->phi = weights[0] * lt.phi + weights[1] * rt.phi + weights[2] * up.phi +
weights[3] * dn.phi + weights[4] * g.phi;
gp->d = weights[0] * lt.d + weights[1] * rt.d + weights[2] * up.d +
......@@ -1233,22 +1234,19 @@ bool PlaneFitGroundDetector::Detect(const float *point_cloud,
if (!vg_coarse_->SetS(point_cloud, nr_points, nr_point_elements)) {
return false;
}
int nr_candis = 0;
int nr_valid_grid = 0;
unsigned int r = 0;
unsigned int c = 0;
unsigned int iter = 0;
// Filter to generate plane fitting candidates
nr_candis = Filter();
// int nr_candis = Filter();
// std::cout << "# of plane candidates: " << nr_candis << std::endl;
// Fit local plane using ransac
// nr_valid_grid = Fit();
nr_valid_grid = FitInOrder();
// int nr_valid_grid = FitInOrder();
// std::cout << "# of valid plane geometry (fitting): " << nr_valid_grid <<
// std::endl;
// Smooth plane using neighborhood information:
for (iter = 0; iter < param_.nr_smooth_iter; ++iter) {
nr_valid_grid = Smooth();
for (int iter = 0; iter < param_.nr_smooth_iter; ++iter) {
Smooth();
}
for (r = 0; r < param_.nr_grids_coarse; ++r) {
......
......@@ -19,18 +19,18 @@
#include <smmintrin.h>
#include <cassert>
#include <vector>
#include <limits>
#include <vector>
#include "modules/perception/common/i_lib/core/i_alloc.h"
#include "modules/perception/common/i_lib/core/i_blas.h"
#include "modules/perception/common/i_lib/pc/i_util.h"
namespace apollo {
namespace perception {
namespace common {
template <typename T, unsigned int d> class PtCluster {
template <typename T, unsigned int d>
class PtCluster {
public:
typedef T *iterator;
typedef const T *const_iterator;
......@@ -119,12 +119,10 @@ template <typename T, unsigned int d> class PtCluster {
};
template <typename T, unsigned int d>
PtCluster<T, d>::PtCluster()
: data_(nullptr), nr_points_(0) {}
PtCluster<T, d>::PtCluster() : data_(nullptr), nr_points_(0) {}
template <typename T, unsigned int d>
PtCluster<T, d>::PtCluster(unsigned int n)
: data_(nullptr), nr_points_(n) {
PtCluster<T, d>::PtCluster(unsigned int n) : data_(nullptr), nr_points_(n) {
if (n != 0) {
data_ = IAllocAligned<T>(n * d, 4);
if (!data_ || !IVerifyAlignment(data_, 4)) {
......@@ -148,7 +146,8 @@ PtCluster<T, d>::PtCluster(const T *data, unsigned int n)
}
}
template <typename T, unsigned int d> void PtCluster<T, d>::CleanUp() {
template <typename T, unsigned int d>
void PtCluster<T, d>::CleanUp() {
IFreeAligned(&data_);
nr_points_ = 0;
}
......@@ -179,7 +178,8 @@ inline int IAssignPointToVoxel(const T *data, T bound_x_min, T bound_x_max,
return (i);
}
template <typename T> class Voxel {
template <typename T>
class Voxel {
public:
Voxel() {}
~Voxel() {}
......@@ -244,9 +244,9 @@ template <typename T> class Voxel {
void PushBack(int id) { indices_.push_back(id); }
unsigned int Capacity() const { return (unsigned int) indices_.capacity(); }
unsigned int Capacity() const { return (unsigned int)indices_.capacity(); }
unsigned int NrPoints() const { return (unsigned int) indices_.size(); }
unsigned int NrPoints() const { return (unsigned int)indices_.size(); }
bool Empty() const { return indices_.empty(); }
......@@ -260,7 +260,8 @@ template <typename T> class Voxel {
};
// -----Voxel Grid XY-----
template <typename T> class VoxelGridXY {
template <typename T>
class VoxelGridXY {
// assuming at most 320000 points
static const unsigned int s_nr_max_reserved_points_ = 320000;
......@@ -320,7 +321,7 @@ template <typename T> class VoxelGridXY {
bool Initialized() const { return initialized_; }
unsigned int NrVoxel() const { return (unsigned int) voxels_.size(); }
unsigned int NrVoxel() const { return (unsigned int)voxels_.size(); }
unsigned int NrVoxelX() const { return nr_voxel_x_; }
......@@ -452,27 +453,30 @@ template <typename T> class VoxelGridXY {
bool AllocAlignedMemory();
private:
unsigned int nr_points_, nr_point_element_;
unsigned int nr_voxel_x_, nr_voxel_y_, nr_voxel_z_;
const T *data_; // point clouds memory
bool initialized_;
unsigned int nr_points_ = 0;
unsigned int nr_point_element_ = 0;
unsigned int nr_voxel_x_ = 0;
unsigned int nr_voxel_y_ = 0;
unsigned int nr_voxel_z_ = 0;
const T *data_ = nullptr; // point clouds memory
bool initialized_ = false;
T dim_x_[2], dim_y_[2], dim_z_[2], voxel_dim_[3];
float *mem_aligned16_f32_;
int *mem_aligned16_i32_;
float *mem_aligned16_f32_ = nullptr;
int *mem_aligned16_i32_ = nullptr;
std::vector<Voxel<T> > voxels_;
};
template <typename T>
VoxelGridXY<T>::VoxelGridXY()
: data_(nullptr),
mem_aligned16_f32_(nullptr),
mem_aligned16_i32_(nullptr),
nr_points_(0),
: nr_points_(0),
nr_point_element_(0),
nr_voxel_x_(0),
nr_voxel_y_(0),
nr_voxel_z_(1),
initialized_(false) {
data_(nullptr),
initialized_(false),
mem_aligned16_f32_(nullptr),
mem_aligned16_i32_(nullptr) {
IZero2(dim_x_);
IZero2(dim_y_);
IZero2(dim_z_);
......@@ -480,7 +484,8 @@ VoxelGridXY<T>::VoxelGridXY()
AllocAlignedMemory();
}
template <typename T> void VoxelGridXY<T>::CleanUp() {
template <typename T>
void VoxelGridXY<T>::CleanUp() {
initialized_ = false;
data_ = nullptr;
nr_points_ = nr_point_element_ = nr_voxel_x_ = nr_voxel_y_ = 0;
......@@ -504,7 +509,8 @@ VoxelGridXY<T>::VoxelGridXY(unsigned int nr_voxel_x, unsigned int nr_voxel_y,
initialized_ = false;
}
template <typename T> void VoxelGridXY<T>::Reserve() {
template <typename T>
void VoxelGridXY<T>::Reserve() {
int r, c, i = 0, m = 0;
unsigned int n = (nr_voxel_x_ * nr_voxel_y_);
......@@ -550,7 +556,8 @@ template <typename T> void VoxelGridXY<T>::Reserve() {
return;
}
template <typename T> bool VoxelGridXY<T>::AllocAlignedMemory() {
template <typename T>
bool VoxelGridXY<T>::AllocAlignedMemory() {
if (!mem_aligned16_f32_) {
mem_aligned16_f32_ = IAllocAligned<float>(4, 4);
}
......@@ -562,7 +569,8 @@ template <typename T> bool VoxelGridXY<T>::AllocAlignedMemory() {
IVerifyAlignment(mem_aligned16_i32_, 4));
}
template <typename T> int VoxelGridXY<T>::WhichVoxel(T x, T y, T z) const {
template <typename T>
int VoxelGridXY<T>::WhichVoxel(T x, T y, T z) const {
int j, k;
if (!initialized_) {
return (-1);
......@@ -574,10 +582,10 @@ template <typename T> int VoxelGridXY<T>::WhichVoxel(T x, T y, T z) const {
}
k = static_cast<int>(IMax(
(unsigned int) 0,
(unsigned int)0,
IMin(nr_voxel_x_ - 1, (unsigned int)((x - dim_x_[0]) / voxel_dim_[0]))));
j = static_cast<int>(IMax(
(unsigned int) 0,
(unsigned int)0,
IMin(nr_voxel_y_ - 1, (unsigned int)((y - dim_y_[0]) / voxel_dim_[1]))));
return (nr_voxel_x_ * j + k);
}
......@@ -949,10 +957,10 @@ bool VoxelGridXY<T>::Set(const T *data, unsigned int nr_points,
continue;
}
k = IMax((unsigned int) 0,
k = IMax((unsigned int)0,
IMin(nr_voxel_xm1,
(unsigned int)((x - dim_x_min) * voxel_width_x_rec)));
j = IMax((unsigned int) 0,
j = IMax((unsigned int)0,
IMin(nr_voxel_ym1,
(unsigned int)((y - dim_y_min) * voxel_width_y_rec)));
i = nr_voxel_x * j + k;
......@@ -981,7 +989,8 @@ bool VoxelGridXY<T>::Set(const T *data, unsigned int nr_points,
// return static_cast<int> (indices.size());
// }
template <typename T> unsigned int VoxelGridXY<T>::NrIndexedPoints() const {
template <typename T>
unsigned int VoxelGridXY<T>::NrIndexedPoints() const {
if (!initialized_) {
return 0;
}
......@@ -1033,8 +1042,8 @@ bool IDownsampleVoxelGridXY(const VoxelGridXY<T> &src, VoxelGridXY<T> *dst,
assert(nr_voxel_z_src == 1);
// scale factors
unsigned int sf_x = (unsigned int) IPow((unsigned int) 2, dsf_dim_x);
unsigned int sf_y = (unsigned int) IPow((unsigned int) 2, dsf_dim_y);
unsigned int sf_x = (unsigned int)IPow((unsigned int)2, dsf_dim_x);
unsigned int sf_y = (unsigned int)IPow((unsigned int)2, dsf_dim_y);
// compute the # of voxels for the new scale
unsigned int nr_voxel_x_dst = nr_voxel_x_src / sf_x;
......@@ -1134,7 +1143,8 @@ bool IDownsampleVoxelGridXY(const VoxelGridXY<T> &src, VoxelGridXY<T> *dst,
}
// -----Multiscale Voxel Grid Pyramid-----
template <typename DATA_TYPE> class VoxelGridXYPyramid {
template <typename DATA_TYPE>
class VoxelGridXYPyramid {
public:
VoxelGridXYPyramid();
VoxelGridXYPyramid(unsigned int nr_scale, unsigned int nr_voxel_x_base,
......@@ -1177,7 +1187,7 @@ template <typename DATA_TYPE> class VoxelGridXYPyramid {
DATA_TYPE spatial_bound_y_min, DATA_TYPE spatial_bound_y_max,
DATA_TYPE spatial_bound_z_min, DATA_TYPE spatial_bound_z_max);
unsigned int NrScale() const { return (unsigned int) vgrids_.size(); }
unsigned int NrScale() const { return (unsigned int)vgrids_.size(); }
unsigned int NrVoxel(unsigned int i = 0) const {
return (i < vgrids_.size()) ? vgrids_[i].nr_voxel() : 0;
......@@ -1263,8 +1273,8 @@ bool VoxelGridXYPyramid<DATA_TYPE>::Alloc(
unsigned int scale;
unsigned int nr_voxel_x = nr_voxel_x_base;
unsigned int nr_voxel_y = nr_voxel_y_base;
unsigned int sf_x = (unsigned int) IPow((unsigned int) 2, dsf_x);
unsigned int sf_y = (unsigned int) IPow((unsigned int) 2, dsf_y);
unsigned int sf_x = (unsigned int)IPow((unsigned int)2, dsf_x);
unsigned int sf_y = (unsigned int)IPow((unsigned int)2, dsf_y);
dsf_x_ = dsf_x;
dsf_y_ = dsf_y;
......@@ -1304,7 +1314,7 @@ bool VoxelGridXYPyramid<DATA_TYPE>::Set(const DATA_TYPE *pc,
return false;
}
unsigned int scale, nr_scale = (unsigned int) vgrids_.size();
unsigned int scale, nr_scale = (unsigned int)vgrids_.size();
pc_ = pc;
nr_points_ = nr_points;
......@@ -1332,7 +1342,7 @@ bool VoxelGridXYPyramid<DATA_TYPE>::SetS(const float *pc,
return false;
}
unsigned int scale, nr_scale = (unsigned int) vgrids_.size();
unsigned int scale, nr_scale = (unsigned int)vgrids_.size();
pc_ = pc;
nr_points_ = nr_points;
......@@ -1401,7 +1411,8 @@ bool VoxelGridXYPyramid<DATA_TYPE>::Set(
return (vgrids_.size() == nr_scale); // check if all scales are valid
}
template <typename DATA_TYPE> void VoxelGridXYPyramid<DATA_TYPE>::CleanUp() {
template <typename DATA_TYPE>
void VoxelGridXYPyramid<DATA_TYPE>::CleanUp() {
pc_ = nullptr;
vgrids_.clear();
nr_points_ = nr_point_element_ = dsf_x_ = dsf_y_ = dsf_z_ = 0;
......
......@@ -4,69 +4,71 @@ package(default_visibility = ["//visibility:public"])
cc_binary(
name = "libperception_component.so",
deps = [":perception_component_inner"],
linkopts = ["-shared"],
linkstatic = False,
deps = [":perception_component_inner"],
)
cc_library(
name = "perception_component_inner",
srcs = [
"fusion_component.cc",
"lidar_output_component.cc",
"lidar_common_flags.cc",
"segmentation_component.cc",
"lidar_output_component.cc",
"recognition_component.cc",
"segmentation_component.cc",
],
hdrs = [
"fusion_component.h",
"lidar_output_component.h",
"lidar_common_flags.h",
"segmentation_component.h",
"recognition_component.h",
"lidar_inner_component_messages.h",
"lidar_output_component.h",
"recognition_component.h",
"segmentation_component.h",
],
copts = [
'-DMODULE_NAME=\\"perception\\"',
],
deps = [
"@eigen",
"//framework:cybertron",
"//modules/drivers/proto:sensor_proto",
"//modules/perception/proto:perception_proto",
"//modules/common/proto:error_code_proto",
"//modules/common/proto:geometry_proto",
"//modules/common/proto:header_proto",
"//modules/drivers/proto:sensor_proto",
"//modules/map/proto:map_proto",
"//modules/perception/base",
"//modules/perception/common/sensor_manager",
"//modules/perception/lib/utils",
"//modules/perception/fusion/app:obstacle_multi_sensor_fusion",
"//modules/perception/fusion/base",
"//modules/perception/fusion/lib/dummy:dummy_algorithms",
"//modules/perception/fusion/lib/fusion_system/probabilistic_fusion",
"//modules/perception/fusion/lib/interface",
"//modules/perception/lib/registerer",
"//modules/perception/map/hdmap:hdmap_input",
"//modules/perception/lib/utils",
"//modules/perception/lidar/app",
"//modules/perception/lidar/common",
"//modules/perception/lidar/lib/classifier/fused_classifier",
"//modules/perception/lidar/lib/classifier/fused_classifier:ccrf_type_fusion",
"//modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector",
"//modules/perception/lidar/lib/interface",
"//modules/perception/lidar/lib/object_builder",
"//modules/perception/lidar/lib/scene_manager/ground_service:ground_service",
"//modules/perception/lidar/lib/scene_manager/roi_service:roi_service",
"//modules/perception/lidar/lib/segmentation/cnnseg:cnn_segmentation",
"//modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector",
"//modules/perception/lidar/lib/roi_filter/hdmap_roi_filter",
"//modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter",
"//modules/perception/lidar/lib/roi_filter/hdmap_roi_filter",
"//modules/perception/lidar/lib/scene_manager/ground_service",
"//modules/perception/lidar/lib/scene_manager/roi_service",
"//modules/perception/lidar/lib/segmentation/cnnseg:cnn_segmentation",
"//modules/perception/lidar/lib/tracker/hm_tracker:hm_multi_target_tracker",
"//modules/perception/lidar/lib/tracker/hm_tracker:kalman_filter",
"//modules/perception/lidar/lib/tracker/hm_tracker:multi_hm_bipartite_graph_matcher",
"//modules/perception/lidar/lib/classifier/fused_classifier",
"//modules/perception/lidar/lib/classifier/fused_classifier:ccrf_type_fusion",
"//modules/perception/fusion/app:obstacle_multi_sensor_fusion",
"//modules/perception/fusion/base",
"//modules/perception/fusion/lib/interface",
"//modules/perception/fusion/lib/dummy:dummy_algorithms",
"//modules/perception/fusion/lib/fusion_system/probabilistic_fusion",
"//modules/perception/map/hdmap:hdmap_input",
"//modules/perception/onboard/common_flags",
"//modules/perception/onboard/inner_component_messages",
"//modules/perception/onboard/msg_serializer",
"//modules/perception/onboard/transform_wrapper",
"//modules/perception/onboard/inner_component_messages",
"//modules/perception/proto:perception_proto",
"//modules/transform:tf2_buffer_lib",
"@eigen",
],
copts = ['-DMODULE_NAME=\\"perception\\"']
)
cpplint()
......@@ -10,7 +10,9 @@ cc_library(
hdrs = [
"planning_component.h",
],
copts = ["-DMODULE_NAME=\\\"planning\\\""],
copts = [
"-DMODULE_NAME=\\\"planning\\\"",
],
deps = [
":planning_lib",
"//framework:cybertron",
......
......@@ -62,6 +62,13 @@ build --proto_toolchain_for_cc="@com_google_protobuf//:cc_toolchain"
# build with profiling
build:cpu_prof --linkopt=-lprofiler
build --copt="-Werror=sign-compare"
build --copt="-Werror=return-type"
build --copt="-Werror=reorder"
build --copt="-Werror=unused-variable"
build --copt="-Werror=unused-but-set-variable"
build --copt="-Werror=switch"
# Enable C++14
# build --cxxopt="-std=c++14"
# Enable colorful output of GCC
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册