pbf_track_object_distance.h 3.3 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16
/******************************************************************************
 * Copyright 2017 The Apollo Authors. All Rights Reserved.
 *
 * Licensed under the Apache License, Version 2.0 (the "License");
 * you may not use this file except in compliance with the License.
 * You may obtain a copy of the License at
 *
 * http://www.apache.org/licenses/LICENSE-2.0
 *
 * Unless required by applicable law or agreed to in writing, software
 * distributed under the License is distributed on an "AS IS" BASIS,
 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 * See the License for the specific language governing permissions and
 * limitations under the License.
 *****************************************************************************/

17 18
#ifndef MODULES_PERCEPTION_OBSTACLE_FUSION_PBF_PBF_TRACK_OBJECT_DISTANCE_H_
#define MODULES_PERCEPTION_OBSTACLE_FUSION_PBF_PBF_TRACK_OBJECT_DISTANCE_H_
19

20 21
#include <memory>

22 23 24 25 26 27 28 29 30 31 32
#include "modules/common/macro.h"
#include "modules/perception/obstacle/base/types.h"
#include "modules/perception/obstacle/fusion/probabilistic_fusion/pbf_sensor_object.h"
#include "modules/perception/obstacle/fusion/probabilistic_fusion/pbf_track.h"

namespace apollo {
namespace perception {

struct TrackObjectDistanceOptions {
  Eigen::Vector3d *ref_point = nullptr;
};
33

34 35
class PbfTrackObjectDistance {
 public:
36 37
  PbfTrackObjectDistance() = default;
  virtual ~PbfTrackObjectDistance() = default;
38 39

  float Compute(const PbfTrackPtr &fused_track,
40
                const std::shared_ptr<PbfSensorObject> &sensor_object,
41 42 43
                const TrackObjectDistanceOptions &options);

 protected:
44 45 46 47 48 49 50 51 52 53
  float ComputeVelodyne64Velodyne64(
      const std::shared_ptr<PbfSensorObject> &fused_object,
      const std::shared_ptr<PbfSensorObject> &sensor_object,
      const Eigen::Vector3d &ref_pos, int range = 3);
  float ComputeVelodyne64Radar(
      const std::shared_ptr<PbfSensorObject> &fused_object,
      const std::shared_ptr<PbfSensorObject> &sensor_object,
      const Eigen::Vector3d &ref_pos, int range = 3);
  float ComputeRadarRadar(const std::shared_ptr<PbfSensorObject> &fused_object,
                          const std::shared_ptr<PbfSensorObject> &sensor_object,
54 55
                          const Eigen::Vector3d &ref_pos, int range = 3);

56 57
  float ComputeDistance3D(const std::shared_ptr<PbfSensorObject> &fused_object,
                          const std::shared_ptr<PbfSensorObject> &sensor_object,
58
                          const Eigen::Vector3d &ref_pos, const int range);
59 60 61 62 63 64 65
  float ComputeEuclideanDistance(const Eigen::Vector3d &des,
                                 const Eigen::Vector3d &src);
  bool ComputePolygonCenter(const PolygonDType &polygon,
                            Eigen::Vector3d *center);
  bool ComputePolygonCenter(const PolygonDType &polygon,
                            const Eigen::Vector3d &ref_pos, int range,
                            Eigen::Vector3d *center);
66 67 68
  float ComputeDistanceAngleMatchProb(
      const std::shared_ptr<PbfSensorObject> &fused_object,
      const std::shared_ptr<PbfSensorObject> &sensor_object);
69 70

  float GetAngle(const ObjectPtr &obj);
71 72 73 74 75 76 77

 private:
  DISALLOW_COPY_AND_ASSIGN(PbfTrackObjectDistance);
};
}  // namespace perception
}  // namespace apollo

78
#endif  // MODULES_PERCEPTION_OBSTACLE_FUSION_PBF_PBF_TRACK_OBJECT_DISTANCE_H_