提交 f151d9a5 编写于 作者: C Calvin Miao 提交者: Jiangtao Hu

Added is on lane check for obstacle

上级 548c6102
......@@ -112,10 +112,22 @@ size_t Obstacle::history_size() const {
const KalmanFilter<double, 4, 2, 0>& Obstacle::kf_lane_tracker(
const std::string& lane_id) {
std::lock_guard<std::mutex> lock(mutex_);
CHECK(kf_lane_trackers_.find(lane_id) != kf_lane_trackers_.end());
return kf_lane_trackers_[lane_id];
}
bool Obstacle::IsOnLane() {
std::lock_guard<std::mutex> lock(mutex_);
if (feature_history_.size() > 0) {
if (feature_history_.front().has_lane() &&
feature_history_.front().lane().has_lane_feature()) {
return true;
}
}
return false;
}
void Obstacle::Insert(const PerceptionObstacle& perception_obstacle,
const double timestamp) {
std::lock_guard<std::mutex> lock(mutex_);
......
......@@ -66,6 +66,8 @@ class Obstacle {
// TODO(author) void SetLaneGraphFeature(ObstacleClusters* p_cluster);
bool IsOnLane();
private:
apollo::common::ErrorCode SetId(
const apollo::perception::PerceptionObstacle& perception_obstacle,
......
......@@ -45,9 +45,15 @@ void PredictorManager::Run(
for (const auto& perception_obstacle :
perception_obstacles.perception_obstacle()) {
int id = perception_obstacle.id();
Obstacle* obstacle = container->GetObstacle(id);
CHECK_NOTNULL(obstacle);
switch (perception_obstacle.type()) {
case PerceptionObstacle::VEHICLE: {
predictor = GetPredictor(ObstacleConf::LANE_SEQUENCE_PREDICTOR);
if (obstacle->IsOnLane()) {
predictor = GetPredictor(ObstacleConf::LANE_SEQUENCE_PREDICTOR);
} else {
predictor = GetPredictor(ObstacleConf::FREE_MOVE_PREDICTOR);
}
break;
}
case PerceptionObstacle::PEDESTRIAN: {
......@@ -60,7 +66,6 @@ void PredictorManager::Run(
}
}
if (predictor != nullptr) {
Obstacle* obstacle = container->GetObstacle(id);
predictor->Predict(obstacle);
PredictionObstacle prediction_obstacle;
prediction_obstacle.CopyFrom(predictor->prediction_obstacle());
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册