50 std::vector<std::vector<double>>&& channels_vec,
51 const std::string& respeaker_extrinsic_file,
52 const int sample_rate,
const double mic_distance);
55 const double kSoundSpeed = 343.2;
56 const int kDistance = 50;
57 std::unique_ptr<Eigen::Matrix4d> respeaker2imu_ptr_;
60 double EstimateDirection(std::vector<std::vector<double>>&& channels_vec,
61 const int sample_rate,
const double mic_distance);
63 bool LoadExtrinsics(
const std::string& yaml_file,
64 Eigen::Matrix4d* respeaker_extrinsic);
68 double GccPhat(
const torch::Tensor& sig,
const torch::Tensor& refsig,
int fs,
69 double max_tau,
int interp);
72 void ConjugateTensor(torch::Tensor* tensor);
73 torch::Tensor ComplexMultiply(
const torch::Tensor& a,
const torch::Tensor& b);
74 torch::Tensor ComplexAbsolute(
const torch::Tensor& tensor);