提交 981179dd 编写于 作者: Z Zhang Liangliang 提交者: Dong Li

Perception: fixed some code issues.

上级 da7bc108
......@@ -14,11 +14,11 @@
* limitations under the License.
*****************************************************************************/
#include "modules/perception/obstacle/fusion/probabilistic_fusion/pbf_hm_track_object_matcher.h"
#include <iomanip>
#include <sstream>
#include <string>
#include "modules/common/log.h"
#include "modules/perception/obstacle/fusion/probabilistic_fusion/pbf_hm_track_object_matcher.h"
#include "modules/perception/obstacle/fusion/probabilistic_fusion/pbf_track_object_distance.h"
namespace apollo {
......@@ -50,8 +50,8 @@ bool PbfHmTrackObjectMatcher::Match(
const Eigen::Vector3d &ref_point = *(options.ref_point);
ComputeAssociationMat(fusion_tracks, sensor_objects,
*unassigned_fusion_tracks, *unassigned_sensor_objects,
ref_point, &association_mat);
*unassigned_fusion_tracks, *unassigned_sensor_objects,
ref_point, &association_mat);
int num_track = fusion_tracks.size();
int num_measurement = sensor_objects.size();
......@@ -65,7 +65,10 @@ bool PbfHmTrackObjectMatcher::Match(
}
std::vector<int> measurement_ind_g2l;
measurement_ind_g2l.resize(num_measurement, -1);
std::vector<int> measurement_ind_l2g = *unassigned_sensor_objects;
// TODO(Perception): remove this line or use the variable
// std::vector<int> measurement_ind_l2g = *unassigned_sensor_objects;
for (size_t i = 0; i < unassigned_sensor_objects->size(); i++) {
measurement_ind_g2l[(*unassigned_sensor_objects)[i]] = i;
}
......@@ -97,7 +100,7 @@ bool PbfHmTrackObjectMatcher::Match(
if ((*track2measurements_dist)[track_ind] >
association_mat[track_ind_loc][j]) {
(*track2measurements_dist)[track_ind] =
association_mat[track_ind_loc][j];
association_mat[track_ind_loc][j];
}
}
}
......@@ -275,9 +278,7 @@ void PbfHmTrackObjectMatcher::MinimizeAssignment(
hungarian_optimizer.minimize(ref_idx, new_idx);
}
bool PbfHmTrackObjectMatcher::Init() {
return true;
}
bool PbfHmTrackObjectMatcher::Init() { return true; }
void PbfHmTrackObjectMatcher::ComputeConnectedComponents(
const std::vector<std::vector<double>> &association_mat,
......
......@@ -34,7 +34,12 @@ double PbfTrack::s_max_lidar_invisible_period_ = 0.25;
double PbfTrack::s_max_radar_invisible_period_ = 0.15;
double PbfTrack::s_max_radar_confident_angle_ = 20;
double PbfTrack::s_min_radar_confident_distance_ = 40;
std::string PbfTrack::s_motion_fusion_method_ = "PbfKalmanMotionFusion"; // NOLINT
// TODO(Perception):
// static and global variable are NOT allowed to be of class types. See
// https://google.github.io/styleguide/cppguide.html#Static_and_Global_Variables
std::string PbfTrack::s_motion_fusion_method_ = // NOLINT
"PbfKalmanMotionFusion"; // NOLINT
bool PbfTrack::s_publish_if_has_lidar_ = true;
bool PbfTrack::s_publish_if_has_radar_ = true;
......@@ -46,11 +51,15 @@ PbfTrack::PbfTrack(PbfSensorObjectPtr obj) {
invisible_in_lidar_ = true;
invisible_in_radar_ = true;
// TODO(Perception): fix the duplicated if - else.
/*
if (s_motion_fusion_method_ == "PbfKalmanMotionFusion") {
motion_fusion_ = new PbfKalmanMotionFusion();
} else {
motion_fusion_ = new PbfKalmanMotionFusion();
}
*/
motion_fusion_ = new PbfKalmanMotionFusion();
if (is_lidar(sensor_type)) {
lidar_objects_[sensor_id] = obj;
......@@ -120,13 +129,11 @@ void PbfTrack::UpdateWithoutSensorObject(const SensorType &sensor_type,
double min_match_dist,
double timestamp) {
UpdateMeasurementsLifeWithoutMeasurement(
&lidar_objects_, sensor_id, timestamp,
s_max_lidar_invisible_period_,
&invisible_in_lidar_);
&lidar_objects_, sensor_id, timestamp, s_max_lidar_invisible_period_,
&invisible_in_lidar_);
UpdateMeasurementsLifeWithoutMeasurement(
&radar_objects_, sensor_id, timestamp,
s_max_radar_invisible_period_,
&invisible_in_radar_);
&radar_objects_, sensor_id, timestamp, s_max_radar_invisible_period_,
&invisible_in_radar_);
is_dead_ = (lidar_objects_.empty() && radar_objects_.empty());
if (!is_dead_) {
double time_diff = timestamp - fused_timestamp_;
......@@ -136,17 +143,11 @@ void PbfTrack::UpdateWithoutSensorObject(const SensorType &sensor_type,
}
}
int PbfTrack::GetTrackId() const {
return idx_;
}
int PbfTrack::GetTrackId() const { return idx_; }
PbfSensorObjectPtr PbfTrack::GetFusedObject() {
return fused_object_;
}
PbfSensorObjectPtr PbfTrack::GetFusedObject() { return fused_object_; }
double PbfTrack::GetFusedTimestamp() const {
return fused_timestamp_;
}
double PbfTrack::GetFusedTimestamp() const { return fused_timestamp_; }
PbfSensorObjectPtr PbfTrack::GetLidarObject(const std::string &sensor_id) {
PbfSensorObjectPtr obj = nullptr;
......
......@@ -18,8 +18,8 @@
#define MODULES_PERCEPTION_OBSTACLE_FUSION_PROBABILISTIC_FUSION_PBF_TRACK_H_
#include <map>
#include <string>
#include <memory>
#include <string>
#include "gtest/gtest.h"
#include "modules/perception/obstacle/fusion/probabilistic_fusion/pbf_base_motion_fusion.h"
#include "modules/perception/obstacle/fusion/probabilistic_fusion/pbf_sensor_object.h"
......@@ -58,13 +58,9 @@ class PbfTrack {
int GetTrackId() const;
double GetTrackingPeriod() const {
return tracking_period_;
}
double GetTrackingPeriod() const { return tracking_period_; }
inline bool IsDead() const {
return is_dead_;
}
inline bool IsDead() const { return is_dead_; }
bool AbleToPublish();
static int GetNextTrackId();
......@@ -138,7 +134,7 @@ class PbfTrack {
bool invisible_in_radar_;
/**@brief motion fusion*/
PbfBaseMotionFusion *motion_fusion_;
PbfBaseMotionFusion *motion_fusion_ = nullptr;
/**@brief one object instance per sensor, might be more later*/
std::map<std::string, PbfSensorObjectPtr> lidar_objects_;
......
......@@ -75,7 +75,7 @@ bool SequenceTypeFuser::Init() {
GetAbsolutePath(work_root, classifiers_property_file_path);
if (!sequence_type_fuser::LoadMultipleMatricesFile(
classifiers_property_file_path, &_smooth_matrices)) {
classifiers_property_file_path, &_smooth_matrices)) {
return false;
}
for (auto& pair : _smooth_matrices) {
......@@ -167,13 +167,12 @@ bool SequenceTypeFuser::FuseWithCCRF(TrackedObjects* tracked_objects) {
for (std::size_t i = 1; i < length; ++i) {
for (std::size_t right = 0; right < VALID_OBJECT_TYPE; ++right) {
double prob = 0.0;
double max_prob = -DBL_MAX;
std::size_t id = 0;
for (std::size_t left = 0; left < VALID_OBJECT_TYPE; ++left) {
prob = _fused_sequence_probs[i - 1](left) +
_transition_matrix(left, right) * _s_alpha +
_fused_oneshot_probs[i](right);
const double prob = _fused_sequence_probs[i - 1](left) +
_transition_matrix(left, right) * _s_alpha +
_fused_oneshot_probs[i](right);
if (prob > max_prob) {
max_prob = prob;
id = left;
......
......@@ -14,6 +14,7 @@
* limitations under the License.
*****************************************************************************/
#include "modules/perception/obstacle/lidar/type_fuser/sequence_type_fuser/util.h"
#include "modules/common/log.h"
namespace apollo {
......@@ -55,9 +56,8 @@ void Normalize(Vectord* prob) {
}
void NormalizeRow(Matrixd* prob) {
double sum = 0.0;
for (std::size_t row = 0; row < VALID_OBJECT_TYPE; ++row) {
sum = 0.0;
double sum = 0.0;
for (std::size_t col = 0; col < VALID_OBJECT_TYPE; ++col) {
sum += (*prob)(row, col);
}
......
......@@ -15,12 +15,15 @@
*****************************************************************************/
#ifndef MODULES_PERCEPTION_OBSTACLE_LIDAR_SEQUENCE_TYPE_FUSER_UTIL_H_
#define MODULES_PERCEPTION_OBSTACLE_LIDAR_SEQUENCE_TYPE_FUSER_UTIL_H_
#include <fstream>
#include <iostream>
#include <map>
#include <string>
#include <vector>
#include "Eigen/Dense"
#include "modules/perception/obstacle/base/types.h"
namespace apollo {
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册