Apollo  6.0
Open source self driving car software
direction_detection.h
Go to the documentation of this file.
1 
2 /******************************************************************************
3  * Copyright 2020 The Apollo Authors. All Rights Reserved.
4  *
5  * Licensed under the Apache License, Version 2.0 (the "License");
6  * you may not use this file except in compliance with the License.
7  * You may obtain a copy of the License at
8  *
9  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.
16  *****************************************************************************/
17 
18 #pragma once
19 
20 #include <algorithm>
21 #include <cmath>
22 #include <memory>
23 #include <string>
24 #include <utility>
25 #include <vector>
26 
27 #include "Eigen/Eigen"
28 // Eigen 3.3.7: #define ALIVE (0)
29 // fastrtps: enum ChangeKind_t { ALIVE, ... };
30 #if defined(ALIVE)
31 #undef ALIVE
32 #endif
33 
34 #include "ATen/ATen.h"
35 #include "torch/torch.h"
36 
37 #include "cyber/cyber.h"
38 #include "modules/common/proto/geometry.pb.h"
39 
40 namespace apollo {
41 namespace audio {
42 
43 using apollo::common::Point3D;
44 
46  public:
49  // Estimates the position of the source of the sound
50  std::pair<Point3D, double> EstimateSoundSource(
51  std::vector<std::vector<double>>&& channels_vec,
52  const std::string& respeaker_extrinsic_file,
53  const int sample_rate, const double mic_distance);
54 
55  private:
56  const double kSoundSpeed = 343.2;
57  const int kDistance = 50;
58  std::unique_ptr<Eigen::Matrix4d> respeaker2imu_ptr_;
59 
60  // Estimates the direction of the source of the sound
61  double EstimateDirection(std::vector<std::vector<double>>&& channels_vec,
62  const int sample_rate, const double mic_distance);
63 
64  bool LoadExtrinsics(const std::string& yaml_file,
65  Eigen::Matrix4d* respeaker_extrinsic);
66 
67  // Computes the offset between the signal sig and the reference signal refsig
68  // using the Generalized Cross Correlation - Phase Transform (GCC-PHAT)method.
69  double GccPhat(const torch::Tensor& sig, const torch::Tensor& refsig, int fs,
70  double max_tau, int interp);
71 
72  // Libtorch does not support Complex type currently.
73  void ConjugateTensor(torch::Tensor* tensor);
74  torch::Tensor ComplexMultiply(const torch::Tensor& a, const torch::Tensor& b);
75  torch::Tensor ComplexAbsolute(const torch::Tensor& tensor);
76 };
77 
78 } // namespace audio
79 } // namespace apollo
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Eigen::Matrix4d Matrix4d
Definition: base_map_fwd.h:32
Definition: direction_detection.h:45
std::pair< Point3D, double > EstimateSoundSource(std::vector< std::vector< double >> &&channels_vec, const std::string &respeaker_extrinsic_file, const int sample_rate, const double mic_distance)