提交 126f06e9 编写于 作者: K kechxu 提交者: Kecheng Xu

audio: add degree into audio detection output

上级 10bac81c
......@@ -30,12 +30,14 @@ void MessageProcess::OnMicrophone(
SirenDetection* siren_detection,
AudioDetection* audio_detection) {
audio_info->Insert(audio_data);
*(audio_detection->mutable_position()) =
auto direction_result =
direction_detection->EstimateSoundSource(
audio_info->GetSignals(audio_data.microphone_config().chunk()),
respeaker_extrinsics_file,
audio_data.microphone_config().sample_rate(),
audio_data.microphone_config().mic_distance());
*(audio_detection->mutable_position()) = direction_result.first;
audio_detection->set_source_degree(direction_result.second);
bool is_siren = siren_detection->Evaluate(audio_info->GetSignals(72000));
audio_detection->set_is_siren(is_siren);
......
......@@ -19,6 +19,7 @@ cc_library(
hdrs = ["direction_detection.h"],
deps = [
"//cyber",
"//modules/common/math:math_utils",
"//modules/common/proto:geometry_cc_proto",
"//third_party:libtorch",
"@com_github_jbeder_yaml_cpp//:yaml-cpp",
......
......@@ -17,17 +17,20 @@
#include "modules/audio/inference/direction_detection.h"
#include "yaml-cpp/yaml.h"
#include "modules/common/math/math_utils.h"
namespace apollo {
namespace audio {
using torch::indexing::None;
using torch::indexing::Slice;
using apollo::common::math::NormalizeAngle;
DirectionDetection::DirectionDetection() {}
DirectionDetection::~DirectionDetection() {}
Point3D DirectionDetection::EstimateSoundSource(
std::pair<Point3D, double> DirectionDetection::EstimateSoundSource(
std::vector<std::vector<double>>&& channels_vec,
const std::string& respeaker_extrinsic_file, const int sample_rate,
const double mic_distance) {
......@@ -35,7 +38,7 @@ Point3D DirectionDetection::EstimateSoundSource(
respeaker2imu_ptr_.reset(new Eigen::Matrix4d);
LoadExtrinsics(respeaker_extrinsic_file, respeaker2imu_ptr_.get());
}
const double degree =
double degree =
EstimateDirection(move(channels_vec), sample_rate, mic_distance);
Eigen::Vector4d source_position(kDistance * sin(degree),
kDistance * cos(degree), 0, 1);
......@@ -45,8 +48,8 @@ Point3D DirectionDetection::EstimateSoundSource(
source_position_p3d.set_x(source_position[0]);
source_position_p3d.set_y(source_position[1]);
source_position_p3d.set_z(source_position[2]);
return source_position_p3d;
degree = NormalizeAngle(degree);
return {source_position_p3d, degree};
}
double DirectionDetection::EstimateDirection(
......@@ -76,7 +79,7 @@ double DirectionDetection::EstimateDirection(
}
best_guess = (-best_guess + 480) % 360;
return static_cast<double>(best_guess) / 90 * M_PI;
return static_cast<double>(best_guess) / 180 * M_PI;
}
bool DirectionDetection::LoadExtrinsics(const std::string& yaml_file,
......
......@@ -47,9 +47,10 @@ class DirectionDetection {
DirectionDetection();
~DirectionDetection();
// Estimates the position of the source of the sound
Point3D EstimateSoundSource(std::vector<std::vector<double>>&& channels_vec,
const std::string& respeaker_extrinsic_file,
const int sample_rate, const double mic_distance);
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);
private:
const double kSoundSpeed = 343.2;
......
......@@ -27,4 +27,5 @@ message AudioDetection {
optional bool is_siren = 2;
optional apollo.audio.MovingResult moving_result = 3 [default = UNKNOWN];
optional apollo.common.Point3D position = 4;
optional double source_degree = 5;
}
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册