diff --git a/WORKSPACE b/WORKSPACE
index 06764895cb3..f79988eb492 100644
--- a/WORKSPACE
+++ b/WORKSPACE
@@ -75,12 +75,11 @@ http_archive(
# grpc
http_archive(
name = "com_github_grpc_grpc",
- sha256 = "419dba362eaf8f1d36849ceee17c3e2ff8ff12ac666b42d3ff02a164ebe090e9",
+ sha256 = "2378b608557a4331c6a6a97f89a9257aee2f8e56a095ce6619eea62e288fcfbe",
patches = ["//third_party/absl:grpc.patch"],
strip_prefix = "grpc-1.30.0",
urls = [
- "https://apollo-system.cdn.bcebos.com/archive/6.0/v1.30.0.tar.gz",
- "https://github.com/grpc/grpc/archive/v1.30.0.tar.gz",
+ "https://apollo-system.cdn.bcebos.com/archive/8.0/v1.30.0-apollo.tar.gz",
],
)
http_archive(
@@ -100,4 +99,4 @@ grpc_deps()
load("@com_github_grpc_grpc//bazel:grpc_extra_deps.bzl", "grpc_extra_deps")
-grpc_extra_deps()
\ No newline at end of file
+grpc_extra_deps()
diff --git a/cyber/BUILD b/cyber/BUILD
index 34bc6928b40..97b536e82b4 100755
--- a/cyber/BUILD
+++ b/cyber/BUILD
@@ -19,7 +19,6 @@ install(
":cyber_conf",
#"//cyber/python/cyber_py3:runtime_files",
"//cyber/proto:runtime_files",
- ":cyberfile.xml",
"cyber.BUILD"
],
data_dest = "cyber",
diff --git a/cyber/cyberfile.xml b/cyber/cyberfile.xml
deleted file mode 100644
index a35a3204815..00000000000
--- a/cyber/cyberfile.xml
+++ /dev/null
@@ -1,38 +0,0 @@
-
- cyber
- local
-
- Apollo Cyber RT is an open source, high performance runtime framework designed specifically for autonomous driving scenarios.
- Based on a centralized computing model, it is greatly optimized for high concurrency, low latency, and high throughput in autonomous driving.
-
-
- Apollo
- Apache License 2.0
- https://www.apollo.auto/
- https://github.com/ApolloAuto/apollo
- https://github.com/ApolloAuto/apollo/issues
-
- module
- //cyber
-
- libncurses5-dev
- libuuid1
-
- 3rd-rules-python-dev
- 3rd-grpc-dev
- 3rd-rules-proto-dev
- 3rd-py-dev
- 3rd-gpus-dev
- 3rd-bazel-skylib-dev
-
- 3rd-protobuf-dev
- 3rd-fastrtps-dev
- 3rd-glog-dev
- 3rd-gflags-dev
- common-msgs-dev
- 3rd-cpplint-dev
- 3rd-gtest-dev
- 3rd-nlohmann-json-dev
- bazel-extend-tools-dev
-
-
diff --git a/cyber/message/protobuf_factory.cc b/cyber/message/protobuf_factory.cc
index e6a67745880..dcacec29ca0 100644
--- a/cyber/message/protobuf_factory.cc
+++ b/cyber/message/protobuf_factory.cc
@@ -47,15 +47,28 @@ bool ProtobufFactory::RegisterMessage(const Descriptor& desc) {
}
bool ProtobufFactory::RegisterMessage(const ProtoDesc& proto_desc) {
+ FileDescriptorProto file_desc_proto;
+ file_desc_proto.ParseFromString(proto_desc.desc());
+
+ // If the message in this proto file has been registered, return true.
+ if (FindMessageTypeByFile(file_desc_proto)) {
+ return true;
+ }
for (int i = 0; i < proto_desc.dependencies_size(); ++i) {
auto dep = proto_desc.dependencies(i);
if (!RegisterMessage(dep)) {
return false;
}
+ FileDescriptorProto dep_file_desc_proto;
+ dep_file_desc_proto.ParseFromString(dep.desc());
+ const google::protobuf::Descriptor* descriptor =
+ FindMessageTypeByFile(dep_file_desc_proto);
+
+ // If descriptor is found, replace the dependency with registered path.
+ if (descriptor != nullptr) {
+ file_desc_proto.set_dependency(i, descriptor->file()->name());
+ }
}
-
- FileDescriptorProto file_desc_proto;
- file_desc_proto.ParseFromString(proto_desc.desc());
return RegisterMessage(file_desc_proto);
}
@@ -207,6 +220,18 @@ const google::protobuf::ServiceDescriptor* ProtobufFactory::FindServiceByName(
return pool_->FindServiceByName(name);
}
+const Descriptor* ProtobufFactory::FindMessageTypeByFile(
+ const FileDescriptorProto& file_desc_proto) {
+ const std::string& scope = file_desc_proto.package();
+ std::string type;
+ if (file_desc_proto.message_type_size()) {
+ type = scope + "." + file_desc_proto.message_type(0).name();
+ }
+ const google::protobuf::Descriptor* descriptor =
+ pool_->FindMessageTypeByName(type);
+ return descriptor;
+}
+
void ErrorCollector::AddError(const std::string& filename,
const std::string& element_name,
const google::protobuf::Message* descriptor,
diff --git a/cyber/message/protobuf_factory.h b/cyber/message/protobuf_factory.h
index a3418ca597e..d9f1b7a59df 100644
--- a/cyber/message/protobuf_factory.h
+++ b/cyber/message/protobuf_factory.h
@@ -87,6 +87,10 @@ class ProtobufFactory {
google::protobuf::Message* GenerateMessageByType(
const std::string& type) const;
+ // Find a descriptor by FileDescriptorProto. Returns nullptr if not found.
+ const Descriptor* FindMessageTypeByFile(
+ const FileDescriptorProto& file_desc_proto);
+
// Find a top-level message type by name. Returns nullptr if not found.
const Descriptor* FindMessageTypeByName(const std::string& type) const;
diff --git a/cyber/setup.bash b/cyber/setup.bash
index e2f83398475..cdabc56007e 100755
--- a/cyber/setup.bash
+++ b/cyber/setup.bash
@@ -27,7 +27,6 @@ for entry in "${mainboard_path}" \
done
pathprepend ${bazel_bin_path}/cyber/python/internal PYTHONPATH
-# todo(zero): The python version determines the path and needs to be optimized
pathprepend "${PYTHON_INSTALL_PATH}/lib/python${PYTHON_VERSION}/site-packages" PYTHONPATH
pathprepend "${PYTHON_INSTALL_PATH}/bin/" PATH
diff --git a/docker/scripts/dev_into.sh b/docker/scripts/dev_into.sh
index 0339e2c1921..061473e14e6 100755
--- a/docker/scripts/dev_into.sh
+++ b/docker/scripts/dev_into.sh
@@ -16,10 +16,44 @@
# limitations under the License.
###############################################################################
DOCKER_USER="${USER}"
-DEV_CONTAINER="apollo_dev_${USER}"
+DEV_CONTAINER_PREFIX='apollo_dev_'
+DEV_CONTAINER="${DEV_CONTAINER_PREFIX}${USER}"
+
+function parse_arguments {
+ local container_name=''
+
+ while [ $# -gt 0 ]; do
+ local opt="$1"
+ shift
+ case "${opt}" in
+ -n | --name)
+ container_name="$1"
+ shift
+ ;;
+
+ --user)
+ export CUSTOM_USER="$1"
+ shift
+ ;;
+ esac
+ done
+
+ [[ ! -z "${container_name}" ]] && DEV_CONTAINER="${DEV_CONTAINER_PREFIX}${container_name}"
+ [[ ! -z "${CUSTOM_USER}" ]] && DOCKER_USER="${CUSTOM_USER}"
+}
+
+function restart_stopped_container {
+ if docker ps -f status=exited -f name="${DEV_CONTAINER}" | grep "${DEV_CONTAINER}"; then
+ docker start "${DEV_CONTAINER}"
+ fi
+}
xhost +local:root 1>/dev/null 2>&1
+parse_arguments "$@"
+
+restart_stopped_container
+
docker exec \
-u "${DOCKER_USER}" \
-e HISTFILE=/apollo/.dev_bash_hist \
diff --git a/docker/scripts/dev_start.sh b/docker/scripts/dev_start.sh
index fb89b56a35d..384f4ac8bc9 100755
--- a/docker/scripts/dev_start.sh
+++ b/docker/scripts/dev_start.sh
@@ -21,7 +21,8 @@ source "${CURR_DIR}/docker_base.sh"
CACHE_ROOT_DIR="${APOLLO_ROOT_DIR}/.cache"
DOCKER_REPO="apolloauto/apollo"
-DEV_CONTAINER="apollo_dev_${USER}"
+DEV_CONTAINER_PREFIX='apollo_dev_'
+DEV_CONTAINER="${DEV_CONTAINER_PREFIX}${USER}"
DEV_INSIDE="in-dev-docker"
SUPPORTED_ARCHS=(x86_64 aarch64)
@@ -29,13 +30,14 @@ TARGET_ARCH="$(uname -m)"
VERSION_X86_64="dev-x86_64-18.04-20221124_1708"
TESTING_VERSION_X86_64="dev-x86_64-18.04-testing-20210112_0008"
-
-VERSION_AARCH64="dev-aarch64-18.04-20201218_0030"
+VERSION_AARCH64="dev-aarch64-20.04-20231024_1054"
USER_VERSION_OPT=
-
-FAST_MODE="y"
+FAST_MODE="n"
GEOLOC=
+TIMEZONE_CN=(
+ "Time zone: Asia/Shanghai (CST, +0800)"
+)
USE_LOCAL_IMAGE=0
CUSTOM_DIST=
@@ -47,16 +49,21 @@ USER_SPECIFIED_MAPS=
MAP_VOLUMES_CONF=
# Install python tools
-PYTHON_INSTALL_PATH="/opt/apollo/python_tools"
-PYTHON_VERSION=$(python3 -c 'import sys; print(".".join(map(str, sys.version_info[0:2])))')
+source docker/setup_host/host_env.sh
DEFAULT_PYTHON_TOOLS=(
- amodel
+ amodel~=0.1.0
)
# Model
MODEL_REPOSITORY="https://apollo-pkg-beta.cdn.bcebos.com/perception_model"
DEFAULT_INSTALL_MODEL=(
- "${MODEL_REPOSITORY}/cnnseg128_caffe.zip"
+ "${MODEL_REPOSITORY}/tl_detection_caffe.zip"
+ "${MODEL_REPOSITORY}/horizontal_caffe.zip"
+ "${MODEL_REPOSITORY}/quadrate_caffe.zip"
+ "${MODEL_REPOSITORY}/vertical_caffe.zip"
+ "${MODEL_REPOSITORY}/darkSCNN_caffe.zip"
+ "${MODEL_REPOSITORY}/cnnseg16_caffe.zip"
+ "${MODEL_REPOSITORY}/3d-r4-half_caffe.zip"
)
# Map
@@ -65,7 +72,7 @@ DEFAULT_MAPS=(
sunnyvale_loop
sunnyvale_with_two_offices
san_mateo
- apollo_virutal_map
+ #apollo_virutal_map
)
DEFAULT_TEST_MAPS=(
@@ -206,6 +213,18 @@ function check_target_arch() {
exit 1
}
+function check_timezone_cn() {
+ # https://en.wikipedia.org/wiki/List_of_tz_database_time_zones
+ time_zone=$(timedatectl | grep "Time zone" | xargs)
+
+ for tz in "${TIMEZONE_CN[@]}"; do
+ if [[ "${time_zone}" == "${tz}" ]]; then
+ GEOLOC="cn"
+ return 0
+ fi
+ done
+}
+
function setup_devices_and_mount_local_volumes() {
local __retval="$1"
@@ -332,7 +351,12 @@ function install_python_tools() {
for tool in ${DEFAULT_PYTHON_TOOLS[@]}; do
info "Install python tool ${tool} ..."
- pip3 install --user "${tool}"
+ # Use /usr/bin/pip3 because native python is used in the container.
+ /usr/bin/pip3 install --user "${tool}"
+ if [ $? -ne 0 ]; then
+ error "Failed to install ${tool}"
+ exit 1
+ fi
done
}
@@ -340,7 +364,7 @@ function install_perception_models() {
if [ "$FAST_MODE" == "n" ] || [ "$FAST_MODE" == "no" ]; then
for model_url in ${DEFAULT_INSTALL_MODEL[@]}; do
info "Install model ${model_url} ..."
- amodel install "${model_url}"
+ amodel install "${model_url}" -s
done
else
warning "Skip the model installation, if you need to run the perception module, you can manually install."
@@ -358,6 +382,8 @@ function main() {
fi
determine_dev_image "${USER_VERSION_OPT}"
+
+ [[ -z "${GEOLOC}" ]] && check_timezone_cn
geo_specific_config "${GEOLOC}"
if [[ "${USE_LOCAL_IMAGE}" -gt 0 ]]; then
@@ -381,11 +407,17 @@ function main() {
mount_map_volumes
- info "Installing python tools ..."
- install_python_tools
+ if ! [ -x "$(command -v pip3)" ]; then
+ warning "Skip install perception models!!! " \
+ "Need pip3 to install Apollo model management tool!" \
+ "Try \"sudo apt install python3-pip\" "
+ else
+ info "Installing python tools ..."
+ install_python_tools
- info "Installing perception models ..."
- install_perception_models
+ info "Installing perception models ..."
+ install_perception_models
+ fi
info "Starting Docker container \"${DEV_CONTAINER}\" ..."
diff --git a/docker/scripts/docker_base.sh b/docker/scripts/docker_base.sh
index 0d31947ba9b..78ef528bde4 100755
--- a/docker/scripts/docker_base.sh
+++ b/docker/scripts/docker_base.sh
@@ -62,11 +62,15 @@ function determine_gpu_use_host() {
local nv_docker_doc="https://github.com/NVIDIA/nvidia-docker/blob/master/README.md"
if [[ "${USE_GPU_HOST}" -eq 1 ]]; then
- if [[ -x "$(which nvidia-container-toolkit)" ]]; then
+ if [[ -x "$(which nvidia-container-toolkit)" || -x "$(which nvidia-container-runtime)" ]]; then
local docker_version
docker_version="$(docker version --format '{{.Server.Version}}')"
if dpkg --compare-versions "${docker_version}" "ge" "19.03"; then
- DOCKER_RUN_CMD="docker run --gpus all"
+ if [[ "${HOST_ARCH}" == "aarch64" ]]; then
+ DOCKER_RUN_CMD="docker run --runtime nvidia"
+ else
+ DOCKER_RUN_CMD="docker run --gpus all"
+ fi
else
warning "Please upgrade to docker-ce 19.03+ to access GPU from container."
USE_GPU_HOST=0
diff --git a/docker/setup_host/host_env.sh b/docker/setup_host/host_env.sh
index 681f42a889a..5aa313e8982 100644
--- a/docker/setup_host/host_env.sh
+++ b/docker/setup_host/host_env.sh
@@ -15,10 +15,10 @@
# See the License for the specific language governing permissions and
# limitations under the License.
###############################################################################
-
APOLLO_ROOT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )/../.." && pwd )"
-PYTHON_INSTALL_PATH="/opt/apollo/python_tools"
+PYTHON_USER_BASE=$(python3 -c 'import site; print(site.USER_BASE)')
+PYTHON_INSTALL_PATH="${PYTHON_USER_BASE}/apollo/tools"
PYTHON_VERSION=$(python3 -c 'import sys; print(".".join(map(str, sys.version_info[0:2])))')
source ${APOLLO_ROOT_DIR}/scripts/common.bashrc
diff --git a/docker/setup_host/setup_host.sh b/docker/setup_host/setup_host.sh
index c92b52b1018..3e2cfd7b375 100755
--- a/docker/setup_host/setup_host.sh
+++ b/docker/setup_host/setup_host.sh
@@ -18,24 +18,41 @@
APOLLO_ROOT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )/../.." && pwd )"
-# Setup core dump format.
-if [ -e /proc/sys/kernel ]; then
- echo "${APOLLO_ROOT_DIR}/data/core/core_%e.%p" | \
- sudo tee /proc/sys/kernel/core_pattern
+set -euo pipefail
+
+# 1. Setup core dump format.
+CORE_DIR="${APOLLO_ROOT_DIR}/data/core"
+if [ ! -d "${CORE_DIR}" ]; then
+ sudo mkdir -p "${CORE_DIR}"
fi
+sudo tee /etc/sysctl.d/99-core-dump.conf > /dev/null < /dev/null <Models:
-# modules/audio/data/torch_siren_detection_model.pt
-
-install(
- name = "install",
- library_dest = "audio/lib",
- data_dest = "audio",
- data = [
- ":runtime_data",
- ":cyberfile.xml",
- ":audio.BUILD",
- ],
- targets = [
- ":libaudio_component.so",
- ],
- deps = [
- ":pb_hdrs",
- "//modules/audio/tools:install",
- ],
-)
-
-install(
- name = "pb_hdrs",
- data_dest = "audio/include",
- data = [
- "//modules/audio/proto:audio_conf_cc_proto",
- ],
-)
-
-install_src_files(
- name = "install_src",
- deps = [
- ":install_audio_src",
- ":install_audio_hdrs",
- ":install_audio_model",
- "//modules/audio/proto:py_pb_audio",
- ],
-)
-
-install_src_files(
- name = "install_audio_src",
- src_dir = ["."],
- dest = "audio/src",
- filter = "*",
-)
-
-install_src_files(
- name = "install_audio_model",
- src_dir = ["data"],
- dest = "audio/data",
- filter = "*"
-)
-
-install_src_files(
- name = "install_audio_hdrs",
- src_dir = ["."],
- dest = "audio/include",
- filter = "*.h",
-)
-
-cpplint()
diff --git a/modules/audio/README.md b/modules/audio/README.md
deleted file mode 100644
index fec01b386a0..00000000000
--- a/modules/audio/README.md
+++ /dev/null
@@ -1,11 +0,0 @@
-# Audio
-
-## Introduction
- The Audio module detect the siren sound coming from the active emergency vehicle. It detects and output siren on/off status, moving status and the relative position of the siren. When active emergency vehicles detected, you can also see active alerts on Dreamview.
-
-
-## Input
- * Audio signal data (cyber channel `/apollo/sensor/microphone`)
-
-## Output
- * Audio detection result, including the siren active/inactive status, moving status(approaching/departing/stationary), and the positions (cyber channel `apollo/audio/audio_detection`).
diff --git a/modules/audio/audio.BUILD b/modules/audio/audio.BUILD
deleted file mode 100644
index efc983e1408..00000000000
--- a/modules/audio/audio.BUILD
+++ /dev/null
@@ -1,11 +0,0 @@
-load("@rules_cc//cc:defs.bzl", "cc_library")
-
-cc_library(
- name = "audio",
- includes = ["include"],
- hdrs = glob(["include/**/*.h"]),
- srcs = glob(["lib/**/*.so*"]),
- include_prefix = "modules/audio",
- strip_include_prefix = "include",
- visibility = ["//visibility:public"],
-)
\ No newline at end of file
diff --git a/modules/audio/audio_component.cc b/modules/audio/audio_component.cc
deleted file mode 100644
index 69581affba9..00000000000
--- a/modules/audio/audio_component.cc
+++ /dev/null
@@ -1,65 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-#include "modules/audio/audio_component.h"
-#include "modules/audio/proto/audio_conf.pb.h"
-#include "modules/common_msgs/basic_msgs/geometry.pb.h"
-#include "modules/common/util/message_util.h"
-
-namespace apollo {
-namespace audio {
-
-using apollo::common::Point3D;
-using apollo::common::util::FillHeader;
-using apollo::drivers::microphone::config::AudioData;
-
-AudioComponent::~AudioComponent() {}
-
-std::string AudioComponent::Name() const {
- // TODO(all) implement
- return "";
-}
-
-bool AudioComponent::Init() {
- AudioConf audio_conf;
- if (!ComponentBase::GetProtoConfig(&audio_conf)) {
- AERROR << "Unable to load audio conf file: "
- << ComponentBase::ConfigFilePath();
- return false;
- }
- localization_reader_ =
- node_->CreateReader(
- audio_conf.topic_conf().localization_topic_name(), nullptr);
- audio_writer_ = node_->CreateWriter(
- audio_conf.topic_conf().audio_detection_topic_name());
- respeaker_extrinsics_file_ = audio_conf.respeaker_extrinsics_path();
- return true;
-}
-
-bool AudioComponent::Proc(const std::shared_ptr& audio_data) {
- // TODO(all) remove GetSignals() multiple calls
- AudioDetection audio_detection;
- MessageProcess::OnMicrophone(*audio_data, respeaker_extrinsics_file_,
- &audio_info_, &direction_detection_, &moving_detection_,
- &siren_detection_, &audio_detection);
-
- FillHeader(node_->Name(), &audio_detection);
- audio_writer_->Write(audio_detection);
- return true;
-}
-
-} // namespace audio
-} // namespace apollo
diff --git a/modules/audio/audio_component.h b/modules/audio/audio_component.h
deleted file mode 100644
index d9d551218a2..00000000000
--- a/modules/audio/audio_component.h
+++ /dev/null
@@ -1,67 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-/**
- * @file
- */
-
-#pragma once
-
-#include
-#include
-
-#include "cyber/component/component.h"
-#include "modules/audio/common/message_process.h"
-#include "modules/common_msgs/localization_msgs/localization.pb.h"
-
-/**
- * @namespace apollo::audio
- * @brief apollo::audio
- */
-namespace apollo {
-namespace audio {
-
-class AudioComponent
- : public cyber::Component {
- public:
- ~AudioComponent();
-
- std::string Name() const;
-
- bool Init() override;
-
- bool Proc(
- const std::shared_ptr&)
- override;
-
- private:
- std::shared_ptr>
- localization_reader_;
-
- std::shared_ptr> audio_writer_;
-
- AudioInfo audio_info_;
-
- DirectionDetection direction_detection_;
- MovingDetection moving_detection_;
- SirenDetection siren_detection_;
- std::string respeaker_extrinsics_file_;
-};
-
-CYBER_REGISTER_COMPONENT(AudioComponent)
-
-} // namespace audio
-} // namespace apollo
diff --git a/modules/audio/common/BUILD b/modules/audio/common/BUILD
deleted file mode 100644
index 7204fc8e13a..00000000000
--- a/modules/audio/common/BUILD
+++ /dev/null
@@ -1,40 +0,0 @@
-load("@rules_cc//cc:defs.bzl", "cc_library")
-load("//tools:cpplint.bzl", "cpplint")
-
-package(default_visibility = ["//visibility:public"])
-
-cc_library(
- name = "audio_gflags",
- srcs = ["audio_gflags.cc"],
- hdrs = ["audio_gflags.h"],
- deps = [
- "@com_github_gflags_gflags//:gflags",
- ],
-)
-
-cc_library(
- name = "audio_info",
- srcs = ["audio_info.cc"],
- hdrs = ["audio_info.h"],
- deps = [
- ":audio_gflags",
- "//modules/drivers/microphone/proto:audio_cc_proto",
- "//modules/drivers/microphone/proto:microphone_config_cc_proto",
- ],
-)
-
-cc_library(
- name = "message_process",
- srcs = ["message_process.cc"],
- hdrs = ["message_process.h"],
- deps = [
- ":audio_info",
- "//modules/audio/inference:direction_detection",
- "//modules/audio/inference:moving_detection",
- "//modules/audio/inference:siren_detection",
- "//modules/common_msgs/audio_msgs:audio_cc_proto",
- "//modules/drivers/microphone/proto:audio_cc_proto",
- ],
-)
-
-cpplint()
diff --git a/modules/audio/common/audio_gflags.cc b/modules/audio/common/audio_gflags.cc
deleted file mode 100644
index 5fd90378985..00000000000
--- a/modules/audio/common/audio_gflags.cc
+++ /dev/null
@@ -1,27 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-#include "modules/audio/common/audio_gflags.h"
-
-DEFINE_int32(cache_signal_time, 3, "The time to cache signal");
-DEFINE_string(torch_siren_detection_model,
- "/apollo/modules/audio/data/torch_siren_detection_model.pt",
- "Siren detection model file");
-
-DEFINE_string(audio_records_dir, "", "The dir path to offline cyber records");
-DEFINE_string(audio_conf_file,
- "/apollo/modules/audio/conf/audio_conf.pb.txt",
- "Default conf file for audio module");
diff --git a/modules/audio/common/audio_gflags.h b/modules/audio/common/audio_gflags.h
deleted file mode 100644
index cf55ad0ce1e..00000000000
--- a/modules/audio/common/audio_gflags.h
+++ /dev/null
@@ -1,25 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-#pragma once
-
-#include "gflags/gflags.h"
-
-DECLARE_int32(cache_signal_time);
-DECLARE_string(torch_siren_detection_model);
-
-DECLARE_string(audio_records_dir);
-DECLARE_string(audio_conf_file);
diff --git a/modules/audio/common/audio_info.cc b/modules/audio/common/audio_info.cc
deleted file mode 100644
index e1f3ea7d07c..00000000000
--- a/modules/audio/common/audio_info.cc
+++ /dev/null
@@ -1,75 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-#include "modules/audio/common/audio_info.h"
-
-#include
-
-#include "modules/audio/common/audio_gflags.h"
-
-namespace apollo {
-namespace audio {
-
-using apollo::drivers::microphone::config::AudioData;
-using apollo::drivers::microphone::config::ChannelData;
-using apollo::drivers::microphone::config::ChannelType;
-using apollo::drivers::microphone::config::MicrophoneConfig;
-
-void AudioInfo::Insert(const AudioData& audio_data) {
- std::size_t index = 0;
- for (const auto& channel_data : audio_data.channel_data()) {
- if (channel_data.channel_type() == ChannelType::RAW) {
- InsertChannelData(index, channel_data, audio_data.microphone_config());
- ++index;
- }
- }
-}
-
-void AudioInfo::InsertChannelData(const std::size_t index,
- const ChannelData& channel_data,
- const MicrophoneConfig& microphone_config) {
- while (index >= signals_.size()) {
- signals_.push_back(std::deque());
- }
- int width = microphone_config.sample_width();
- const std::string& data = channel_data.data();
- for (std::size_t i = 0; i < data.length(); i += width) {
- int16_t signal = ((int16_t(data[i + 1])) << 8) | (0x00ff & data[i]);
- signals_[index].push_back(static_cast(signal));
- }
- std::size_t max_signal_length = static_cast(
- FLAGS_cache_signal_time * microphone_config.sample_rate());
- while (signals_[index].size() > max_signal_length) {
- signals_[index].pop_front();
- }
-}
-
-std::vector> AudioInfo::GetSignals(
- const int signal_length) {
- std::vector> signals;
- for (std::size_t i = 0; i < signals_.size(); ++i) {
- int start_index = static_cast(signals_[i].size()) - signal_length;
- start_index = std::max(0, start_index);
- std::deque::iterator iter = signals_[i].begin();
- iter += start_index;
- std::vector signal(iter, signals_[i].end());
- signals.push_back(signal);
- }
- return signals;
-}
-
-} // namespace audio
-} // namespace apollo
diff --git a/modules/audio/common/audio_info.h b/modules/audio/common/audio_info.h
deleted file mode 100644
index 931354b011e..00000000000
--- a/modules/audio/common/audio_info.h
+++ /dev/null
@@ -1,48 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-#include
-#include
-#include
-#include
-
-#include "modules/drivers/microphone/proto/audio.pb.h"
-#include "modules/drivers/microphone/proto/microphone_config.pb.h"
-
-namespace apollo {
-namespace audio {
-
-class AudioInfo {
- public:
- AudioInfo() = default;
-
- void Insert(
- const apollo::drivers::microphone::config::AudioData&);
-
- std::vector> GetSignals(const int signal_length);
-
- private:
- void InsertChannelData(
- const std::size_t index,
- const apollo::drivers::microphone::config::ChannelData& channel_data,
- const apollo::drivers::microphone::config::MicrophoneConfig&
- microphone_config);
-
- std::vector> signals_;
-};
-
-} // namespace audio
-} // namespace apollo
diff --git a/modules/audio/common/message_process.cc b/modules/audio/common/message_process.cc
deleted file mode 100644
index 1918f2131c2..00000000000
--- a/modules/audio/common/message_process.cc
+++ /dev/null
@@ -1,51 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-#include "modules/audio/common/message_process.h"
-
-namespace apollo {
-namespace audio {
-
-using apollo::drivers::microphone::config::AudioData;
-
-void MessageProcess::OnMicrophone(
- const AudioData& audio_data,
- const std::string& respeaker_extrinsics_file,
- AudioInfo* audio_info,
- DirectionDetection* direction_detection,
- MovingDetection* moving_detection,
- SirenDetection* siren_detection,
- AudioDetection* audio_detection) {
- audio_info->Insert(audio_data);
- 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);
- auto signals =
- audio_info->GetSignals(audio_data.microphone_config().chunk());
- MovingResult moving_result = moving_detection->Detect(signals);
- audio_detection->set_moving_result(moving_result);
-}
-
-} // namespace audio
-} // namespace apollo
diff --git a/modules/audio/common/message_process.h b/modules/audio/common/message_process.h
deleted file mode 100644
index 0b1ac251208..00000000000
--- a/modules/audio/common/message_process.h
+++ /dev/null
@@ -1,46 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-#pragma once
-
-#include
-
-#include "modules/audio/common/audio_info.h"
-#include "modules/audio/inference/direction_detection.h"
-#include "modules/audio/inference/moving_detection.h"
-#include "modules/audio/inference/siren_detection.h"
-#include "modules/common_msgs/audio_msgs/audio.pb.h"
-#include "modules/drivers/microphone/proto/audio.pb.h"
-
-namespace apollo {
-namespace audio {
-
-class MessageProcess {
- public:
- MessageProcess() = delete;
-
- static void OnMicrophone(
- const apollo::drivers::microphone::config::AudioData& audio_data,
- const std::string& respeaker_extrinsics_file,
- AudioInfo* audio_info,
- DirectionDetection* direction_detection,
- MovingDetection* moving_detection,
- SirenDetection* siren_detection,
- AudioDetection* audio_detection);
-};
-
-} // namespace audio
-} // namespace apollo
diff --git a/modules/audio/conf/audio.conf b/modules/audio/conf/audio.conf
deleted file mode 100644
index adc44948bb2..00000000000
--- a/modules/audio/conf/audio.conf
+++ /dev/null
@@ -1 +0,0 @@
---flagfile=/apollo/modules/common/data/global_flagfile.txt
diff --git a/modules/audio/conf/audio_conf.pb.txt b/modules/audio/conf/audio_conf.pb.txt
deleted file mode 100644
index c5b91553d48..00000000000
--- a/modules/audio/conf/audio_conf.pb.txt
+++ /dev/null
@@ -1,8 +0,0 @@
-topic_conf {
- audio_data_topic_name: "/apollo/sensor/microphone"
- audio_detection_topic_name: "/apollo/audio_detection"
- localization_topic_name: "/apollo/localization/pose"
- audio_event_topic_name: "/apollo/audio_event"
- perception_topic_name: "/apollo/perception/obstacles"
-}
-respeaker_extrinsics_path: "/apollo/modules/audio/conf/respeaker_extrinsics.yaml"
\ No newline at end of file
diff --git a/modules/audio/conf/respeaker_extrinsics.yaml b/modules/audio/conf/respeaker_extrinsics.yaml
deleted file mode 100644
index da8dc961f87..00000000000
--- a/modules/audio/conf/respeaker_extrinsics.yaml
+++ /dev/null
@@ -1,17 +0,0 @@
-header:
- stamp:
- secs: 0
- nsecs: 0
- seq: 0
- frame_id: novatel
-child_frame_id: microphone
-transform:
- rotation:
- x: 0
- y: 0
- z: 0
- w: 1
- translation:
- x: 0.0
- y: 0.68
- z: 0.72
diff --git a/modules/audio/cyberfile.xml b/modules/audio/cyberfile.xml
deleted file mode 100644
index 78a8798df8a..00000000000
--- a/modules/audio/cyberfile.xml
+++ /dev/null
@@ -1,41 +0,0 @@
-
- audio
- local
-
- The Audio module detect the siren sound coming from the active emergency vehicle.
- It detects and output siren on/off status, moving status and the relative position of the siren.
- When active emergency vehicles detected, you can also see active alerts on Dreamview.
-
-
- Apollo
- Apache License 2.0
- https://www.apollo.auto/
- https://github.com/ApolloAuto/apollo
- https://github.com/ApolloAuto/apollo/issues
-
- module
- //modules/audio
-
- common-msgs-dev
- cyber-dev
- common-dev
- drivers-dev
- 3rd-gflags-dev
- 3rd-boost-dev
- 3rd-eigen3-dev
- 3rd-fftw3-dev
- 3rd-yaml-cpp-dev
- 3rd-gtest-dev
- 3rd-libtorch-cpu-dev
- 3rd-mkl-dev
-
- 3rd-rules-python-dev
- 3rd-grpc-dev
- 3rd-bazel-skylib-dev
- 3rd-rules-proto-dev
- 3rd-py-dev
-
-
-
-
-
diff --git a/modules/audio/dag/audio.dag b/modules/audio/dag/audio.dag
deleted file mode 100644
index f636bdd2524..00000000000
--- a/modules/audio/dag/audio.dag
+++ /dev/null
@@ -1,19 +0,0 @@
-module_config {
- module_library : "/apollo/bazel-bin/modules/audio/libaudio_component.so"
- components {
- class_name : "AudioComponent"
- config {
- name: "audio"
- config_file_path: "/apollo/modules/audio/conf/audio_conf.pb.txt"
- flag_file_path: "/apollo/modules/audio/conf/audio.conf"
- readers: [
- {
- channel: "/apollo/sensor/microphone"
- qos_profile: {
- depth : 1
- }
- }
- ]
- }
- }
-}
diff --git a/modules/audio/data/.gitkeep b/modules/audio/data/.gitkeep
deleted file mode 100644
index e69de29bb2d..00000000000
diff --git a/modules/audio/inference/BUILD b/modules/audio/inference/BUILD
deleted file mode 100644
index c61c6408759..00000000000
--- a/modules/audio/inference/BUILD
+++ /dev/null
@@ -1,68 +0,0 @@
-load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test")
-load("//tools:cpplint.bzl", "cpplint")
-load("//tools/platform:build_defs.bzl", "if_gpu")
-
-package(default_visibility = ["//visibility:public"])
-
-cc_library(
- name = "moving_detection",
- srcs = ["moving_detection.cc"],
- hdrs = ["moving_detection.h"],
- deps = [
- "//modules/common_msgs/audio_msgs:audio_cc_proto",
- "@fftw3",
- ],
-)
-
-cc_library(
- name = "direction_detection",
- srcs = ["direction_detection.cc"],
- hdrs = ["direction_detection.h"],
- deps = [
- "//cyber",
- "//modules/common/math",
- "//modules/common_msgs/basic_msgs:geometry_cc_proto",
- #"//third_party/libtorch",
- "@com_github_jbeder_yaml_cpp//:yaml-cpp",
- "@eigen",
- ] + if_gpu(
- ["@libtorch_gpu"],
- ["@libtorch_cpu"],
- ),
-)
-
-cc_library(
- name = "siren_detection",
- srcs = ["siren_detection.cc"],
- hdrs = ["siren_detection.h"],
- deps = [
- "//cyber",
- "//modules/audio/common:audio_gflags",
- #"//third_party/libtorch",
- ] + if_gpu(
- ["@libtorch_gpu"],
- ["@libtorch_cpu"],
- ),
-)
-
-# cc_test(
-# name = "siren_detection_test",
-# size = "small",
-# srcs = ["siren_detection_test.cc"],
-# deps = [
-# ":siren_detection",
-# "@com_google_googletest//:gtest_main",
-# ],
-# )
-
-cc_test(
- name = "moving_detection_test",
- size = "small",
- srcs = ["moving_detection_test.cc"],
- deps = [
- ":moving_detection",
- "@com_google_googletest//:gtest_main",
- ],
-)
-
-cpplint()
diff --git a/modules/audio/inference/direction_detection.cc b/modules/audio/inference/direction_detection.cc
deleted file mode 100644
index 3567c2fb595..00000000000
--- a/modules/audio/inference/direction_detection.cc
+++ /dev/null
@@ -1,181 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-#include "modules/audio/inference/direction_detection.h"
-#include "yaml-cpp/yaml.h"
-
-#include "cyber/common/file.h"
-#include "cyber/common/log.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() {}
-
-std::pair DirectionDetection::EstimateSoundSource(
- std::vector>&& channels_vec,
- const std::string& respeaker_extrinsic_file, const int sample_rate,
- const double mic_distance) {
- if (!respeaker2imu_ptr_.get()) {
- respeaker2imu_ptr_.reset(new Eigen::Matrix4d);
- LoadExtrinsics(respeaker_extrinsic_file, respeaker2imu_ptr_.get());
- }
- double degree =
- EstimateDirection(move(channels_vec), sample_rate, mic_distance);
- Eigen::Vector4d source_position(kDistance * sin(degree),
- kDistance * cos(degree), 0, 1);
- source_position = (*respeaker2imu_ptr_) * source_position;
-
- Point3D source_position_p3d;
- source_position_p3d.set_x(source_position[0]);
- source_position_p3d.set_y(source_position[1]);
- source_position_p3d.set_z(source_position[2]);
- degree = NormalizeAngle(degree);
- return {source_position_p3d, degree};
-}
-
-double DirectionDetection::EstimateDirection(
- std::vector>&& channels_vec, const int sample_rate,
- const double mic_distance) {
- std::vector channels_ts;
- auto options = torch::TensorOptions().dtype(torch::kFloat64);
- int size = static_cast(channels_vec[0].size());
- for (auto& signal : channels_vec) {
- channels_ts.push_back(torch::from_blob(signal.data(), {size}, options));
- }
-
- double tau0, tau1;
- double theta0, theta1;
- const double max_tau = mic_distance / kSoundSpeed;
- tau0 = GccPhat(channels_ts[0], channels_ts[2], sample_rate, max_tau, 1);
- theta0 = asin(tau0 / max_tau) * 180 / M_PI;
- tau1 = GccPhat(channels_ts[1], channels_ts[3], sample_rate, max_tau, 1);
- theta1 = asin(tau1 / max_tau) * 180 / M_PI;
-
- int best_guess = 0;
- if (fabs(theta0) < fabs(theta1)) {
- best_guess = theta1 > 0 ? std::fmod(theta0 + 360, 360) : (180 - theta0);
- } else {
- best_guess = theta0 < 0 ? std::fmod(theta1 + 360, 360) : (180 - theta1);
- best_guess = (best_guess + 90 + 180) % 360;
- }
- best_guess = (-best_guess + 480) % 360;
-
- return static_cast(best_guess) / 180 * M_PI;
-}
-
-bool DirectionDetection::LoadExtrinsics(const std::string& yaml_file,
- Eigen::Matrix4d* respeaker_extrinsic) {
- if (!apollo::cyber::common::PathExists(yaml_file)) {
- AINFO << yaml_file << " does not exist!";
- return false;
- }
- YAML::Node node = YAML::LoadFile(yaml_file);
- double qw = 0.0;
- double qx = 0.0;
- double qy = 0.0;
- double qz = 0.0;
- double tx = 0.0;
- double ty = 0.0;
- double tz = 0.0;
- try {
- if (node.IsNull()) {
- AINFO << "Load " << yaml_file << " failed! please check!";
- return false;
- }
- qw = node["transform"]["rotation"]["w"].as();
- qx = node["transform"]["rotation"]["x"].as();
- qy = node["transform"]["rotation"]["y"].as();
- qz = node["transform"]["rotation"]["z"].as();
- tx = node["transform"]["translation"]["x"].as();
- ty = node["transform"]["translation"]["y"].as();
- tz = node["transform"]["translation"]["z"].as();
- } catch (YAML::Exception& e) {
- AERROR << "load camera extrinsic file " << yaml_file
- << " with error, YAML exception:" << e.what();
- return false;
- }
- respeaker_extrinsic->setConstant(0);
- Eigen::Quaterniond q;
- q.x() = qx;
- q.y() = qy;
- q.z() = qz;
- q.w() = qw;
- (*respeaker_extrinsic).block<3, 3>(0, 0) = q.normalized().toRotationMatrix();
- (*respeaker_extrinsic)(0, 3) = tx;
- (*respeaker_extrinsic)(1, 3) = ty;
- (*respeaker_extrinsic)(2, 3) = tz;
- (*respeaker_extrinsic)(3, 3) = 1;
- return true;
-}
-
-double DirectionDetection::GccPhat(const torch::Tensor& sig,
- const torch::Tensor& refsig, int fs,
- double max_tau, int interp) {
- const int n_sig = sig.size(0), n_refsig = refsig.size(0),
- n = n_sig + n_refsig;
- torch::Tensor psig = at::constant_pad_nd(sig, {0, n_refsig}, 0);
- torch::Tensor prefsig = at::constant_pad_nd(refsig, {0, n_sig}, 0);
- psig = at::rfft(psig, 1, false, true);
- prefsig = at::rfft(prefsig, 1, false, true);
-
- ConjugateTensor(&prefsig);
- torch::Tensor r = ComplexMultiply(psig, prefsig);
- torch::Tensor cc =
- at::irfft(r / ComplexAbsolute(r), 1, false, true, {interp * n});
- int max_shift = static_cast(interp * n / 2);
- if (max_tau != 0)
- max_shift = std::min(static_cast(interp * fs * max_tau), max_shift);
-
- auto begin = cc.index({Slice(cc.size(0) - max_shift, None)});
- auto end = cc.index({Slice(None, max_shift + 1)});
- cc = at::cat({begin, end});
- // find max cross correlation index
- const int shift = at::argmax(at::abs(cc), 0).item() - max_shift;
- const double tau = shift / static_cast(interp * fs);
-
- return tau;
-}
-
-void DirectionDetection::ConjugateTensor(torch::Tensor* tensor) {
- tensor->index_put_({"...", 1}, -tensor->index({"...", 1}));
-}
-
-torch::Tensor DirectionDetection::ComplexMultiply(const torch::Tensor& a,
- const torch::Tensor& b) {
- torch::Tensor real = a.index({"...", 0}) * b.index({"...", 0}) -
- a.index({"...", 1}) * b.index({"...", 1});
- torch::Tensor imag = a.index({"...", 0}) * b.index({"...", 1}) +
- a.index({"...", 1}) * b.index({"...", 0});
- return at::cat({real.reshape({-1, 1}), imag.reshape({-1, 1})}, 1);
-}
-
-torch::Tensor DirectionDetection::ComplexAbsolute(const torch::Tensor& tensor) {
- torch::Tensor res = tensor * tensor;
- res = at::sqrt(res.sum(1)).reshape({-1, 1});
-
- return res;
-}
-
-} // namespace audio
-} // namespace apollo
diff --git a/modules/audio/inference/direction_detection.h b/modules/audio/inference/direction_detection.h
deleted file mode 100644
index b946d497533..00000000000
--- a/modules/audio/inference/direction_detection.h
+++ /dev/null
@@ -1,78 +0,0 @@
-
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-#pragma once
-
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include "Eigen/Eigen"
-// Eigen 3.3.7: #define ALIVE (0)
-// fastrtps: enum ChangeKind_t { ALIVE, ... };
-#if defined(ALIVE)
-#undef ALIVE
-#endif
-
-#include "ATen/ATen.h"
-#include "torch/torch.h"
-
-#include "modules/common_msgs/basic_msgs/geometry.pb.h"
-
-namespace apollo {
-namespace audio {
-
-using apollo::common::Point3D;
-
-class DirectionDetection {
- public:
- DirectionDetection();
- ~DirectionDetection();
- // Estimates the position of the source of the sound
- std::pair EstimateSoundSource(
- std::vector>&& channels_vec,
- const std::string& respeaker_extrinsic_file,
- const int sample_rate, const double mic_distance);
-
- private:
- const double kSoundSpeed = 343.2;
- const int kDistance = 50;
- std::unique_ptr respeaker2imu_ptr_;
-
- // Estimates the direction of the source of the sound
- double EstimateDirection(std::vector>&& channels_vec,
- const int sample_rate, const double mic_distance);
-
- bool LoadExtrinsics(const std::string& yaml_file,
- Eigen::Matrix4d* respeaker_extrinsic);
-
- // Computes the offset between the signal sig and the reference signal refsig
- // using the Generalized Cross Correlation - Phase Transform (GCC-PHAT)method.
- double GccPhat(const torch::Tensor& sig, const torch::Tensor& refsig, int fs,
- double max_tau, int interp);
-
- // Libtorch does not support Complex type currently.
- void ConjugateTensor(torch::Tensor* tensor);
- torch::Tensor ComplexMultiply(const torch::Tensor& a, const torch::Tensor& b);
- torch::Tensor ComplexAbsolute(const torch::Tensor& tensor);
-};
-
-} // namespace audio
-} // namespace apollo
diff --git a/modules/audio/inference/moving_detection.cc b/modules/audio/inference/moving_detection.cc
deleted file mode 100644
index d62d78f90d9..00000000000
--- a/modules/audio/inference/moving_detection.cc
+++ /dev/null
@@ -1,144 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-#include "modules/audio/inference/moving_detection.h"
-
-#include
-
-namespace apollo {
-namespace audio {
-
-MovingResult MovingDetection::Detect(
- const std::vector>& signals) {
- int approaching_count = 0;
- int departing_count = 0;
- for (std::size_t i = 0; i < signals.size(); ++i) {
- while (signal_stats_.size() <= i) {
- signal_stats_.push_back({});
- }
- MovingResult result = DetectSingleChannel(i, signals[i]);
- if (result == APPROACHING) {
- ++approaching_count;
- } else if (result == DEPARTING) {
- ++departing_count;
- }
- }
- if (approaching_count > departing_count) {
- return APPROACHING;
- }
- if (approaching_count < departing_count) {
- return DEPARTING;
- }
- return UNKNOWN;
-}
-
-MovingResult MovingDetection::DetectSingleChannel(
- const std::size_t channel_index, const std::vector& signals) {
- static constexpr int kStartFrequency = 3;
- static constexpr int kFrameNumStored = 10;
- std::vector> fft_results = fft1d(signals);
- SignalStat signal_stat = GetSignalStat(fft_results, kStartFrequency);
- signal_stats_[channel_index].push_back(signal_stat);
- while (static_cast(signal_stats_[channel_index].size()) >
- kFrameNumStored) {
- signal_stats_[channel_index].pop_front();
- }
- // TODO(kechxu) refactor the following initial version
- MovingResult power_result = AnalyzePower(signal_stats_[channel_index]);
- if (power_result != UNKNOWN) {
- return power_result;
- }
- MovingResult top_frequency_result =
- AnalyzeTopFrequence(signal_stats_[channel_index]);
- return top_frequency_result;
-}
-
-MovingResult MovingDetection::AnalyzePower(
- const std::deque& signal_stats) {
- int n = static_cast(signal_stats.size());
- if (n < 3) {
- return UNKNOWN;
- }
- double first = signal_stats[n - 3].power();
- double second = signal_stats[n - 2].power();
- double third = signal_stats[n - 1].power();
- if (first < second && second < third) {
- return APPROACHING;
- }
- if (first > second && second > third) {
- return DEPARTING;
- }
- return UNKNOWN;
-}
-
-MovingResult MovingDetection::AnalyzeTopFrequence(
- const std::deque& signal_stats) {
- int n = static_cast(signal_stats.size());
- if (n < 3) {
- return UNKNOWN;
- }
- int first = signal_stats[n - 3].top_frequency();
- int second = signal_stats[n - 2].top_frequency();
- int third = signal_stats[n - 1].top_frequency();
- if (first < second && second < third) {
- return APPROACHING;
- }
- if (first > second && second > third) {
- return DEPARTING;
- }
- return UNKNOWN;
-}
-
-std::vector> MovingDetection::fft1d(
- const std::vector& signal) {
- int n = static_cast(signal.size());
- fftw_complex in[n]; // NOLINT
- fftw_complex out[n]; // NOLINT
- for (int i = 0; i < n; ++i) {
- in[i][0] = signal[i];
- in[i][1] = 0.0;
- }
-
- fftw_plan p = fftw_plan_dft_1d(n, in, out, FFTW_FORWARD, FFTW_ESTIMATE);
- fftw_execute(p);
-
- std::vector> output;
- output.reserve(n);
- for (int i = 0; i < n; ++i) {
- output.emplace_back(out[i][0], out[i][1]);
- }
- return output;
-}
-
-MovingDetection::SignalStat MovingDetection::GetSignalStat(
- const std::vector>& fft_results,
- const int start_frequency) {
- double total_power = 0.0;
- int top_frequency = -1;
- double max_power = -1.0;
- for (int i = start_frequency; i < static_cast(fft_results.size()); ++i) {
- double power = std::abs(fft_results[i]);
- total_power += power;
- if (power > max_power) {
- max_power = power;
- top_frequency = i;
- }
- }
- return {total_power, top_frequency};
-}
-
-} // namespace audio
-} // namespace apollo
diff --git a/modules/audio/inference/moving_detection.h b/modules/audio/inference/moving_detection.h
deleted file mode 100644
index 64fb24e3e5a..00000000000
--- a/modules/audio/inference/moving_detection.h
+++ /dev/null
@@ -1,66 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-#include
-#include
-#include
-
-#include "modules/common_msgs/audio_msgs/audio.pb.h"
-
-namespace apollo {
-namespace audio {
-
-/**
- * @file moving_detection.h
- * @description detect if the sound is approaching or departing
- */
-
-class MovingDetection {
- public:
- MovingDetection() = default;
-
- std::vector> fft1d(const std::vector& signals);
-
- MovingResult Detect(const std::vector>& signals);
-
- MovingResult DetectSingleChannel(
- const std::size_t channel_index, const std::vector& signal);
-
- private:
- class SignalStat {
- public:
- SignalStat(double power, int top_frequency)
- : power_(power), top_frequency_(top_frequency) {}
- double power() const { return power_; }
- int top_frequency() const { return top_frequency_; }
- private:
- double power_;
- int top_frequency_;
- };
-
- SignalStat GetSignalStat(
- const std::vector>& fft_results,
- const int start_frequency);
-
- MovingResult AnalyzePower(const std::deque& signal_stats);
-
- MovingResult AnalyzeTopFrequence(const std::deque& signal_stats);
-
- std::vector> signal_stats_;
-};
-
-} // namespace audio
-} // namespace apollo
diff --git a/modules/audio/inference/siren_detection.cc b/modules/audio/inference/siren_detection.cc
deleted file mode 100644
index 851b08996cd..00000000000
--- a/modules/audio/inference/siren_detection.cc
+++ /dev/null
@@ -1,95 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-#include "modules/audio/inference/siren_detection.h"
-
-#include
-#include
-
-#include
-
-#include "cyber/common/log.h"
-#include "modules/audio/common/audio_gflags.h"
-
-namespace apollo {
-namespace audio {
-
-SirenDetection::SirenDetection() : device_(torch::kCPU) {
- LoadModel();
-}
-
-bool SirenDetection::Evaluate(const std::vector>& signals) {
- // Sanity checks.
- omp_set_num_threads(1);
- if (signals.size() == 0) {
- AERROR << "Got no channel in signals!";
- return false;
- }
- if (signals[0].size() == 0) {
- AERROR << "Got no signal in channel 0!";
- return false;
- }
- if (signals[0].size() != 72000) {
- AERROR << "signals[0].size() = " << signals[0].size() << ", skiping!";
- return false;
- }
- torch::Tensor audio_tensor = torch::empty(4 * 1 * 72000);
- float* data = audio_tensor.data_ptr();
-
- for (const auto& channel : signals) {
- for (const auto& i : channel) {
- *data++ = static_cast(i) / 32767.0;
- }
- }
-
- torch::Tensor torch_input = torch::from_blob(audio_tensor.data_ptr(),
- {4, 1, 72000});
- std::vector torch_inputs;
- torch_inputs.push_back(torch_input.to(device_));
-
- auto start_time = std::chrono::system_clock::now();
- at::Tensor torch_output_tensor = torch_model_.forward(torch_inputs).toTensor()
- .to(torch::kCPU);
-
- auto end_time = std::chrono::system_clock::now();
- std::chrono::duration diff = end_time - start_time;
- AINFO << "SirenDetection used time: " << diff.count() * 1000 << " ms.";
- auto torch_output = torch_output_tensor.accessor();
-
- // majority vote with 4 channels
- float neg_score = torch_output[0][0] + torch_output[1][0] +
- torch_output[2][0] + torch_output[3][0];
- float pos_score = torch_output[0][1] + torch_output[1][1] +
- torch_output[2][1] + torch_output[3][1];
- ADEBUG << "neg_score = " << neg_score << ", pos_score = " << pos_score;
- if (neg_score < pos_score) {
- return true;
- } else {
- return false;
- }
-}
-
-void SirenDetection::LoadModel() {
- if (torch::cuda::is_available()) {
- AINFO << "CUDA is available";
- device_ = torch::Device(torch::kCUDA);
- }
- torch::set_num_threads(1);
- torch_model_ = torch::jit::load(FLAGS_torch_siren_detection_model, device_);
-}
-
-} // namespace audio
-} // namespace apollo
diff --git a/modules/audio/inference/siren_detection.h b/modules/audio/inference/siren_detection.h
deleted file mode 100644
index ac201f30e0c..00000000000
--- a/modules/audio/inference/siren_detection.h
+++ /dev/null
@@ -1,49 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-#pragma once
-
-#include
-
-#include "torch/script.h"
-#include "torch/torch.h"
-
-namespace apollo {
-namespace audio {
-
-/**
- * @file moving_detection.h
- * @description detect if the sound is approaching or departing
- */
-
-class SirenDetection {
- public:
- SirenDetection();
-
- ~SirenDetection() = default;
-
- bool Evaluate(const std::vector>& signals);
-
- private:
- void LoadModel();
-
- private:
- torch::jit::script::Module torch_model_;
- torch::Device device_;
-};
-
-} // namespace audio
-} // namespace apollo
diff --git a/modules/audio/launch/audio.launch b/modules/audio/launch/audio.launch
deleted file mode 100644
index 7ea8afa11fd..00000000000
--- a/modules/audio/launch/audio.launch
+++ /dev/null
@@ -1,7 +0,0 @@
-
-
- audio
- /apollo/modules/audio/dag/audio.dag
- audio
-
-
diff --git a/modules/audio/proto/BUILD b/modules/audio/proto/BUILD
deleted file mode 100644
index a03b3526abe..00000000000
--- a/modules/audio/proto/BUILD
+++ /dev/null
@@ -1,34 +0,0 @@
-## Auto generated by `proto_build_generator.py`
-load("@rules_proto//proto:defs.bzl", "proto_library")
-load("@rules_cc//cc:defs.bzl", "cc_proto_library")
-load("//tools:python_rules.bzl", "py_proto_library")
-load("//tools/install:install.bzl", "install", "install_files")
-
-package(default_visibility = ["//visibility:public"])
-
-cc_proto_library(
- name = "audio_conf_cc_proto",
- deps = [
- ":audio_conf_proto",
- ],
-)
-
-proto_library(
- name = "audio_conf_proto",
- srcs = ["audio_conf.proto"],
-)
-
-py_proto_library(
- name = "audio_conf_py_pb2",
- deps = [
- ":audio_conf_proto",
- ],
-)
-
-install_files(
- name = "py_pb_audio",
- dest = "audio/python/modules/audio/proto",
- files = [
- "audio_conf_py_pb2",
- ]
-)
diff --git a/modules/audio/proto/audio_conf.proto b/modules/audio/proto/audio_conf.proto
deleted file mode 100644
index db54a01d7a5..00000000000
--- a/modules/audio/proto/audio_conf.proto
+++ /dev/null
@@ -1,32 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-syntax = "proto2";
-
-package apollo.audio;
-
-message TopicConf {
- optional string audio_data_topic_name = 1;
- optional string audio_detection_topic_name = 2;
- optional string localization_topic_name = 3;
- optional string audio_event_topic_name = 4;
- optional string perception_topic_name = 5;
-}
-
-message AudioConf {
- optional TopicConf topic_conf = 1;
- optional string respeaker_extrinsics_path = 2;
-}
diff --git a/modules/audio/tools/BUILD b/modules/audio/tools/BUILD
deleted file mode 100644
index 2c7bfa57fcd..00000000000
--- a/modules/audio/tools/BUILD
+++ /dev/null
@@ -1,50 +0,0 @@
-load("@rules_cc//cc:defs.bzl", "cc_binary")
-load("//tools:cpplint.bzl", "cpplint")
-load("@rules_python//python:defs.bzl", "py_binary")
-load("//tools/install:install.bzl", "install")
-
-package(default_visibility = ["//visibility:public"])
-
-install(
- name = "install",
- runtime_dest = "audio/bin",
- targets = [
- ":audio_offline_processing",
- ],
- visibility = ["//visibility:public"],
-)
-
-py_binary(
- name = "audiosaver",
- srcs = ["audiosaver.py"],
- deps = [
- "//cyber/python/cyber_py3:cyber",
- "//modules/common_msgs/basic_msgs:header_py_pb2",
- "//modules/drivers/microphone/proto:audio_py_pb2",
- "//modules/drivers/microphone/proto:microphone_config_py_pb2",
- ],
- tags = ["exclude"]
-)
-
-cc_binary(
- name = "audio_offline_processing",
- srcs = ["audio_offline_processing.cc"],
- copts = [
- "-DMODULE_NAME=\\\"audio\\\"",
- ],
- linkopts = [
- "-lgomp",
- ],
- deps = [
- "//cyber",
- "//modules/audio/common:audio_gflags",
- "//modules/audio/common:message_process",
- "//modules/audio/proto:audio_conf_cc_proto",
- "//modules/common_msgs/audio_msgs:audio_event_cc_proto",
- "//modules/common_msgs/localization_msgs:localization_cc_proto",
- "//modules/common_msgs/perception_msgs:perception_obstacle_cc_proto",
- "@boost",
- ],
-)
-
-cpplint()
diff --git a/modules/audio/tools/README.md b/modules/audio/tools/README.md
deleted file mode 100644
index 6cad57fe805..00000000000
--- a/modules/audio/tools/README.md
+++ /dev/null
@@ -1,18 +0,0 @@
-## Dump audio to wave
-
-We provide tools to dump audio data from topic `/apollo/sensor/microphone` to wave files.
-
-### How
-
-To do so,
-1. Change `WAV_SAVING_PATH` in `audiosaver.py` to the directory for saving wave files, which is default to `/tmp`.
-2. Run command `python3 audiosaver.py` to start to listen to audio data from the topic `/apollo/sensor/microphone` (while playing a record, etc.).
-3. Terminate the program with `Ctrl + C` when you want to stop listening & save data to wave files under the target directory.
-
-By default, there are 6 audio channels, so 6 files will be generated -- one for each audio channel. For information of the audio channel, refer to [Microphone](../../drivers/microphone/README.md) and [Microphone Configuration](../../drivers/microphone/conf/respeaker.pb.txt).
-
-### Other References
-
-* Hardware Specification -- [Respeaker](../../../docs/specs/Microphone/Re_Speaker_USB_Mic_Array_Guide.md)
-* Driver Configuration -- [Microphone](../../drivers/microphone/README.md)
-
diff --git a/modules/audio/tools/audio_offline_processing.cc b/modules/audio/tools/audio_offline_processing.cc
deleted file mode 100644
index 06a11a4060a..00000000000
--- a/modules/audio/tools/audio_offline_processing.cc
+++ /dev/null
@@ -1,151 +0,0 @@
-/******************************************************************************
- * Copyright 2020 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.
- *****************************************************************************/
-
-#include
-
-#include
-#include
-
-#include "cyber/common/file.h"
-#include "cyber/record/record_reader.h"
-#include "cyber/record/record_writer.h"
-#include "modules/audio/common/audio_gflags.h"
-#include "modules/audio/common/message_process.h"
-#include "modules/audio/proto/audio_conf.pb.h"
-#include "modules/common_msgs/audio_msgs/audio_event.pb.h"
-#include "modules/common_msgs/localization_msgs/localization.pb.h"
-#include "modules/common_msgs/perception_msgs/perception_obstacle.pb.h"
-
-namespace apollo {
-namespace audio {
-
-using apollo::cyber::record::RecordReader;
-using apollo::cyber::record::RecordMessage;
-using apollo::cyber::record::RecordWriter;
-using apollo::drivers::microphone::config::AudioData;
-using apollo::localization::LocalizationEstimate;
-using apollo::perception::PerceptionObstacles;
-
-void GetRecordFileNames(const boost::filesystem::path& p,
- std::vector* record_files) {
- if (!boost::filesystem::exists(p)) {
- return;
- }
- if (boost::filesystem::is_regular_file(p)) {
- AINFO << "Found record file: " << p.c_str();
- record_files->push_back(p.c_str());
- return;
- }
- if (boost::filesystem::is_directory(p)) {
- for (auto& entry : boost::make_iterator_range(
- boost::filesystem::directory_iterator(p), {})) {
- GetRecordFileNames(entry.path(), record_files);
- }
- }
-}
-
-void ProcessSingleRecordFile(const AudioConf& audio_conf,
- const std::string& input_record_filepath,
- const std::string& output_record_filepath,
- AudioInfo* audio_info,
- DirectionDetection* direction_detection,
- MovingDetection* moving_detection,
- SirenDetection* siren_detection) {
- RecordReader reader(input_record_filepath);
- RecordMessage message;
- RecordWriter writer;
- writer.Open(output_record_filepath);
- while (reader.ReadMessage(&message)) {
- if (message.channel_name ==
- audio_conf.topic_conf().audio_data_topic_name()) {
- AudioData audio_data;
- if (audio_data.ParseFromString(message.content)) {
- AudioDetection audio_detection;
- std::string respeaker_extrinsics_file =
- audio_conf.respeaker_extrinsics_path();
- MessageProcess::OnMicrophone(audio_data, respeaker_extrinsics_file,
- audio_info, direction_detection, moving_detection, siren_detection,
- &audio_detection);
- writer.WriteMessage(
- audio_conf.topic_conf().audio_detection_topic_name(),
- audio_detection, message.time);
- AINFO << "Generate a new audio detection message.";
- }
- } else if (message.channel_name ==
- audio_conf.topic_conf().audio_event_topic_name()) {
- AudioEvent audio_event;
- if (audio_event.ParseFromString(message.content)) {
- writer.WriteMessage(message.channel_name, audio_event,
- message.time);
- AINFO << "Save an audio even message.";
- }
- } else if (message.channel_name ==
- audio_conf.topic_conf().localization_topic_name()) {
- LocalizationEstimate localization;
- if (localization.ParseFromString(message.content)) {
- writer.WriteMessage(
- message.channel_name, localization, message.time);
- AINFO << "Save a localization message.";
- }
- } else if (message.channel_name ==
- audio_conf.topic_conf().perception_topic_name()) {
- PerceptionObstacles perception_obstacles;
- if (perception_obstacles.ParseFromString(message.content)) {
- writer.WriteMessage(
- message.channel_name, perception_obstacles, message.time);
- AINFO << "Save a perception message.";
- }
- }
- }
- writer.Close();
-}
-
-void ProcessFolder() {
- if (FLAGS_audio_records_dir.empty()) {
- AERROR << "The input folder is empty";
- return;
- }
- AudioConf audio_conf;
- if (!cyber::common::GetProtoFromFile(FLAGS_audio_conf_file,
- &audio_conf)) {
- return;
- }
- AudioInfo audio_info;
- DirectionDetection direction_detection;
- MovingDetection moving_detection;
- SirenDetection siren_detection;
- std::vector offline_bags;
- GetRecordFileNames(boost::filesystem::path(FLAGS_audio_records_dir),
- &offline_bags);
- std::sort(offline_bags.begin(), offline_bags.end());
- for (std::size_t i = 0; i < offline_bags.size(); ++i) {
- const std::string& input_record_filepath = offline_bags[i];
- std::string output_record_filepath =
- input_record_filepath + ".new_audio_detection";
- ProcessSingleRecordFile(audio_conf, input_record_filepath,
- output_record_filepath, &audio_info, &direction_detection,
- &moving_detection, &siren_detection);
- }
-}
-
-} // namespace audio
-} // namespace apollo
-
-int main(int argc, char* argv[]) {
- google::ParseCommandLineFlags(&argc, &argv, true);
- apollo::audio::ProcessFolder();
- return 0;
-}
diff --git a/modules/audio/tools/audiosaver.py b/modules/audio/tools/audiosaver.py
deleted file mode 100644
index 3d2d30c3f21..00000000000
--- a/modules/audio/tools/audiosaver.py
+++ /dev/null
@@ -1,69 +0,0 @@
-#!/usr/bin/env python3
-
-# ****************************************************************************
-# Copyright 2020 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.
-# ****************************************************************************
-# -*- coding: utf-8 -*-
-import atexit
-import os
-import wave
-from cyber.python.cyber_py3 import cyber
-from modules.drivers.microphone.proto.audio_pb2 import AudioData
-
-RESPEAKER_CHANNEL = "/apollo/sensor/microphone"
-WAV_SAVING_PATH = "/tmp"
-frames = [b"" for _ in range(6)]
-sample_width = 0
-sample_rate = 0
-
-
-def save_to_wave(frames, filepath, sample_width, sample_rate, n_channels=1):
- """Save frame to file.wave"""
- with wave.open(filepath, 'wb') as wf:
- wf.setnchannels(n_channels)
- wf.setsampwidth(sample_width)
- wf.setframerate(sample_rate)
- wf.writeframes(frames)
-
-
-def before_exit():
- for idx, data in enumerate(frames):
- file_path = os.path.join(WAV_SAVING_PATH, "channel_{}.wav".format(idx))
- save_to_wave(data, file_path, sample_width, sample_rate, 1)
- print("Done...")
-
-
-def callback(audio):
- global frames, sample_width, sample_rate
- sample_width = audio.microphone_config.sample_width
- sample_rate = audio.microphone_config.sample_rate
- print("=" * 40)
- print(audio.header)
- for idx, channel_data in enumerate(audio.channel_data):
- frames[idx] += channel_data.data
-
-
-def run():
- print("=" * 120)
- test_node = cyber.Node("audiosaver")
- test_node.create_reader(RESPEAKER_CHANNEL, AudioData, callback)
- test_node.spin()
-
-
-if __name__ == '__main__':
- atexit.register(before_exit)
- cyber.init()
- run()
- cyber.shutdown()
diff --git a/modules/bridge/BUILD b/modules/bridge/BUILD
deleted file mode 100644
index bc742a16bab..00000000000
--- a/modules/bridge/BUILD
+++ /dev/null
@@ -1,154 +0,0 @@
-load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library", "cc_test")
-load("//tools/install:install.bzl", "install", "install_files", "install_src_files")
-load("//tools:cpplint.bzl", "cpplint")
-
-package(default_visibility = ["//visibility:public"])
-
-BRIDGE_COPTS = ['-DMODULE_NAME=\\"bridge\\"']
-
-filegroup(
- name = "runtime_data",
- srcs = glob([
- "conf/*.txt",
- "dag/*.dag",
- "launch/*.launch",
- ]),
-)
-
-install(
- name = "install",
- library_dest = "bridge/lib",
- data_dest = "bridge",
- data = [
- ":runtime_data",
- "cyberfile.xml",
- "bridge.BUILD"
- ],
- targets = [
- ":libudp_bridge_sender_component.so",
- ":libudp_bridge_receiver_component.so",
- ":libudp_bridge_multi_receiver_component.so",
- ],
- deps = [
- "//modules/bridge/test:install",
- "//modules/bridge/proto:py_pb_bridge",
- "//modules/bridge/common:install",
- ],
-)
-install(
- name = "pb_hdrs",
- data_dest = "bridge/include",
- data = [
- "//modules/bridge/proto:udp_bridge_remote_info_cc_proto",
- ],
-)
-
-cc_library(
- name = "udp_bridge",
- copts = BRIDGE_COPTS,
- deps = [
- "//cyber",
- "//modules/bridge/common:bridge_gflags",
- "//modules/bridge/common:bridge_header",
- "//modules/bridge/common:bridge_proto_diser_buf_factory",
- "//modules/bridge/common:bridge_proto_diserialized_buf",
- "//modules/bridge/common:bridge_proto_serialized_buf",
- "//modules/bridge/common:macro",
- "//modules/bridge/common:util",
- "//modules/bridge/proto:udp_bridge_remote_info_cc_proto",
- "//modules/common_msgs/chassis_msgs:chassis_cc_proto",
- "//modules/common_msgs/planning_msgs:planning_cc_proto",
- "//modules/common/monitor_log",
- "//modules/common/util",
- ],
-)
-
-cc_library(
- name = "udp_bridge_sender",
- srcs = ["udp_bridge_sender_component.cc"],
- hdrs = ["udp_bridge_sender_component.h"],
- copts = BRIDGE_COPTS,
- alwayslink = True,
- deps = [
- ":udp_bridge",
- ],
-)
-
-cc_library(
- name = "udp_bridge_receiver",
- srcs = ["udp_bridge_receiver_component.cc"],
- hdrs = ["udp_bridge_receiver_component.h"],
- copts = BRIDGE_COPTS,
- alwayslink = True,
- deps = [
- ":udp_bridge",
- "//modules/bridge/common:udp_listener",
- ],
-)
-
-cc_library(
- name = "udp_bridge_multi_receiver",
- srcs = ["udp_bridge_multi_receiver_component.cc"],
- hdrs = ["udp_bridge_multi_receiver_component.h"],
- copts = BRIDGE_COPTS,
- alwayslink = True,
- deps = [
- ":udp_bridge",
- "//modules/bridge/common:udp_listener",
- ],
-)
-
-cc_binary(
- name = "libudp_bridge_sender_component.so",
- linkshared = True,
- linkstatic = True,
- deps = [":udp_bridge_sender"],
-)
-
-cc_binary(
- name = "libudp_bridge_receiver_component.so",
- linkshared = True,
- linkstatic = True,
- deps = [":udp_bridge_receiver"],
-)
-
-cc_binary(
- name = "libudp_bridge_multi_receiver_component.so",
- linkshared = True,
- linkstatic = True,
- deps = [":udp_bridge_multi_receiver"],
-)
-
-cc_test(
- name = "udp_bridge_component_test",
- size = "small",
- srcs = ["udp_bridge_component_test.cc"],
- deps = [
- ":udp_bridge_sender",
- "@com_google_googletest//:gtest_main",
- ],
- linkstatic = True,
-)
-install_src_files(
- name = "install_src",
- deps = [
- ":install_bridge_src",
- ":install_bridge_hdrs"
- ],
-)
-
-install_src_files(
- name = "install_bridge_src",
- src_dir = ["."],
- dest = "bridge/src",
- filter = "*",
-)
-
-install_src_files(
- name = "install_bridge_hdrs",
- src_dir = ["."],
- dest = "bridge/include",
- filter = "*.h",
-)
-
-cpplint()
diff --git a/modules/bridge/README.md b/modules/bridge/README.md
deleted file mode 100644
index 9245b2736c4..00000000000
--- a/modules/bridge/README.md
+++ /dev/null
@@ -1,85 +0,0 @@
-# Bridge
-
-## Introduction
-
-This module provides a way for other Apollo modules interactiving with process
-outside of Apollo by socket. It includes sender and receiver components.
-
-## Input
-
-In sender component, there is only one input, which is the proto struct sender
-handled. In receiver comonent, its input is different with others. Its input
-comes from UDP socket.
-
-## Output
-
-Sender's output is by way of UDP socket. Receiver has one output which is
-receiver handled.
-
-## Launch
-
-The startup of Bridge is consistent with the startup of other modules. Bridge
-contains two sub-modules, other than: sender and receiver. The sender is
-responsible for sending the udp data, and the receiver is responsible for
-receiving the data packet sent by the udp client, and parsing it, and then
-sending it to the module that has registered to respond to the message. The
-start command of Sender is as follows.
-
-```
-$ cyber_launch start /apollo/modules/bridge/launch/bridge_receiver.launch
-```
-
-The start command of Receiver is as follows:
-
-```
-$ cyber_launch start /apollo/modules/bridge/launch/bridge_sender.launch
-```
-
-## modify the configuration
-
-- Receiver listens to port 8900 by default, and can change the port number to be
- monitored by modifying its corresponding configuration file. The corresponding
- configuration file can be queried in the dag file, as shown in the following
- figure. 
-
-Its configuration file:
-/Apollo/modules/bridge/conf/udp_bridge_receiver_chassis.pb.txt
-
-
-
-Note: If you want to receive data from the client outside the docker, you need
-to do port mapping with the -p parameter when starting docker, you need to
-modify the docker/scripts/dev_start.sh file, as shown below.
-
-
-Add a new line -p 8900:8900 after -d \. This allows you to map the internal and
-external ports of docker, and you can accept the data sent by the external
-client of docker.
-
-- The sender configuration file is searched in the same way as the receiver. The
- sender that sends the ADCTrajectory is sent to 127.0.0.1:8900 by default; the
- sender that sends the LocalizationEstimate is sent to 127.0.0.1:8901 by
- default. The above ip address and port number can be modified through the
- corresponding configuration file. The configuration file information is as
- shown below. 
-
-## Add new message
-
-To send/receive new messages via udp, you can add two lines of code to the
-corresponding file. If you want to add the message apollo::test::PbTest, as
-shown below.  Add a new line after the 80th line of this
-file udp_bridge_receiver_component.h:
-
-```
-RECEIVER_BRIDGE_COMPONENT_REGISTER(test::PbTest)
-```
-
-Also add after 197 lines of udp_bridge_receiver_component.cc
-
-```
-BRIDGE_RECV_IMPL(test::PbTest)
-```
-
- The addition of Sender is consistent with the receiver.
-After the code is modified, save it, then add the corresponding configuration
-file, startup file, and dag file. Recompile the code and start it.
diff --git a/modules/bridge/bridge.BUILD b/modules/bridge/bridge.BUILD
deleted file mode 100644
index 5bf875efc39..00000000000
--- a/modules/bridge/bridge.BUILD
+++ /dev/null
@@ -1,11 +0,0 @@
-load("@rules_cc//cc:defs.bzl", "cc_library")
-
-cc_library(
- name = "bridge",
- includes = ["include"],
- hdrs = glob(["include/**/*.h"]),
- srcs = glob(["lib/**/*.so*"]),
- include_prefix = "modules/bridge",
- strip_include_prefix = "include",
- visibility = ["//visibility:public"],
-)
\ No newline at end of file
diff --git a/modules/bridge/common/BUILD b/modules/bridge/common/BUILD
deleted file mode 100644
index 653746911cc..00000000000
--- a/modules/bridge/common/BUILD
+++ /dev/null
@@ -1,106 +0,0 @@
-load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test", "cc_binary")
-load("//tools:cpplint.bzl", "cpplint")
-load("//tools/install:install.bzl", "install", "install_files", "install_src_files")
-
-package(default_visibility = ["//visibility:public"])
-
-install(
- name = "install",
- targets = ["libbridge_gflags.so"],
- library_dest = "bridge/lib",
-)
-
-cc_library(
- name = "bridge_buffer",
- srcs = ["bridge_buffer.cc"],
- hdrs = ["bridge_buffer.h"],
-)
-
-cc_binary(
- name = "libbridge_gflags.so",
- srcs = ["bridge_gflags.cc", "bridge_gflags.h"],
- deps = [
- "@com_github_gflags_gflags//:gflags",
- ],
- linkshared = True,
- linkstatic = True,
-)
-
-cc_library(
- name = "bridge_gflags",
- srcs = [":libbridge_gflags.so"],
- hdrs = ["bridge_gflags.h"],
- alwayslink = True,
- deps = [
- "@com_github_gflags_gflags//:gflags",
- ],
-)
-
-cc_library(
- name = "util",
- srcs = ["util.cc"],
- hdrs = ["util.h"],
- deps = [
- ":bridge_buffer",
- ":macro",
- ],
-)
-
-cc_library(
- name = "macro",
- hdrs = ["macro.h"],
-)
-
-cc_library(
- name = "bridge_proto_serialized_buf",
- hdrs = ["bridge_proto_serialized_buf.h"],
-)
-
-cc_library(
- name = "bridge_proto_diserialized_buf",
- hdrs = ["bridge_proto_diserialized_buf.h"],
-)
-
-cc_library(
- name = "bridge_proto_diser_buf_factory",
- hdrs = ["bridge_proto_diser_buf_factory.h"],
- deps = [
- "//modules/common/adapters:adapter_gflags",
- ],
-)
-
-cc_library(
- name = "udp_listener",
- hdrs = ["udp_listener.h"],
-)
-
-cc_library(
- name = "bridge_header",
- srcs = ["bridge_header.cc"],
- hdrs = [
- "bridge_header.h",
- "bridge_header_item.h",
- ],
-)
-
-cc_test(
- name = "bridge_buffer_test",
- size = "small",
- srcs = ["bridge_buffer_test.cc"],
- deps = [
- ":bridge_buffer",
- "@com_google_googletest//:gtest_main",
- ],
-)
-
-cc_test(
- name = "bridge_proto_buf_test",
- size = "small",
- srcs = ["bridge_proto_buf_test.cc"],
- deps = [
- "//modules/bridge:udp_bridge",
- "@com_google_googletest//:gtest_main",
- ],
-)
-
-cpplint()
diff --git a/modules/bridge/common/bridge_buffer.cc b/modules/bridge/common/bridge_buffer.cc
deleted file mode 100644
index 6b013da88a2..00000000000
--- a/modules/bridge/common/bridge_buffer.cc
+++ /dev/null
@@ -1,77 +0,0 @@
-/******************************************************************************
- * Copyright 2019 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.
- *****************************************************************************/
-
-#include "modules/bridge/common/bridge_buffer.h"
-
-#include
-
-namespace apollo {
-namespace bridge {
-
-#define BRIDGE_IMPL(type) template class BridgeBuffer
-
-template
-BridgeBuffer::BridgeBuffer() {}
-
-template
-BridgeBuffer::BridgeBuffer(size_t size) {
- reset(size);
-}
-
-template
-BridgeBuffer::~BridgeBuffer() {
- std::lock_guard lg(mutex_);
- if (buf_) {
- delete[] buf_;
- }
- buf_ = nullptr;
- size_ = 0;
- capacity_ = 0;
-}
-
-template
-BridgeBuffer::operator T *() {
- return buf_;
-}
-
-template
-void BridgeBuffer::reset(size_t size) {
- std::lock_guard lg(mutex_);
- if (capacity_ < size) {
- if (buf_) {
- delete[] buf_;
- }
- capacity_ = size;
- buf_ = new T[capacity_];
- }
- size_ = size;
- memset(buf_, 0, sizeof(T) * capacity_);
-}
-
-template
-void BridgeBuffer::write(size_t index, const T *data, size_t size) {
- std::lock_guard lg(mutex_);
- reset(size + index);
- T *p = buf_ + index;
- memcpy(p, data, size);
-}
-
-BRIDGE_IMPL(char);
-BRIDGE_IMPL(int);
-BRIDGE_IMPL(double);
-
-} // namespace bridge
-} // namespace apollo
diff --git a/modules/bridge/common/bridge_buffer.h b/modules/bridge/common/bridge_buffer.h
deleted file mode 100644
index ee00ff7b7e2..00000000000
--- a/modules/bridge/common/bridge_buffer.h
+++ /dev/null
@@ -1,48 +0,0 @@
-/******************************************************************************
- * Copyright 2019 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.
- *****************************************************************************/
-
-#pragma once
-
-#include
-
-namespace apollo {
-namespace bridge {
-
-template
-class BridgeBuffer {
- public:
- BridgeBuffer();
- explicit BridgeBuffer(size_t size);
- virtual ~BridgeBuffer();
-
- operator T *();
- void reset(size_t size);
- size_t size() const { return size_; }
- size_t capacity() const { return capacity_; }
- void write(size_t index, const T *data, size_t size);
-
- private:
- T *buf_ = nullptr;
- size_t size_ = 0;
- size_t capacity_ = 0;
- std::mutex mutex_;
-
- BridgeBuffer(const BridgeBuffer &) = delete;
- BridgeBuffer &operator=(const BridgeBuffer &) = delete;
-};
-
-} // namespace bridge
-} // namespace apollo
diff --git a/modules/bridge/common/bridge_buffer_test.cc b/modules/bridge/common/bridge_buffer_test.cc
deleted file mode 100644
index 99b4a6bdab4..00000000000
--- a/modules/bridge/common/bridge_buffer_test.cc
+++ /dev/null
@@ -1,55 +0,0 @@
-/******************************************************************************
- * Copyright 2019 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.
- *****************************************************************************/
-
-#include "modules/bridge/common/bridge_buffer.h"
-
-#include
-#include
-
-#include "gtest/gtest.h"
-
-namespace apollo {
-namespace bridge {
-
-TEST(BridgeBufferTest, bridge_buf_test) {
- BridgeBuffer buf;
- char *p = buf;
- EXPECT_EQ(0, buf.capacity());
- EXPECT_EQ(0, buf.size());
-
- buf.reset(100);
- char *p1 = buf;
- EXPECT_EQ(100, buf.capacity());
- EXPECT_EQ(100, buf.size());
- EXPECT_NE(p, p1);
-
- std::string str("hello world");
- snprintf(buf, str.length() + 1, "%s", str.c_str());
- EXPECT_STREQ(buf, str.c_str());
-
- buf.reset(80);
- char *p2 = buf;
- EXPECT_EQ(100, buf.capacity());
- EXPECT_EQ(80, buf.size());
- EXPECT_EQ(p2, p1);
-
- std::string str1("hi world");
- snprintf(buf, str1.length() + 1, "%s", str1.c_str());
- EXPECT_STREQ(buf, str1.c_str());
-}
-
-} // namespace bridge
-} // namespace apollo
diff --git a/modules/bridge/common/bridge_gflags.cc b/modules/bridge/common/bridge_gflags.cc
deleted file mode 100644
index 2bd0c1169c2..00000000000
--- a/modules/bridge/common/bridge_gflags.cc
+++ /dev/null
@@ -1,20 +0,0 @@
-/******************************************************************************
- * Copyright 2019 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.
- *****************************************************************************/
-
-#include "modules/bridge/common/bridge_gflags.h"
-
-DEFINE_string(bridge_module_name, "Bridge", "Bridge module name");
-DEFINE_double(timeout, 1.0, "receive/send proto msg time out");
diff --git a/modules/bridge/common/bridge_gflags.h b/modules/bridge/common/bridge_gflags.h
deleted file mode 100644
index d3c9b67297c..00000000000
--- a/modules/bridge/common/bridge_gflags.h
+++ /dev/null
@@ -1,22 +0,0 @@
-/******************************************************************************
- * Copyright 2019 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.
- *****************************************************************************/
-
-#pragma once
-
-#include "gflags/gflags.h"
-
-DECLARE_string(bridge_module_name);
-DECLARE_double(timeout);
diff --git a/modules/bridge/common/bridge_header.cc b/modules/bridge/common/bridge_header.cc
deleted file mode 100644
index 42b1a2c05ca..00000000000
--- a/modules/bridge/common/bridge_header.cc
+++ /dev/null
@@ -1,92 +0,0 @@
-/******************************************************************************
- * Copyright 2019 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.
- *****************************************************************************/
-
-#include "modules/bridge/common/bridge_header.h"
-
-#include
-
-namespace apollo {
-namespace bridge {
-
-bool BridgeHeader::Serialize(char *buf, size_t size) {
- if (!buf || size == 0) {
- return false;
- }
- char *cursor = buf;
- char *p_header_size = nullptr;
- cursor = SerializeHeaderFlag(cursor, size);
- p_header_size = cursor;
- cursor += sizeof(hsize) + 1;
- for (int i = 0; i < Header_Tail; i++) {
- cursor = header_item[i]->SerializeItem(cursor, size);
- }
-
- if (!SerializeHeaderSize(p_header_size, size)) {
- return false;
- }
- return true;
-}
-
-bool BridgeHeader::Diserialize(const char *buf, size_t buf_size) {
- const char *cursor = buf;
-
- int i = static_cast(buf_size);
- while (i > 0) {
- HType type = *(reinterpret_cast(cursor));
- if (type >= Header_Tail || type < 0) {
- cursor += sizeof(HType) + 1;
- bsize size = *(reinterpret_cast(cursor));
- cursor += sizeof(bsize) + size + 2;
- i -= static_cast(sizeof(HType) + sizeof(bsize) + size + 3);
- continue;
- }
- size_t value_size = 0;
- for (int j = 0; j < Header_Tail; j++) {
- if (type == header_item[j]->GetType()) {
- cursor = header_item[j]->DiserializeItem(cursor, &value_size);
- break;
- }
- }
- i -= static_cast(value_size);
- }
- return true;
-}
-
-bool BridgeHeader::IsAvailable(const char *buf) {
- if (!buf) {
- return false;
- }
- if (memcmp(BRIDGE_HEADER_FLAG, buf, sizeof(BRIDGE_HEADER_FLAG) - 1) != 0) {
- return false;
- }
- return true;
-}
-
-char *BridgeHeader::SerializeHeaderFlag(char *buf, size_t size) {
- if (!buf || size == 0) {
- return nullptr;
- }
- return SerializeBasicType(
- BRIDGE_HEADER_FLAG, buf, size);
-}
-
-char *BridgeHeader::SerializeHeaderSize(char *buf, size_t size) {
- hsize header_size = GetHeaderSize();
- return SerializeBasicType(&header_size, buf, size);
-}
-
-} // namespace bridge
-} // namespace apollo
diff --git a/modules/bridge/common/bridge_header.h b/modules/bridge/common/bridge_header.h
deleted file mode 100644
index de7eed5b0a2..00000000000
--- a/modules/bridge/common/bridge_header.h
+++ /dev/null
@@ -1,149 +0,0 @@
-/******************************************************************************
- * Copyright 2019 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.
- *****************************************************************************/
-
-#pragma once
-
-#include
-#include
-
-#include "modules/bridge/common/bridge_header_item.h"
-
-namespace apollo {
-namespace bridge {
-
-typedef uint32_t hsize;
-
-constexpr char BRIDGE_HEADER_FLAG[] = "ApolloBridgeHeader";
-constexpr size_t HEADER_FLAG_SIZE = sizeof(BRIDGE_HEADER_FLAG);
-constexpr size_t Item_Header_Size = sizeof(HType) + sizeof(bsize) + 2;
-
-class BridgeHeader {
- public:
- BridgeHeader() = default;
- ~BridgeHeader() = default;
-
- public:
- bool Serialize(char *buf, size_t size);
- bool Diserialize(const char *buf, size_t buf_size);
- bool IsAvailable(const char *buf);
-
- uint32_t GetHeaderVer() const { return header_ver_.value_; }
- hsize GetHeaderSize() const {
- return static_cast(header_body_size_ + HEADER_FLAG_SIZE +
- sizeof(hsize) + 2);
- }
- bsize GetHeaderBodySize() const { return header_body_size_; }
- std::string GetMsgName() const { return msg_name_.value_; }
- uint32_t GetMsgID() const { return msg_id_.value_; }
- uint32_t GetTotalFrames() const { return total_frames_.value_; }
- uint32_t GetIndex() const { return index_.value_; }
- double GetTimeStamp() const { return time_stamp_.value_; }
- bsize GetMsgSize() const { return msg_size_.value_; }
- bsize GetFrameSize() const { return frame_size_.value_; }
- bsize GetFramePos() const { return frame_pos_.value_; }
-
- void SetHeaderVer(uint32_t header_ver) {
- header_ver_ = header_ver;
- header_body_size_ +=
- static_cast(Item_Header_Size + 1 + sizeof(uint32_t));
- }
- void SetMsgName(const std::string &msg_name) {
- msg_name_ = msg_name;
- header_body_size_ +=
- static_cast(Item_Header_Size + 1 + msg_name.length() + 1);
- }
- void SetMsgID(uint32_t msg_id) {
- msg_id_ = msg_id;
- header_body_size_ +=
- static_cast(Item_Header_Size + 1 + sizeof(uint32_t));
- }
- void SetTotalFrames(uint32_t total_frames) {
- total_frames_ = total_frames;
- header_body_size_ +=
- static_cast(Item_Header_Size + 1 + sizeof(uint32_t));
- }
- void SetFrameSize(bsize frame_size) {
- frame_size_ = frame_size;
- header_body_size_ +=
- static_cast(Item_Header_Size + 1 + sizeof(bsize));
- }
- void SetFramePos(bsize frame_pos) {
- frame_pos_ = frame_pos;
- header_body_size_ +=
- static_cast(Item_Header_Size + 1 + sizeof(bsize));
- }
- void SetIndex(uint32_t index) {
- index_ = index;
- header_body_size_ +=
- static_cast(Item_Header_Size + 1 + sizeof(uint32_t));
- }
- void SetTimeStamp(double time_stamp) {
- time_stamp_ = time_stamp;
- header_body_size_ +=
- static_cast(Item_Header_Size + 1 + sizeof(double));
- }
- void SetMsgSize(bsize msg_size) {
- msg_size_ = msg_size;
- header_body_size_ +=
- static_cast(Item_Header_Size + 1 + sizeof(bsize));
- }
-
- private:
- template
- char *SerializeBasicType(const T *value, char *buf, size_t size) {
- if (!buf || size < S) {
- return nullptr;
- }
- char *res = buf;
- memcpy(res, value, S);
- res[S] = '\n';
- res += S + 1;
- return res;
- }
-
- template
- bool DiserializeBasicType(T *value, const char *buf) {
- if (!buf) {
- return false;
- }
- char temp[S] = {0};
- memcpy(temp, buf, S);
- *value = *(reinterpret_cast(temp));
- return true;
- }
-
- char *SerializeHeaderFlag(char *buf, size_t size);
- char *SerializeHeaderSize(char *buf, size_t size);
-
- private:
- HeaderItem header_ver_;
- HeaderItem msg_name_;
- HeaderItem msg_id_;
- HeaderItem msg_size_;
- HeaderItem total_frames_;
- HeaderItem frame_size_;
- HeaderItem frame_pos_;
- HeaderItem index_;
- HeaderItem time_stamp_;
- hsize header_body_size_ = 0;
- HeaderItemBase *header_item[Header_Tail] = {
- &header_ver_, &msg_name_, &msg_id_, &msg_size_, &total_frames_,
- &frame_size_, &frame_pos_, &index_, &time_stamp_,
- };
-};
-
-} // namespace bridge
-} // namespace apollo
diff --git a/modules/bridge/common/bridge_header_item.h b/modules/bridge/common/bridge_header_item.h
deleted file mode 100644
index 238e53862f2..00000000000
--- a/modules/bridge/common/bridge_header_item.h
+++ /dev/null
@@ -1,167 +0,0 @@
-/******************************************************************************
- * Copyright 2019 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.
- *****************************************************************************/
-
-#pragma once
-
-#include
-
-namespace apollo {
-namespace bridge {
-
-typedef uint32_t bsize;
-
-enum HType {
- Header_Ver,
- Msg_Name,
- Msg_ID,
- Msg_Size,
- Msg_Frames,
- Frame_Size,
- Frame_Pos,
- Frame_Index,
- Time_Stamp,
-
- Header_Tail,
-};
-
-class HeaderItemBase {
- public:
- HeaderItemBase() = default;
- virtual ~HeaderItemBase() {}
-
- public:
- virtual char *SerializeItem(char *buf, size_t buf_size) = 0;
- virtual const char *DiserializeItem(const char *buf,
- size_t *diserialized_size) = 0;
- virtual HType GetType() const = 0;
-};
-
-template
-struct HeaderItem;
-
-template
-char *SerializeItemImp(const HeaderItem &item, char *buf,
- size_t buf_size) {
- if (!buf || buf_size == 0 ||
- buf_size < size_t(sizeof(t) + item.ValueSize() + 3)) {
- return nullptr;
- }
- char *res = buf;
- size_t item_size = item.ValueSize();
-
- HType type = t;
- memcpy(res, &type, sizeof(HType));
- res[sizeof(HType)] = ':';
- res = res + sizeof(HType) + 1;
-
- memcpy(res, &item_size, sizeof(size_t));
- res[sizeof(bsize)] = ':';
- res = res + sizeof(bsize) + 1;
-
- memcpy(res, item.GetValuePtr(), item.ValueSize());
- res[item.ValueSize()] = '\n';
- res += item.ValueSize() + 1;
- return res;
-}
-
-template
-const char *DiserializeItemImp(HeaderItem *item, const char *buf,
- size_t *diserialized_size) {
- if (!buf || !diserialized_size) {
- return nullptr;
- }
- const char *res = buf;
-
- char p_type[sizeof(HType)] = {0};
- memcpy(p_type, buf, sizeof(HType));
- HType type = *(reinterpret_cast(p_type));
- if (type != t) {
- return nullptr;
- }
- res += sizeof(HType) + 1;
- *diserialized_size += sizeof(HType) + 1;
-
- char p_size[sizeof(bsize)] = {0};
- memcpy(p_size, res, sizeof(bsize));
- bsize size = *(reinterpret_cast(p_size));
- res += sizeof(bsize) + 1;
- *diserialized_size += sizeof(bsize) + 1;
-
- item->SetValue(res);
- res += size + 1;
- *diserialized_size += size + 1;
- return res;
-}
-
-template
-struct HeaderItem : public HeaderItemBase {
- T value_;
-
- operator T() { return value_; }
- HeaderItem &operator=(const T &val) {
- value_ = val;
- return *this;
- }
- HType GetType() const override { return t; }
- size_t ValueSize() const { return sizeof(value_); }
- const T *GetValuePtr() const { return &value_; }
- void SetValue(const char *buf) {
- if (!buf) {
- return;
- }
- value_ = *(reinterpret_cast(buf));
- }
-
- char *SerializeItem(char *buf, size_t buf_size) override {
- return SerializeItemImp(*this, buf, buf_size);
- }
-
- const char *DiserializeItem(const char *buf,
- size_t *diserialized_size) override {
- return DiserializeItemImp(this, buf, diserialized_size);
- }
-};
-
-template
-struct HeaderItem : public HeaderItemBase {
- std::string value_;
- operator std::string() { return value_; }
- HeaderItem &operator=(const std::string &val) {
- value_ = val;
- return *this;
- }
- size_t ValueSize() const { return value_.length() + 1; }
- HType GetType() const override { return t; }
- const char *GetValuePtr() const { return value_.c_str(); }
- void SetValue(const char *buf) {
- if (!buf) {
- return;
- }
- value_ = std::string(buf);
- }
-
- char *SerializeItem(char *buf, size_t buf_size) override {
- return SerializeItemImp(*this, buf, buf_size);
- }
-
- const char *DiserializeItem(const char *buf,
- size_t *diserialized_size) override {
- return DiserializeItemImp(this, buf, diserialized_size);
- }
-};
-
-} // namespace bridge
-} // namespace apollo
diff --git a/modules/bridge/common/bridge_proto_buf_test.cc b/modules/bridge/common/bridge_proto_buf_test.cc
deleted file mode 100644
index f27c6d0f536..00000000000
--- a/modules/bridge/common/bridge_proto_buf_test.cc
+++ /dev/null
@@ -1,97 +0,0 @@
-/******************************************************************************
- * Copyright 2019 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.
- *****************************************************************************/
-
-#include "gtest/gtest.h"
-
-#include "modules/common_msgs/planning_msgs/planning.pb.h"
-
-#include "cyber/init.h"
-#include "modules/bridge/common/bridge_proto_diserialized_buf.h"
-#include "modules/bridge/common/bridge_proto_serialized_buf.h"
-
-namespace apollo {
-namespace bridge {
-
-TEST(BridgeProtoBufTest, Simple) {
- cyber::Init("bridge_proto_buf_test");
- BridgeProtoSerializedBuf proto_buf;
-
- auto adc_trajectory = std::make_shared();
- double x = 1.0;
- double y = 1.0;
- for (size_t i = 0; i < 100; ++i) {
- auto *point = adc_trajectory->add_trajectory_point();
- double offset = 0.1 * static_cast(i);
- point->mutable_path_point()->set_x(x + offset);
- point->mutable_path_point()->set_y(y + offset);
- }
- adc_trajectory->mutable_header()->set_sequence_num(123);
- proto_buf.Serialize(adc_trajectory, "planning::ADCTrajectory");
-
- BridgeProtoDiserializedBuf proto_recv_buf;
-
- size_t frame_count = proto_buf.GetSerializedBufCount();
- for (size_t i = 0; i < frame_count; i++) {
- char header_flag[sizeof(BRIDGE_HEADER_FLAG) + 1] = {0};
- bsize offset = 0;
- memcpy(header_flag, proto_buf.GetSerializedBuf(i), HEADER_FLAG_SIZE);
- EXPECT_STREQ(header_flag, BRIDGE_HEADER_FLAG);
- offset += static_cast(sizeof(BRIDGE_HEADER_FLAG) + 1);
-
- char header_size_buf[sizeof(hsize) + 1] = {0};
- const char *cursor = proto_buf.GetSerializedBuf(i) + offset;
- memcpy(header_size_buf, cursor, sizeof(hsize));
- hsize header_size = *(reinterpret_cast(header_size_buf));
- EXPECT_EQ(header_size, 184);
- offset += static_cast(sizeof(hsize) + 1);
-
- BridgeHeader header;
- bsize buf_size = header_size - offset;
- cursor = proto_buf.GetSerializedBuf(i) + offset;
- EXPECT_TRUE(header.Diserialize(cursor, buf_size));
- EXPECT_STREQ(header.GetMsgName().c_str(), "planning::ADCTrajectory");
- EXPECT_EQ(header.GetMsgID(), 123);
-
- proto_recv_buf.Initialize(header);
- char *buf = proto_recv_buf.GetBuf(header.GetFramePos());
- cursor = proto_buf.GetSerializedBuf(i) + header_size;
- memcpy(buf, cursor, header.GetFrameSize());
- proto_recv_buf.UpdateStatus(header.GetIndex());
- if (i < frame_count - 1) {
- EXPECT_FALSE(proto_recv_buf.IsReadyDiserialize());
- } else {
- EXPECT_TRUE(proto_recv_buf.IsReadyDiserialize());
- }
- }
- auto pb_msg = std::make_shared();
- proto_recv_buf.Diserialized(pb_msg);
- EXPECT_EQ(pb_msg->header().sequence_num(),
- adc_trajectory->header().sequence_num());
- EXPECT_EQ(pb_msg->trajectory_point_size(),
- adc_trajectory->trajectory_point_size());
-
- int traj_size = adc_trajectory->trajectory_point_size();
- EXPECT_EQ(traj_size, 100);
- for (int i = 0; i < traj_size; ++i) {
- EXPECT_EQ(adc_trajectory->trajectory_point(i).path_point().x(),
- pb_msg->trajectory_point(i).path_point().x());
- EXPECT_EQ(adc_trajectory->trajectory_point(i).path_point().y(),
- pb_msg->trajectory_point(i).path_point().x());
- }
-}
-
-} // namespace bridge
-} // namespace apollo
diff --git a/modules/bridge/common/bridge_proto_diser_buf_factory.h b/modules/bridge/common/bridge_proto_diser_buf_factory.h
deleted file mode 100644
index 42aa3b37f0f..00000000000
--- a/modules/bridge/common/bridge_proto_diser_buf_factory.h
+++ /dev/null
@@ -1,44 +0,0 @@
-/******************************************************************************der
- * Copyright 2019 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.
- *****************************************************************************/
-
-#pragma once
-
-#include
-#include
-
-#include "modules/common_msgs/chassis_msgs/chassis.pb.h"
-
-#include "modules/bridge/common/bridge_proto_diserialized_buf.h"
-#include "modules/common/adapters/adapter_gflags.h"
-
-namespace apollo {
-namespace bridge {
-
-class ProtoDiserializedBufBaseFactory {
- public:
- static std::shared_ptr CreateObj(
- const BridgeHeader &header) {
- std::shared_ptr obj;
- if (strcmp("Chassis", header.GetMsgName().c_str()) == 0) {
- obj = std::make_shared>(
- FLAGS_chassis_topic);
- }
- return obj;
- }
-};
-
-} // namespace bridge
-} // namespace apollo
diff --git a/modules/bridge/common/bridge_proto_diserialized_buf.h b/modules/bridge/common/bridge_proto_diserialized_buf.h
deleted file mode 100644
index cd87299dd01..00000000000
--- a/modules/bridge/common/bridge_proto_diserialized_buf.h
+++ /dev/null
@@ -1,177 +0,0 @@
-/******************************************************************************der
- * Copyright 2019 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.
- *****************************************************************************/
-
-#pragma once
-
-#include
-#include
-#include
-
-#include "cyber/cyber.h"
-#include "modules/bridge/common/bridge_header.h"
-#include "modules/bridge/common/macro.h"
-
-namespace apollo {
-namespace bridge {
-
-constexpr uint32_t INT_BITS = static_cast(sizeof(uint32_t) * 8);
-
-class ProtoDiserializedBufBase {
- public:
- ProtoDiserializedBufBase() {}
- virtual ~ProtoDiserializedBufBase() {}
-
- virtual bool Initialize(const BridgeHeader &header,
- std::shared_ptr node) = 0;
-
- virtual bool DiserializedAndPub() = 0;
- virtual bool IsReadyDiserialize() const = 0;
- virtual bool IsTheProto(const BridgeHeader &header) = 0;
- virtual void UpdateStatus(uint32_t frame_index) = 0;
- virtual uint32_t GetMsgID() const = 0;
- virtual std::string GetMsgName() const = 0;
- virtual char *GetBuf(size_t offset) = 0;
-};
-
-template
-class BridgeProtoDiserializedBuf : public ProtoDiserializedBufBase {
- public:
- BridgeProtoDiserializedBuf() {}
- explicit BridgeProtoDiserializedBuf(const std::string &topic_name)
- : topic_name_(topic_name) {}
- virtual ~BridgeProtoDiserializedBuf();
-
- virtual bool DiserializedAndPub();
- virtual bool Initialize(const BridgeHeader &header,
- std::shared_ptr node);
-
- virtual bool IsReadyDiserialize() const { return is_ready_diser; }
- virtual void UpdateStatus(uint32_t frame_index);
- virtual bool IsTheProto(const BridgeHeader &header);
-
- bool Initialize(const BridgeHeader &header);
- bool Diserialized(std::shared_ptr proto);
- virtual char *GetBuf(size_t offset) { return proto_buf_ + offset; }
- virtual uint32_t GetMsgID() const { return sequence_num_; }
- virtual std::string GetMsgName() const { return proto_name_; }
-
- private:
- size_t total_frames_ = 0;
- size_t total_size_ = 0;
- std::string proto_name_ = "";
- std::vector status_list_;
- char *proto_buf_ = nullptr;
- bool is_ready_diser = false;
- uint32_t sequence_num_ = 0;
- std::shared_ptr> writer_;
- std::string topic_name_ = "";
-};
-
-template
-BridgeProtoDiserializedBuf::~BridgeProtoDiserializedBuf() {
- FREE_ARRY(proto_buf_);
-}
-
-template
-bool BridgeProtoDiserializedBuf::Diserialized(std::shared_ptr proto) {
- if (!proto_buf_ || !proto) {
- return false;
- }
- proto->ParseFromArray(proto_buf_, static_cast(total_size_));
- return true;
-}
-
-template
-void BridgeProtoDiserializedBuf::UpdateStatus(uint32_t frame_index) {
- size_t status_size = status_list_.size();
- if (status_size == 0) {
- is_ready_diser = false;
- return;
- }
-
- uint32_t status_index = frame_index / INT_BITS;
- status_list_[status_index] |= (1 << (frame_index % INT_BITS));
- for (size_t i = 0; i < status_size; i++) {
- if (i == status_size - 1) {
- if (static_cast(status_list_[i]) ==
- (1 << total_frames_ % INT_BITS) - 1) {
- AINFO << "diserialized is ready";
- is_ready_diser = true;
- } else {
- is_ready_diser = false;
- break;
- }
- } else {
- if (status_list_[i] != 0xffffffff) {
- is_ready_diser = false;
- break;
- }
- is_ready_diser = true;
- }
- }
-}
-
-template
-bool BridgeProtoDiserializedBuf::IsTheProto(const BridgeHeader &header) {
- if (strcmp(proto_name_.c_str(), header.GetMsgName().c_str()) == 0 &&
- sequence_num_ == header.GetMsgID()) {
- return true;
- }
- return false;
-}
-
-template
-bool BridgeProtoDiserializedBuf::Initialize(const BridgeHeader &header) {
- total_size_ = header.GetMsgSize();
- total_frames_ = header.GetTotalFrames();
- proto_name_ = header.GetMsgName();
- sequence_num_ = header.GetMsgID();
- if (total_frames_ == 0) {
- return false;
- }
- int status_size = static_cast(total_frames_ / INT_BITS +
- ((total_frames_ % INT_BITS) ? 1 : 0));
- if (status_list_.empty()) {
- for (int i = 0; i < status_size; i++) {
- status_list_.push_back(0);
- }
- }
-
- if (!proto_buf_) {
- proto_buf_ = new char[total_size_];
- }
- return true;
-}
-
-template
-bool BridgeProtoDiserializedBuf::Initialize(
- const BridgeHeader &header, std::shared_ptr node) {
- writer_ = node->CreateWriter(topic_name_.c_str());
- return Initialize(header);
-}
-
-template
-bool BridgeProtoDiserializedBuf::DiserializedAndPub() {
- auto pb_msg = std::make_shared();
- if (!Diserialized(pb_msg)) {
- return false;
- }
- writer_->Write(pb_msg);
- return true;
-}
-
-} // namespace bridge
-} // namespace apollo
diff --git a/modules/bridge/common/bridge_proto_serialized_buf.h b/modules/bridge/common/bridge_proto_serialized_buf.h
deleted file mode 100644
index 6b0cbd7e816..00000000000
--- a/modules/bridge/common/bridge_proto_serialized_buf.h
+++ /dev/null
@@ -1,106 +0,0 @@
-/******************************************************************************der
- * Copyright 2019 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.
- *****************************************************************************/
-
-#pragma once
-
-#include
-#include
-#include
-
-#include "modules/bridge/common/bridge_header.h"
-#include "modules/bridge/common/macro.h"
-
-namespace apollo {
-namespace bridge {
-
-template
-class BridgeProtoSerializedBuf {
- public:
- BridgeProtoSerializedBuf() {}
- ~BridgeProtoSerializedBuf();
-
- char *GetFrame(size_t index);
- bool Serialize(const std::shared_ptr &proto, const std::string &msg_name);
-
- const char *GetSerializedBuf(size_t index) const {
- return frames_[index].buf_;
- }
- size_t GetSerializedBufCount() const { return frames_.size(); }
- size_t GetSerializedBufSize(size_t index) const {
- return frames_[index].buf_len_;
- }
-
- private:
- struct Buf {
- char *buf_;
- size_t buf_len_;
- };
-
- private:
- std::vector frames_;
-};
-
-template
-BridgeProtoSerializedBuf::~BridgeProtoSerializedBuf() {
- for (auto frame : frames_) {
- FREE_ARRY(frame.buf_);
- }
-}
-
-template
-bool BridgeProtoSerializedBuf::Serialize(const std::shared_ptr &proto,
- const std::string &msg_name) {
- bsize msg_len = static_cast(proto->ByteSizeLong());
- char *tmp = new char[msg_len]();
- if (!proto->SerializeToArray(tmp, static_cast(msg_len))) {
- FREE_ARRY(tmp);
- return false;
- }
- bsize offset = 0;
- bsize frame_index = 0;
- uint32_t total_frames = static_cast(msg_len / FRAME_SIZE +
- (msg_len % FRAME_SIZE ? 1 : 0));
-
- while (offset < msg_len) {
- bsize left = msg_len - frame_index * FRAME_SIZE;
- bsize cpy_size = (left > FRAME_SIZE) ? FRAME_SIZE : left;
-
- BridgeHeader header;
- header.SetHeaderVer(0);
- header.SetMsgName(msg_name);
- header.SetMsgID(proto->header().sequence_num());
- header.SetTimeStamp(proto->header().timestamp_sec());
- header.SetMsgSize(msg_len);
- header.SetTotalFrames(total_frames);
- header.SetFrameSize(cpy_size);
- header.SetIndex(frame_index);
- header.SetFramePos(frame_index * FRAME_SIZE);
- hsize header_size = header.GetHeaderSize();
- Buf buf;
- buf.buf_ = new char[cpy_size + header_size];
- buf.buf_len_ = cpy_size + header_size;
- header.Serialize(buf.buf_, buf.buf_len_);
- memcpy(buf.buf_ + header_size, tmp + frame_index * FRAME_SIZE, cpy_size);
- frames_.push_back(buf);
- frame_index++;
- offset += cpy_size;
- }
- FREE_ARRY(tmp);
- return true;
-}
-
-} // namespace bridge
-} // namespace apollo
diff --git a/modules/bridge/common/macro.h b/modules/bridge/common/macro.h
deleted file mode 100644
index a22a714eb18..00000000000
--- a/modules/bridge/common/macro.h
+++ /dev/null
@@ -1,38 +0,0 @@
-/******************************************************************************
- * Copyright 2018 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.
- *****************************************************************************/
-
-#pragma once
-
-namespace apollo {
-namespace bridge {
-
-#define _1K 1024
-
-#define FREE_ARRY(arry) \
- if (arry) { \
- delete[] arry; \
- } \
- arry = nullptr
-
-#define FREE_POINTER(p) \
- if (p) { \
- delete p; \
- } \
- p = nullptr
-
-constexpr uint32_t FRAME_SIZE = 1024;
-} // namespace bridge
-} // namespace apollo
diff --git a/modules/bridge/common/udp_listener.h b/modules/bridge/common/udp_listener.h
deleted file mode 100644
index 0d4154c2570..00000000000
--- a/modules/bridge/common/udp_listener.h
+++ /dev/null
@@ -1,189 +0,0 @@
-/******************************************************************************
- * Copyright 2018 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.
- *****************************************************************************/
-
-#pragma once
-
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-namespace apollo {
-namespace bridge {
-
-constexpr int MAXEPOLLSIZE = 100;
-
-template
-class UDPListener {
- public:
- typedef bool (T::*func)(int fd);
- UDPListener() {}
- UDPListener(T *receiver, uint16_t port, func msg_handle) {
- receiver_ = receiver;
- listened_port_ = port;
- msg_handle_ = msg_handle;
- }
- ~UDPListener() {
- if (listener_sock_ != -1) {
- close(listener_sock_);
- }
- }
-
- void SetMsgHandle(func msg_handle) { msg_handle_ = msg_handle; }
- bool Initialize(T *receiver, func msg_handle, uint16_t port);
- bool Listen();
-
- static void *pthread_handle_message(void *param);
-
- public:
- struct Param {
- int fd_ = 0;
- UDPListener *listener_ = nullptr;
- };
-
- private:
- bool setnonblocking(int sockfd);
- void MessageHandle(int fd);
-
- private:
- T *receiver_ = nullptr;
- uint16_t listened_port_ = 0;
- int listener_sock_ = -1;
- func msg_handle_ = nullptr;
- int kdpfd_ = 0;
-};
-
-template
-bool UDPListener::Initialize(T *receiver, func msg_handle, uint16_t port) {
- msg_handle_ = msg_handle;
- if (!msg_handle_) {
- return false;
- }
-
- receiver_ = receiver;
- if (!receiver_) {
- return false;
- }
- listened_port_ = port;
- struct rlimit rt;
- rt.rlim_max = rt.rlim_cur = MAXEPOLLSIZE;
- if (setrlimit(RLIMIT_NOFILE, &rt) == -1) {
- return false;
- }
-
- listener_sock_ = socket(AF_INET, SOCK_DGRAM, 0);
- if (listener_sock_ == -1) {
- return false;
- }
- int opt = SO_REUSEADDR;
- setsockopt(listener_sock_, SOL_SOCKET, SO_REUSEADDR, &opt, sizeof(opt));
- setnonblocking(listener_sock_);
-
- struct sockaddr_in serv_addr;
- serv_addr.sin_family = PF_INET;
- serv_addr.sin_port = htons((uint16_t)listened_port_);
- serv_addr.sin_addr.s_addr = INADDR_ANY;
- if (bind(listener_sock_, (struct sockaddr *)&serv_addr,
- sizeof(struct sockaddr)) == -1) {
- close(listener_sock_);
- return false;
- }
- kdpfd_ = epoll_create(MAXEPOLLSIZE);
- struct epoll_event ev;
- ev.events = EPOLLIN | EPOLLET;
- ev.data.fd = listener_sock_;
- if (epoll_ctl(kdpfd_, EPOLL_CTL_ADD, listener_sock_, &ev) < 0) {
- close(listener_sock_);
- return false;
- }
- return true;
-}
-
-template
-bool UDPListener::Listen() {
- int nfds = -1;
- bool res = true;
- struct epoll_event events[MAXEPOLLSIZE];
- while (true) {
- nfds = epoll_wait(kdpfd_, events, 10000, -1);
- if (nfds == -1) {
- res = false;
- break;
- }
-
- for (int i = 0; i < nfds; ++i) {
- if (events[i].data.fd == listener_sock_) {
- pthread_t thread;
- pthread_attr_t attr;
- pthread_attr_init(&attr);
- pthread_attr_setscope(&attr, PTHREAD_SCOPE_SYSTEM);
- pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_DETACHED);
- Param *par = new Param;
- par->fd_ = events[i].data.fd;
- par->listener_ = this;
- if (pthread_create(&thread, &attr,
- &UDPListener::pthread_handle_message,
- reinterpret_cast(par))) {
- res = false;
- return res;
- }
- }
- }
- }
- close(listener_sock_);
- return res;
-}
-
-template
-bool UDPListener::setnonblocking(int sockfd) {
- if (fcntl(sockfd, F_SETFL, fcntl(sockfd, F_GETFD, 0) | O_NONBLOCK) == -1) {
- return false;
- }
- return true;
-}
-
-template
-void *UDPListener::pthread_handle_message(void *param) {
- Param *par = static_cast(param);
- int fd = par->fd_;
- UDPListener *listener = par->listener_;
- if (par) {
- delete par;
- }
- par = nullptr;
- if (!listener) {
- pthread_exit(nullptr);
- }
- listener->MessageHandle(fd);
- pthread_exit(nullptr);
-}
-
-template
-void UDPListener::MessageHandle(int fd) {
- if (!receiver_ || !msg_handle_) {
- return;
- }
- (receiver_->*msg_handle_)(fd);
-}
-
-} // namespace bridge
-} // namespace apollo
diff --git a/modules/bridge/common/util.cc b/modules/bridge/common/util.cc
deleted file mode 100644
index fdbf5303fa9..00000000000
--- a/modules/bridge/common/util.cc
+++ /dev/null
@@ -1,32 +0,0 @@
-/******************************************************************************
- * Copyright 2018 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.
- *****************************************************************************/
-#include "modules/bridge/common/util.h"
-
-namespace apollo {
-namespace bridge {
-
-int GetProtoSize(const char *buf, size_t size) {
- if (size != sizeof(size_t)) {
- return 0;
- }
- char size_buf[sizeof(size_t)] = {0};
- memcpy(size_buf, buf, sizeof(size_t));
- int proto_size = *(reinterpret_cast(size_buf));
- return proto_size;
-}
-
-} // namespace bridge
-} // namespace apollo
diff --git a/modules/bridge/common/util.h b/modules/bridge/common/util.h
deleted file mode 100644
index 75ed6aa1d2e..00000000000
--- a/modules/bridge/common/util.h
+++ /dev/null
@@ -1,83 +0,0 @@
-/******************************************************************************
- * Copyright 2019 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.
- *****************************************************************************/
-
-#pragma once
-
-#include
-#include
-#include
-#include