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. ![](images/Picture1.png) - -Its configuration file: -/Apollo/modules/bridge/conf/udp_bridge_receiver_chassis.pb.txt - -![](images/Picture2.png) - -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. -![](images/Picture3.png) - -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. ![](images/Picture4.png) - -## 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. ![](images/Picture5.png) 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) -``` - -![](images/Picture6.png) 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 - -#include "modules/bridge/common/bridge_buffer.h" -#include "modules/bridge/common/macro.h" - -namespace apollo { -namespace bridge { - -const int HEADER_BUF_SIZE = sizeof(size_t); -template -void WriteToBuffer(BridgeBuffer *buf, const std::shared_ptr &pb_msg) { - if (!buf) { - return; - } - size_t msg_len = pb_msg->ByteSize(); - size_t total_size = HEADER_BUF_SIZE + msg_len; - - buf->reset(total_size); - - buf->write(0, reinterpret_cast(&msg_len), sizeof(size_t)); - pb_msg->SerializeToArray(reinterpret_cast(buf + sizeof(size_t)), - static_cast(msg_len)); -} - -template -bool RemoveItem(std::vector *list, const T *t) { - if (!list) { - return false; - } - typename std::vector::iterator itor = list->begin(); - for (; itor != list->end();) { - if (*itor == t) { - T *tmp = *itor; - FREE_POINTER(tmp); - itor = list->erase(itor); - continue; - } - ++itor; - } - return true; -} - -template -bool RemoveItem(std::vector> *list, std::shared_ptr t) { - if (!list) { - return false; - } - typename std::vector>::iterator itor = list->begin(); - for (; itor != list->end();) { - if (itor->get() == t.get()) { - itor = list->erase(itor); - continue; - } - ++itor; - } - return true; -} - -int GetProtoSize(const char *buf, size_t size); - -} // namespace bridge -} // namespace apollo diff --git a/modules/bridge/conf/bridge.conf b/modules/bridge/conf/bridge.conf deleted file mode 100644 index 2ffb5fdc877..00000000000 --- a/modules/bridge/conf/bridge.conf +++ /dev/null @@ -1,2 +0,0 @@ ---flagfile=/apollo/modules/common/data/global_flagfile.txt ---timeout=10000.0 diff --git a/modules/bridge/conf/udp_bridge_receiver_chassis.pb.txt b/modules/bridge/conf/udp_bridge_receiver_chassis.pb.txt deleted file mode 100644 index fd79953dc91..00000000000 --- a/modules/bridge/conf/udp_bridge_receiver_chassis.pb.txt +++ /dev/null @@ -1,4 +0,0 @@ -topic_name: "/apollo/canbus/Chassis" -bind_port: 8900 -proto_name: "Chassis" -enable_timeout: false diff --git a/modules/bridge/conf/udp_bridge_sender_adctrajectory.pb.txt b/modules/bridge/conf/udp_bridge_sender_adctrajectory.pb.txt deleted file mode 100644 index dabf9b2bfcd..00000000000 --- a/modules/bridge/conf/udp_bridge_sender_adctrajectory.pb.txt +++ /dev/null @@ -1,3 +0,0 @@ -remote_ip: "127.0.0.1" -remote_port: 8900 -proto_name: "ADCTrajectory" diff --git a/modules/bridge/conf/udp_bridge_sender_localization.pb.txt b/modules/bridge/conf/udp_bridge_sender_localization.pb.txt deleted file mode 100644 index 092b2bacacb..00000000000 --- a/modules/bridge/conf/udp_bridge_sender_localization.pb.txt +++ /dev/null @@ -1,3 +0,0 @@ -remote_ip: "127.0.0.1" -remote_port: 8901 -proto_name: "LocalizationEstimate" diff --git a/modules/bridge/cyberfile.xml b/modules/bridge/cyberfile.xml deleted file mode 100644 index 1228aca6ad8..00000000000 --- a/modules/bridge/cyberfile.xml +++ /dev/null @@ -1,32 +0,0 @@ - - bridge - local - - This module provides a way for other Apollo modules interactiving with process - outside of Apollo by socket. It includes sender and receiver components. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/bridge - - cyber-dev - common-dev - 3rd-gflags-dev - 3rd-gtest-dev - common-msgs-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/bridge/dag/bridge_multi_receiver.dag b/modules/bridge/dag/bridge_multi_receiver.dag deleted file mode 100644 index 6fb1c3b3e19..00000000000 --- a/modules/bridge/dag/bridge_multi_receiver.dag +++ /dev/null @@ -1,12 +0,0 @@ -module_config { - module_library: "/apollo/bazel-bin/modules/bridge/libudp_bridge_multi_receiver_component.so" - - components { - - class_name: "UDPBridgeMultiReceiverComponent" - config { - name: "bridge_receiver_Chassis" - config_file_path: "/apollo/modules/bridge/conf/udp_bridge_receiver_chassis.pb.txt" - } - } -} diff --git a/modules/bridge/dag/bridge_receiver.dag b/modules/bridge/dag/bridge_receiver.dag deleted file mode 100644 index fd5515dfeed..00000000000 --- a/modules/bridge/dag/bridge_receiver.dag +++ /dev/null @@ -1,12 +0,0 @@ -module_config { - module_library: "/apollo/bazel-bin/modules/bridge/libudp_bridge_receiver_component.so" - - components { - - class_name: "UDPBridgeReceiverComponent" - config { - name: "bridge_receiver_Chassis" - config_file_path: "/apollo/modules/bridge/conf/udp_bridge_receiver_chassis.pb.txt" - } - } -} diff --git a/modules/bridge/dag/bridge_sender.dag b/modules/bridge/dag/bridge_sender.dag deleted file mode 100644 index e9543da1c49..00000000000 --- a/modules/bridge/dag/bridge_sender.dag +++ /dev/null @@ -1,26 +0,0 @@ -module_config { - module_library: "/apollo/bazel-bin/modules/bridge/libudp_bridge_sender_component.so" - components { - - class_name: "UDPBridgeSenderComponent" - config { - name: "bridge_sender_ADCTrajectory" - config_file_path: "/apollo/modules/bridge/conf/udp_bridge_sender_adctrajectory.pb.txt" - readers { - channel: "/apollo/planning" - } - } - } - - components { - - class_name: "UDPBridgeSenderComponent" - config { - name: "bridge_sender_LocalizationEstimate" - config_file_path: "/apollo/modules/bridge/conf/udp_bridge_sender_localization.pb.txt" - readers { - channel: "/apollo/localization/pose" - } - } - } -} diff --git a/modules/bridge/images/Picture1.png b/modules/bridge/images/Picture1.png deleted file mode 100644 index e1a3941149a..00000000000 Binary files a/modules/bridge/images/Picture1.png and /dev/null differ diff --git a/modules/bridge/images/Picture2.png b/modules/bridge/images/Picture2.png deleted file mode 100644 index d53be7bf546..00000000000 Binary files a/modules/bridge/images/Picture2.png and /dev/null differ diff --git a/modules/bridge/images/Picture3.png b/modules/bridge/images/Picture3.png deleted file mode 100644 index 3662b82956c..00000000000 Binary files a/modules/bridge/images/Picture3.png and /dev/null differ diff --git a/modules/bridge/images/Picture4.png b/modules/bridge/images/Picture4.png deleted file mode 100644 index 4ef560755af..00000000000 Binary files a/modules/bridge/images/Picture4.png and /dev/null differ diff --git a/modules/bridge/images/Picture5.png b/modules/bridge/images/Picture5.png deleted file mode 100644 index 345a58da0ee..00000000000 Binary files a/modules/bridge/images/Picture5.png and /dev/null differ diff --git a/modules/bridge/images/Picture6.png b/modules/bridge/images/Picture6.png deleted file mode 100644 index d3c94eb9433..00000000000 Binary files a/modules/bridge/images/Picture6.png and /dev/null differ diff --git a/modules/bridge/launch/bridge_multi_receiver.launch b/modules/bridge/launch/bridge_multi_receiver.launch deleted file mode 100644 index d0c0d3e6830..00000000000 --- a/modules/bridge/launch/bridge_multi_receiver.launch +++ /dev/null @@ -1,7 +0,0 @@ - - - bridge_multi_receiver - /apollo/modules/bridge/dag/bridge_multi_receiver.dag - udp_bridge_multi_receiver - - diff --git a/modules/bridge/launch/bridge_receiver.launch b/modules/bridge/launch/bridge_receiver.launch deleted file mode 100644 index ec691fe1c61..00000000000 --- a/modules/bridge/launch/bridge_receiver.launch +++ /dev/null @@ -1,7 +0,0 @@ - - - bridge_receiver - /apollo/modules/bridge/dag/bridge_receiver.dag - udp_bridge_receiver - - diff --git a/modules/bridge/launch/bridge_sender.launch b/modules/bridge/launch/bridge_sender.launch deleted file mode 100644 index 2174f4e36c1..00000000000 --- a/modules/bridge/launch/bridge_sender.launch +++ /dev/null @@ -1,7 +0,0 @@ - - - bridge_sender - /apollo/modules/bridge/dag/bridge_sender.dag - udp_bridge_sender - - diff --git a/modules/bridge/proto/BUILD b/modules/bridge/proto/BUILD deleted file mode 100644 index 03d7fa45631..00000000000 --- a/modules/bridge/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 = "udp_bridge_remote_info_cc_proto", - deps = [ - ":udp_bridge_remote_info_proto", - ], -) - -proto_library( - name = "udp_bridge_remote_info_proto", - srcs = ["udp_bridge_remote_info.proto"], -) - -py_proto_library( - name = "udp_bridge_remote_info_py_pb2", - deps = [ - ":udp_bridge_remote_info_proto", - ], -) - -install_files( - name = "py_pb_bridge", - dest = "bridge/python/modules/bridge/proto", - files = [ - "udp_bridge_remote_info_py_pb2", - ] -) diff --git a/modules/bridge/proto/udp_bridge_remote_info.proto b/modules/bridge/proto/udp_bridge_remote_info.proto deleted file mode 100644 index e01cd838070..00000000000 --- a/modules/bridge/proto/udp_bridge_remote_info.proto +++ /dev/null @@ -1,16 +0,0 @@ -syntax = "proto2"; - -package apollo.bridge; - -message UDPBridgeSenderRemoteInfo { - optional string remote_ip = 1 [default = "127.0.0.1"]; - optional int32 remote_port = 2 [default = 8900]; - optional string proto_name = 3 [default = "ProtoMsgName"]; -} - -message UDPBridgeReceiverRemoteInfo { - optional string topic_name = 1 [default = ""]; - optional int32 bind_port = 2 [default = 8500]; - optional string proto_name = 3 [default = "ProtoMsgName"]; - optional bool enable_timeout = 4 [default = true]; -} diff --git a/modules/bridge/test/BUILD b/modules/bridge/test/BUILD deleted file mode 100644 index 90ee9d6b2e1..00000000000 --- a/modules/bridge/test/BUILD +++ /dev/null @@ -1,36 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_binary") -load("//tools:cpplint.bzl", "cpplint") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -install( - name = "install", - runtime_dest = "bridge/bin", - targets = [ - ":bridge_receiver_test", - ":bridge_sender_test", - ], - visibility = ["//visibility:public"], -) - -cc_binary( - name = "bridge_receiver_test", - srcs = ["bridge_receiver_test.cc"], - deps = [ - "//cyber", - "//modules/bridge:udp_bridge", - "//modules/bridge/common:udp_listener", - ], -) - -cc_binary( - name = "bridge_sender_test", - srcs = ["bridge_sender_test.cc"], - deps = [ - "//cyber", - "//modules/bridge:udp_bridge", - ], -) - -cpplint() diff --git a/modules/bridge/test/bridge_receiver_test.cc b/modules/bridge/test/bridge_receiver_test.cc deleted file mode 100644 index da88472e81e..00000000000 --- a/modules/bridge/test/bridge_receiver_test.cc +++ /dev/null @@ -1,198 +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 -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include "modules/common_msgs/chassis_msgs/chassis.pb.h" - -#include "cyber/common/log.h" -#include "modules/bridge/common/bridge_proto_diserialized_buf.h" -#include "modules/bridge/common/macro.h" -#include "modules/bridge/common/udp_listener.h" -#include "modules/bridge/common/util.h" - -using apollo::bridge::BRIDGE_HEADER_FLAG; -using apollo::bridge::BridgeHeader; -using apollo::bridge::FRAME_SIZE; -using apollo::bridge::HEADER_FLAG_SIZE; -using apollo::bridge::hsize; -using apollo::bridge::MAXEPOLLSIZE; -using apollo::canbus::Chassis; -using BPDBChassis = apollo::bridge::BridgeProtoDiserializedBuf; - -void *pthread_handle_message(void *pfd) { - struct sockaddr_in client_addr; - socklen_t sock_len = static_cast(sizeof(client_addr)); - int bytes = 0; - int total_recv = 2 * FRAME_SIZE; - char total_buf[2 * FRAME_SIZE] = {0}; - bytes = - static_cast(recvfrom(*static_cast(pfd), total_buf, total_recv, - 0, (struct sockaddr *)&client_addr, &sock_len)); - ADEBUG << "total recv " << bytes; - if (bytes <= 0 || bytes > total_recv) { - pthread_exit(nullptr); - } - char header_flag[sizeof(BRIDGE_HEADER_FLAG) + 1] = {0}; - size_t offset = 0; - memcpy(header_flag, total_buf, HEADER_FLAG_SIZE); - if (strcmp(header_flag, BRIDGE_HEADER_FLAG) != 0) { - ADEBUG << "header flag not match!"; - pthread_exit(nullptr); - } - offset += sizeof(BRIDGE_HEADER_FLAG) + 1; - - char header_size_buf[sizeof(hsize) + 1] = {0}; - const char *cursor = total_buf + offset; - memcpy(header_size_buf, cursor, sizeof(hsize)); - hsize header_size = *(reinterpret_cast(header_size_buf)); - if (header_size > FRAME_SIZE) { - ADEBUG << "header size is more than FRAME_SIZE!"; - pthread_exit(nullptr); - } - offset += sizeof(hsize) + 1; - - BridgeHeader header; - size_t buf_size = header_size - offset; - cursor = total_buf + offset; - if (!header.Diserialize(cursor, buf_size)) { - ADEBUG << "header diserialize failed!"; - pthread_exit(nullptr); - } - - ADEBUG << "proto name : " << header.GetMsgName().c_str(); - ADEBUG << "proto sequence num: " << header.GetMsgID(); - ADEBUG << "proto total frames: " << header.GetTotalFrames(); - ADEBUG << "proto frame index: " << header.GetIndex(); - - BPDBChassis *proto_buf = new BPDBChassis(); - proto_buf->Initialize(header); - if (!proto_buf) { - pthread_exit(nullptr); - } - - cursor = total_buf + header_size; - char *buf = proto_buf->GetBuf(header.GetFramePos()); - memcpy(buf, cursor, header.GetFrameSize()); - proto_buf->UpdateStatus(header.GetIndex()); - if (proto_buf->IsReadyDiserialize()) { - auto pb_msg = std::make_shared(); - proto_buf->Diserialized(pb_msg); - ADEBUG << "sequence num: " << pb_msg->header().sequence_num(); - ADEBUG << "timestamp sec: " << pb_msg->header().timestamp_sec(); - ADEBUG << "engine rpm: " << pb_msg->engine_rpm(); - ADEBUG << "odometer m: " << pb_msg->odometer_m(); - ADEBUG << "throttle percentage: " << pb_msg->throttle_percentage(); - ADEBUG << "brake percentage: " << pb_msg->brake_percentage(); - ADEBUG << "steering percentage: " << pb_msg->steering_percentage(); - ADEBUG << "steering torque nm: " << pb_msg->steering_torque_nm(); - ADEBUG << "parking brake: " << pb_msg->parking_brake(); - } - pthread_exit(nullptr); -} - -bool receive(uint16_t port) { - struct rlimit rt; - rt.rlim_max = rt.rlim_cur = MAXEPOLLSIZE; - if (setrlimit(RLIMIT_NOFILE, &rt) == -1) { - ADEBUG << "set resource limitation failed"; - return false; - } - - int listener_sock = socket(AF_INET, SOCK_DGRAM, 0); - if (listener_sock == -1) { - ADEBUG << "create socket failed"; - return false; - } - int opt = SO_REUSEADDR; - setsockopt(listener_sock, SOL_SOCKET, SO_REUSEADDR, &opt, sizeof(opt)); - if (fcntl(listener_sock, F_SETFL, - fcntl(listener_sock, F_GETFD, 0) | O_NONBLOCK) == -1) { - ADEBUG << "set nonblocking failed"; - return false; - } - - struct sockaddr_in serv_addr; - serv_addr.sin_family = PF_INET; - serv_addr.sin_port = htons((uint16_t)port); - serv_addr.sin_addr.s_addr = INADDR_ANY; - if (bind(listener_sock, (struct sockaddr *)&serv_addr, - sizeof(struct sockaddr)) == -1) { - close(listener_sock); - ADEBUG << "bind socket failed"; - return false; - } - int 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) { - ADEBUG << "set control interface for an epoll descriptor failed"; - close(listener_sock); - return false; - } - - ADEBUG << "Ready!"; - - int nfds = -1; - bool res = true; - struct epoll_event events[MAXEPOLLSIZE]; - while (true) { - nfds = epoll_wait(kdpfd, events, 10000, -1); - if (nfds == -1) { - ADEBUG << "some error occurs while waiting for I/O event"; - 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); - if (pthread_create(&thread, &attr, &pthread_handle_message, - reinterpret_cast(&events[i].data.fd))) { - ADEBUG << "message handler creation failed"; - res = false; - break; - } - } - } - if (!res) { - break; - } - } - close(listener_sock); - return res; -} - -int main(int argc, char *argv[]) { - receive(8900); - return 0; -} diff --git a/modules/bridge/test/bridge_sender_test.cc b/modules/bridge/test/bridge_sender_test.cc deleted file mode 100644 index 3a07188f966..00000000000 --- a/modules/bridge/test/bridge_sender_test.cc +++ /dev/null @@ -1,113 +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 -#include -#include -#include - -#include -#include - -#include "modules/common_msgs/chassis_msgs/chassis.pb.h" - -#include "cyber/common/log.h" -#include "cyber/scheduler/scheduler_factory.h" -#include "cyber/time/clock.h" -#include "modules/bridge/common/bridge_proto_serialized_buf.h" - -using apollo::cyber::Clock; - -bool send(const std::string &remote_ip, uint16_t remote_port, uint32_t count) { - if (count == 0) { - count = 10000; - } - float total = static_cast(count); - float hundred = 100.00; - for (uint32_t i = 0; i < count; i++) { - double timestamp_ = Clock::NowInSeconds() + 2.0; - float coefficient = static_cast(i); - auto pb_msg = std::make_shared(); - pb_msg->mutable_header()->set_sequence_num(i); - pb_msg->mutable_header()->set_timestamp_sec(timestamp_); - pb_msg->set_engine_started(true); - pb_msg->set_engine_rpm(static_cast(coefficient * 2.0)); - pb_msg->set_odometer_m(coefficient); - pb_msg->set_fuel_range_m(100); - pb_msg->set_throttle_percentage(coefficient * hundred / total); - pb_msg->set_brake_percentage(coefficient * hundred / total); - pb_msg->set_steering_percentage(coefficient * hundred / total); - pb_msg->set_steering_torque_nm(coefficient); - pb_msg->set_parking_brake(i % 2); - pb_msg->set_high_beam_signal(false); - pb_msg->set_low_beam_signal(true); - pb_msg->set_left_turn_signal(false); - pb_msg->set_right_turn_signal(false); - pb_msg->set_horn(false); - pb_msg->set_wiper(false); - pb_msg->set_disengage_status(false); - pb_msg->set_driving_mode(apollo::canbus::Chassis::COMPLETE_MANUAL); - pb_msg->set_error_code(apollo::canbus::Chassis::NO_ERROR); - pb_msg->set_gear_location(apollo::canbus::Chassis::GEAR_NEUTRAL); - - struct sockaddr_in server_addr; - server_addr.sin_addr.s_addr = inet_addr(remote_ip.c_str()); - server_addr.sin_family = AF_INET; - server_addr.sin_port = htons(remote_port); - - ADEBUG << "connecting to server... "; - - int sock_fd = socket(AF_INET, SOCK_DGRAM | SOCK_NONBLOCK, 0); - - int res = - connect(sock_fd, (struct sockaddr *)&server_addr, sizeof(server_addr)); - if (res < 0) { - ADEBUG << "connected server failed "; - continue; - } - - ADEBUG << "connected to server success. port [" << remote_port << "]"; - - apollo::bridge::BridgeProtoSerializedBuf proto_buf; - proto_buf.Serialize(pb_msg, "Chassis"); - for (size_t j = 0; j < proto_buf.GetSerializedBufCount(); j++) { - ssize_t nbytes = send(sock_fd, proto_buf.GetSerializedBuf(j), - proto_buf.GetSerializedBufSize(j), 0); - if (nbytes != static_cast(proto_buf.GetSerializedBufSize(j))) { - ADEBUG << "sent msg failed "; - break; - } - ADEBUG << "sent " << nbytes << " bytes to server with sequence num " << i; - } - close(sock_fd); - - // 1000Hz - std::this_thread::sleep_for(std::chrono::milliseconds(1)); - } - return true; -} - -int main(int argc, char *argv[]) { - uint32_t count = 0; - if (argc < 2) { - count = 10000; - } else { - count = atoi(argv[1]); - CHECK_LE(count, 20000U); - } - send("127.0.0.1", 8900, count); - return 0; -} diff --git a/modules/bridge/udp_bridge_component_test.cc b/modules/bridge/udp_bridge_component_test.cc deleted file mode 100644 index a39714abc05..00000000000 --- a/modules/bridge/udp_bridge_component_test.cc +++ /dev/null @@ -1,32 +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 "cyber/init.h" -#include "modules/bridge/udp_bridge_sender_component.h" - -namespace apollo { -namespace bridge { - -TEST(UDPBridgeSenderComponentTest, Simple) { - cyber::Init("udp_bridge_component_test"); - UDPBridgeSenderComponent udp_bridge_component; - EXPECT_EQ(udp_bridge_component.Name(), "Bridge"); -} - -} // namespace bridge -} // namespace apollo diff --git a/modules/bridge/udp_bridge_multi_receiver_component.cc b/modules/bridge/udp_bridge_multi_receiver_component.cc deleted file mode 100644 index 8f140cd1a98..00000000000 --- a/modules/bridge/udp_bridge_multi_receiver_component.cc +++ /dev/null @@ -1,191 +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/udp_bridge_multi_receiver_component.h" - -#include "cyber/time/clock.h" -#include "modules/bridge/common/bridge_proto_diser_buf_factory.h" -#include "modules/bridge/common/macro.h" -#include "modules/bridge/common/util.h" - -namespace apollo { -namespace bridge { - -UDPBridgeMultiReceiverComponent::UDPBridgeMultiReceiverComponent() - : monitor_logger_buffer_(common::monitor::MonitorMessageItem::CONTROL) {} - -bool UDPBridgeMultiReceiverComponent::Init() { - AINFO << "UDP bridge multi :receiver init, startin..."; - apollo::bridge::UDPBridgeReceiverRemoteInfo udp_bridge_remote; - if (!this->GetProtoConfig(&udp_bridge_remote)) { - AINFO << "load udp bridge component proto param failed"; - return false; - } - bind_port_ = udp_bridge_remote.bind_port(); - enable_timeout_ = udp_bridge_remote.enable_timeout(); - ADEBUG << "UDP Bridge remote port is: " << bind_port_; - - if (!InitSession((uint16_t)bind_port_)) { - return false; - } - ADEBUG << "initialize session successful."; - MsgDispatcher(); - return true; -} - -bool UDPBridgeMultiReceiverComponent::InitSession(uint16_t port) { - return listener_->Initialize( - this, &UDPBridgeMultiReceiverComponent::MsgHandle, port); -} - -void UDPBridgeMultiReceiverComponent::MsgDispatcher() { - ADEBUG << "msg dispatcher start successful."; - listener_->Listen(); -} - -std::shared_ptr -UDPBridgeMultiReceiverComponent::CreateBridgeProtoBuf( - const BridgeHeader &header) { - std::shared_ptr proto_buf; - if (IsTimeout(header.GetTimeStamp())) { - std::vector>::iterator itor = - proto_list_.begin(); - for (; itor != proto_list_.end();) { - if ((*itor)->IsTheProto(header)) { - itor = proto_list_.erase(itor); - break; - } - ++itor; - } - return proto_buf; - } - - for (auto proto : proto_list_) { - if (proto->IsTheProto(header)) { - return proto; - } - } - - proto_buf = ProtoDiserializedBufBaseFactory::CreateObj(header); - if (!proto_buf) { - return proto_buf; - } - proto_buf->Initialize(header, node_); - proto_list_.push_back(proto_buf); - return proto_buf; -} - -bool UDPBridgeMultiReceiverComponent::IsProtoExist(const BridgeHeader &header) { - for (auto proto : proto_list_) { - if (proto->IsTheProto(header)) { - return true; - } - } - return false; -} - -bool UDPBridgeMultiReceiverComponent::IsTimeout(double time_stamp) { - if (enable_timeout_ == false) { - return false; - } - double cur_time = apollo::cyber::Clock::NowInSeconds(); - if (cur_time < time_stamp) { - return true; - } - if (FLAGS_timeout < cur_time - time_stamp) { - return true; - } - return false; -} - -bool UDPBridgeMultiReceiverComponent::MsgHandle(int fd) { - struct sockaddr_in client_addr; - socklen_t sock_len = static_cast(sizeof(client_addr)); - int total_recv = 2 * FRAME_SIZE; - char total_buf[2 * FRAME_SIZE] = {0}; - int bytes = - static_cast(recvfrom(fd, total_buf, total_recv, 0, - (struct sockaddr *)&client_addr, &sock_len)); - if (bytes <= 0 || bytes > total_recv) { - return false; - } - - if (strncmp(total_buf, BRIDGE_HEADER_FLAG, HEADER_FLAG_SIZE) != 0) { - AERROR << "Header flag didn't match!"; - return false; - } - size_t offset = HEADER_FLAG_SIZE + 1; - - const char *cursor = total_buf + offset; - hsize header_size = *(reinterpret_cast(cursor)); - offset += sizeof(hsize) + 1; - - if (header_size < offset || header_size > FRAME_SIZE) { - AERROR << "header size is more than FRAME_SIZE!"; - return false; - } - - cursor = total_buf + offset; - size_t buf_size = header_size - offset; - BridgeHeader header; - if (!header.Diserialize(cursor, buf_size)) { - AERROR << "header diserialize failed!"; - return false; - } - - ADEBUG << "proto name : " << header.GetMsgName().c_str(); - ADEBUG << "proto sequence num: " << header.GetMsgID(); - ADEBUG << "proto total frames: " << header.GetTotalFrames(); - ADEBUG << "proto frame index: " << header.GetIndex(); - - std::lock_guard lock(mutex_); - std::shared_ptr proto_buf = - CreateBridgeProtoBuf(header); - if (!proto_buf) { - return false; - } - - cursor = total_buf + header_size; - char *buf = proto_buf->GetBuf(header.GetFramePos()); - memcpy(buf, cursor, header.GetFrameSize()); - proto_buf->UpdateStatus(header.GetIndex()); - if (proto_buf->IsReadyDiserialize()) { - proto_buf->DiserializedAndPub(); - RemoveInvalidBuf(proto_buf->GetMsgID(), proto_buf->GetMsgName()); - RemoveItem(&proto_list_, proto_buf); - } - return true; -} - -bool UDPBridgeMultiReceiverComponent::RemoveInvalidBuf( - uint32_t msg_id, const std::string &msg_name) { - if (msg_id == 0) { - return false; - } - std::vector>::iterator itor = - proto_list_.begin(); - for (; itor != proto_list_.end();) { - if ((*itor)->GetMsgID() < msg_id && - strcmp((*itor)->GetMsgName().c_str(), msg_name.c_str()) == 0) { - itor = proto_list_.erase(itor); - continue; - } - ++itor; - } - return true; -} - -} // namespace bridge -} // namespace apollo diff --git a/modules/bridge/udp_bridge_multi_receiver_component.h b/modules/bridge/udp_bridge_multi_receiver_component.h deleted file mode 100644 index c681ff5a5b0..00000000000 --- a/modules/bridge/udp_bridge_multi_receiver_component.h +++ /dev/null @@ -1,74 +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 "modules/bridge/proto/udp_bridge_remote_info.pb.h" -#include "modules/common_msgs/chassis_msgs/chassis.pb.h" - -#include "cyber/class_loader/class_loader.h" -#include "cyber/component/component.h" -#include "cyber/cyber.h" -#include "cyber/init.h" -#include "cyber/scheduler/scheduler_factory.h" -#include "modules/bridge/common/bridge_gflags.h" -#include "modules/bridge/common/bridge_header.h" -#include "modules/bridge/common/bridge_proto_diserialized_buf.h" -#include "modules/bridge/common/udp_listener.h" -#include "modules/common/monitor_log/monitor_log_buffer.h" - -namespace apollo { -namespace bridge { -class UDPBridgeMultiReceiverComponent final : public cyber::Component<> { - public: - UDPBridgeMultiReceiverComponent(); - ~UDPBridgeMultiReceiverComponent() = default; - - bool Init() override; - std::string Name() const { return FLAGS_bridge_module_name; } - std::shared_ptr CreateBridgeProtoBuf( - const BridgeHeader &header); - bool IsProtoExist(const BridgeHeader &header); - bool IsTimeout(double time_stamp); - void MsgDispatcher(); - bool InitSession(uint16_t port); - bool MsgHandle(int fd); - - private: - bool RemoveInvalidBuf(uint32_t msg_id, const std::string &msg_name); - - private: - common::monitor::MonitorLogBuffer monitor_logger_buffer_; - std::shared_ptr> listener_ = - std::make_shared>(); - unsigned int bind_port_ = 0; - bool enable_timeout_ = true; - std::mutex mutex_; - std::vector> proto_list_; -}; - -CYBER_REGISTER_COMPONENT(UDPBridgeMultiReceiverComponent) - -} // namespace bridge -} // namespace apollo diff --git a/modules/bridge/udp_bridge_receiver_component.cc b/modules/bridge/udp_bridge_receiver_component.cc deleted file mode 100644 index 07cb5383f00..00000000000 --- a/modules/bridge/udp_bridge_receiver_component.cc +++ /dev/null @@ -1,221 +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/udp_bridge_receiver_component.h" - -#include "cyber/time/clock.h" -#include "modules/bridge/common/macro.h" -#include "modules/bridge/common/util.h" - -namespace apollo { -namespace bridge { - -#define BRIDGE_RECV_IMPL(pb_msg) \ - template class UDPBridgeReceiverComponent - -template -UDPBridgeReceiverComponent::UDPBridgeReceiverComponent() - : monitor_logger_buffer_(common::monitor::MonitorMessageItem::CONTROL) {} - -template -UDPBridgeReceiverComponent::~UDPBridgeReceiverComponent() { - for (auto proto : proto_list_) { - FREE_POINTER(proto); - } -} - -template -bool UDPBridgeReceiverComponent::Init() { - AINFO << "UDP bridge receiver init, startin..."; - apollo::bridge::UDPBridgeReceiverRemoteInfo udp_bridge_remote; - if (!this->GetProtoConfig(&udp_bridge_remote)) { - AINFO << "load udp bridge component proto param failed"; - return false; - } - bind_port_ = udp_bridge_remote.bind_port(); - proto_name_ = udp_bridge_remote.proto_name(); - topic_name_ = udp_bridge_remote.topic_name(); - enable_timeout_ = udp_bridge_remote.enable_timeout(); - ADEBUG << "UDP Bridge remote port is: " << bind_port_; - ADEBUG << "UDP Bridge for Proto is: " << proto_name_; - writer_ = node_->CreateWriter(topic_name_.c_str()); - - if (!InitSession((uint16_t)bind_port_)) { - return false; - } - ADEBUG << "initialize session successful."; - MsgDispatcher(); - return true; -} - -template -bool UDPBridgeReceiverComponent::InitSession(uint16_t port) { - return listener_->Initialize(this, &UDPBridgeReceiverComponent::MsgHandle, - port); -} - -template -void UDPBridgeReceiverComponent::MsgDispatcher() { - ADEBUG << "msg dispatcher start successful."; - listener_->Listen(); -} - -template -BridgeProtoDiserializedBuf - *UDPBridgeReceiverComponent::CreateBridgeProtoBuf( - const BridgeHeader &header) { - if (IsTimeout(header.GetTimeStamp())) { - typename std::vector *>::iterator itor = - proto_list_.begin(); - for (; itor != proto_list_.end();) { - if ((*itor)->IsTheProto(header)) { - BridgeProtoDiserializedBuf *tmp = *itor; - FREE_POINTER(tmp); - itor = proto_list_.erase(itor); - break; - } - ++itor; - } - return nullptr; - } - - for (auto proto : proto_list_) { - if (proto->IsTheProto(header)) { - return proto; - } - } - BridgeProtoDiserializedBuf *proto_buf = new BridgeProtoDiserializedBuf; - if (!proto_buf) { - return nullptr; - } - proto_buf->Initialize(header); - proto_list_.push_back(proto_buf); - return proto_buf; -} - -template -bool UDPBridgeReceiverComponent::IsProtoExist(const BridgeHeader &header) { - for (auto proto : proto_list_) { - if (proto->IsTheProto(header)) { - return true; - } - } - return false; -} - -template -bool UDPBridgeReceiverComponent::IsTimeout(double time_stamp) { - if (enable_timeout_ == false) { - return false; - } - double cur_time = apollo::cyber::Clock::NowInSeconds(); - if (cur_time < time_stamp) { - return true; - } - if (FLAGS_timeout < cur_time - time_stamp) { - return true; - } - return false; -} - -template -bool UDPBridgeReceiverComponent::MsgHandle(int fd) { - struct sockaddr_in client_addr; - socklen_t sock_len = static_cast(sizeof(client_addr)); - int bytes = 0; - int total_recv = 2 * FRAME_SIZE; - char total_buf[2 * FRAME_SIZE] = {0}; - bytes = - static_cast(recvfrom(fd, total_buf, total_recv, 0, - (struct sockaddr *)&client_addr, &sock_len)); - ADEBUG << "total recv " << bytes; - if (bytes <= 0 || bytes > total_recv) { - return false; - } - char header_flag[sizeof(BRIDGE_HEADER_FLAG) + 1] = {0}; - size_t offset = 0; - memcpy(header_flag, total_buf, HEADER_FLAG_SIZE); - if (strcmp(header_flag, BRIDGE_HEADER_FLAG) != 0) { - AINFO << "header flag not match!"; - return false; - } - offset += sizeof(BRIDGE_HEADER_FLAG) + 1; - - char header_size_buf[sizeof(hsize) + 1] = {0}; - const char *cursor = total_buf + offset; - memcpy(header_size_buf, cursor, sizeof(hsize)); - hsize header_size = *(reinterpret_cast(header_size_buf)); - if (header_size > FRAME_SIZE) { - AINFO << "header size is more than FRAME_SIZE!"; - return false; - } - offset += sizeof(hsize) + 1; - - BridgeHeader header; - size_t buf_size = header_size - offset; - cursor = total_buf + offset; - if (!header.Diserialize(cursor, buf_size)) { - AINFO << "header diserialize failed!"; - return false; - } - - ADEBUG << "proto name : " << header.GetMsgName().c_str(); - ADEBUG << "proto sequence num: " << header.GetMsgID(); - ADEBUG << "proto total frames: " << header.GetTotalFrames(); - ADEBUG << "proto frame index: " << header.GetIndex(); - - std::lock_guard lock(mutex_); - BridgeProtoDiserializedBuf *proto_buf = CreateBridgeProtoBuf(header); - if (!proto_buf) { - return false; - } - - cursor = total_buf + header_size; - char *buf = proto_buf->GetBuf(header.GetFramePos()); - memcpy(buf, cursor, header.GetFrameSize()); - proto_buf->UpdateStatus(header.GetIndex()); - if (proto_buf->IsReadyDiserialize()) { - auto pb_msg = std::make_shared(); - proto_buf->Diserialized(pb_msg); - writer_->Write(pb_msg); - RemoveInvalidBuf(proto_buf->GetMsgID()); - RemoveItem(&proto_list_, proto_buf); - } - return true; -} - -template -bool UDPBridgeReceiverComponent::RemoveInvalidBuf(uint32_t msg_id) { - if (msg_id == 0) { - return false; - } - typename std::vector *>::iterator itor = - proto_list_.begin(); - for (; itor != proto_list_.end();) { - if ((*itor)->GetMsgID() < msg_id) { - BridgeProtoDiserializedBuf *tmp = *itor; - FREE_POINTER(tmp); - itor = proto_list_.erase(itor); - continue; - } - ++itor; - } - return true; -} - -BRIDGE_RECV_IMPL(canbus::Chassis); -} // namespace bridge -} // namespace apollo diff --git a/modules/bridge/udp_bridge_receiver_component.h b/modules/bridge/udp_bridge_receiver_component.h deleted file mode 100644 index 4bfbe6194ae..00000000000 --- a/modules/bridge/udp_bridge_receiver_component.h +++ /dev/null @@ -1,84 +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 "modules/bridge/proto/udp_bridge_remote_info.pb.h" -#include "modules/common_msgs/chassis_msgs/chassis.pb.h" - -#include "cyber/class_loader/class_loader.h" -#include "cyber/component/component.h" -#include "cyber/cyber.h" -#include "cyber/init.h" -#include "cyber/scheduler/scheduler_factory.h" -#include "modules/bridge/common/bridge_gflags.h" -#include "modules/bridge/common/bridge_header.h" -#include "modules/bridge/common/bridge_proto_diserialized_buf.h" -#include "modules/bridge/common/udp_listener.h" -#include "modules/common/monitor_log/monitor_log_buffer.h" - -namespace apollo { -namespace bridge { - -#define RECEIVER_BRIDGE_COMPONENT_REGISTER(pb_msg) \ - CYBER_REGISTER_COMPONENT(UDPBridgeReceiverComponent) - -template -class UDPBridgeReceiverComponent final : public cyber::Component<> { - public: - UDPBridgeReceiverComponent(); - ~UDPBridgeReceiverComponent(); - - bool Init() override; - - std::string Name() const { return FLAGS_bridge_module_name; } - bool MsgHandle(int fd); - - private: - bool InitSession(uint16_t port); - void MsgDispatcher(); - bool IsProtoExist(const BridgeHeader &header); - BridgeProtoDiserializedBuf *CreateBridgeProtoBuf( - const BridgeHeader &header); - bool IsTimeout(double time_stamp); - bool RemoveInvalidBuf(uint32_t msg_id); - - private: - common::monitor::MonitorLogBuffer monitor_logger_buffer_; - unsigned int bind_port_ = 0; - std::string proto_name_ = ""; - std::string topic_name_ = ""; - bool enable_timeout_ = true; - std::shared_ptr> writer_; - std::mutex mutex_; - - std::shared_ptr>> listener_ = - std::make_shared>>(); - - std::vector *> proto_list_; -}; - -RECEIVER_BRIDGE_COMPONENT_REGISTER(canbus::Chassis) -} // namespace bridge -} // namespace apollo diff --git a/modules/bridge/udp_bridge_sender_component.cc b/modules/bridge/udp_bridge_sender_component.cc deleted file mode 100644 index 28d2f071586..00000000000 --- a/modules/bridge/udp_bridge_sender_component.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/udp_bridge_sender_component.h" - -#include "modules/bridge/common/bridge_proto_serialized_buf.h" -#include "modules/bridge/common/macro.h" -#include "modules/bridge/common/util.h" - -namespace apollo { -namespace bridge { - -#define BRIDGE_IMPL(pb_msg) template class UDPBridgeSenderComponent - -using apollo::bridge::UDPBridgeSenderRemoteInfo; -using apollo::cyber::io::Session; -using apollo::localization::LocalizationEstimate; - -template -bool UDPBridgeSenderComponent::Init() { - AINFO << "UDP bridge sender init, startin..."; - apollo::bridge::UDPBridgeSenderRemoteInfo udp_bridge_remote; - if (!this->GetProtoConfig(&udp_bridge_remote)) { - AINFO << "load udp bridge component proto param failed"; - return false; - } - remote_ip_ = udp_bridge_remote.remote_ip(); - remote_port_ = udp_bridge_remote.remote_port(); - proto_name_ = udp_bridge_remote.proto_name(); - ADEBUG << "UDP Bridge remote ip is: " << remote_ip_; - ADEBUG << "UDP Bridge remote port is: " << remote_port_; - ADEBUG << "UDP Bridge for Proto is: " << proto_name_; - return true; -} - -template -bool UDPBridgeSenderComponent::Proc(const std::shared_ptr &pb_msg) { - if (remote_port_ == 0 || remote_ip_.empty()) { - AERROR << "remote info is invalid!"; - return false; - } - - if (pb_msg == nullptr) { - AERROR << "proto msg is not ready!"; - return false; - } - - struct sockaddr_in server_addr; - server_addr.sin_addr.s_addr = inet_addr(remote_ip_.c_str()); - server_addr.sin_family = AF_INET; - server_addr.sin_port = htons(static_cast(remote_port_)); - int sock_fd = socket(AF_INET, SOCK_DGRAM | SOCK_NONBLOCK, 0); - - int res = - connect(sock_fd, (struct sockaddr *)&server_addr, sizeof(server_addr)); - if (res < 0) { - close(sock_fd); - return false; - } - - BridgeProtoSerializedBuf proto_buf; - proto_buf.Serialize(pb_msg, proto_name_); - for (size_t j = 0; j < proto_buf.GetSerializedBufCount(); j++) { - ssize_t nbytes = send(sock_fd, proto_buf.GetSerializedBuf(j), - proto_buf.GetSerializedBufSize(j), 0); - if (nbytes != static_cast(proto_buf.GetSerializedBufSize(j))) { - break; - } - } - close(sock_fd); - - return true; -} - -BRIDGE_IMPL(LocalizationEstimate); -BRIDGE_IMPL(planning::ADCTrajectory); - -} // namespace bridge -} // namespace apollo diff --git a/modules/bridge/udp_bridge_sender_component.h b/modules/bridge/udp_bridge_sender_component.h deleted file mode 100644 index 6e492120b03..00000000000 --- a/modules/bridge/udp_bridge_sender_component.h +++ /dev/null @@ -1,70 +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 -#include -#include -#include - -#include "modules/bridge/proto/udp_bridge_remote_info.pb.h" -#include "modules/common_msgs/planning_msgs/planning.pb.h" - -#include "cyber/class_loader/class_loader.h" -#include "cyber/component/component.h" -#include "cyber/cyber.h" -#include "cyber/init.h" -#include "cyber/io/session.h" -#include "cyber/scheduler/scheduler_factory.h" -#include "modules/bridge/common/bridge_gflags.h" -#include "modules/common/monitor_log/monitor_log_buffer.h" -#include "modules/common/util/util.h" - -namespace apollo { -namespace bridge { - -#define BRIDGE_COMPONENT_REGISTER(pb_msg) \ - CYBER_REGISTER_COMPONENT(UDPBridgeSenderComponent) - -template -class UDPBridgeSenderComponent final : public cyber::Component { - public: - UDPBridgeSenderComponent() - : monitor_logger_buffer_(common::monitor::MonitorMessageItem::CONTROL) {} - - bool Init() override; - bool Proc(const std::shared_ptr &pb_msg) override; - - std::string Name() const { return FLAGS_bridge_module_name; } - - private: - common::monitor::MonitorLogBuffer monitor_logger_buffer_; - unsigned int remote_port_ = 0; - std::string remote_ip_ = ""; - std::string proto_name_ = ""; - std::mutex mutex_; -}; - -BRIDGE_COMPONENT_REGISTER(planning::ADCTrajectory) -BRIDGE_COMPONENT_REGISTER(localization::LocalizationEstimate) - -} // namespace bridge -} // namespace apollo diff --git a/modules/calibration/BUILD b/modules/calibration/BUILD index 6c18041858f..6ddd9359241 100644 --- a/modules/calibration/BUILD +++ b/modules/calibration/BUILD @@ -7,7 +7,6 @@ install( data_dest = "calibration", data = [ ":calibrated_vehicles", - ":cyberfile.xml", ":calibration.BUILD", ], ) diff --git a/modules/calibration/cyberfile.xml b/modules/calibration/cyberfile.xml deleted file mode 100644 index c5f67495837..00000000000 --- a/modules/calibration/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - calibration - local - - Apollo calibration module. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/calibration - - diff --git a/modules/canbus/BUILD b/modules/canbus/BUILD index ebf73c49ae1..6f7b085dbae 100644 --- a/modules/canbus/BUILD +++ b/modules/canbus/BUILD @@ -1,5 +1,5 @@ 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/install:install.bzl", "install", "install_files") load("//tools:cpplint.bzl", "cpplint") package(default_visibility = ["//visibility:public"]) @@ -11,15 +11,17 @@ cc_library( srcs = ["canbus_component.cc"], hdrs = ["canbus_component.h"], copts = CANBUS_COPTS, - alwayslink = True, deps = [ "//cyber", - "//modules/canbus/common:canbus_gflags", - "//modules/canbus/vehicle:abstract_vehicle_factory", + "//modules/canbus/common:canbus_common", + "//modules/canbus/vehicle:vehicle_factory", "//modules/common/adapters:adapter_gflags", "//modules/common/monitor_log", "//modules/common/status", - "//modules/drivers/canbus:sensor_canbus_lib", + "//modules/drivers/canbus/can_client", + "//modules/drivers/canbus/can_client:can_client_factory", + "//modules/drivers/canbus/can_comm:can_receiver", + "//modules/drivers/canbus/can_comm:can_sender", "//modules/common_msgs/guardian_msgs:guardian_cc_proto", "@com_github_gflags_gflags//:gflags", ], @@ -39,53 +41,29 @@ cc_test( cc_binary( name = "libcanbus_component.so", linkshared = True, - linkstatic = True, + linkstatic = False, deps = [ ":canbus_component_lib", ], ) -install( - name = "testdata", - data_dest = "canbus/addition_data", - data = [ - ":test_data", - ], -) - install( name = "install", - library_dest = "canbus/lib", - data_dest = "canbus", data = [ ":runtime_data", - ":cyberfile.xml", - ":canbus.BUILD", ], targets = [ ":libcanbus_component.so", ], deps = [ ":pb_canbus", - ":pb_hdrs", - ":testdata", - "//modules/canbus/common:install", - "//modules/canbus/tools:install", - ], -) - -install( - name = "pb_hdrs", - data_dest = "canbus/include", - data = [ - "//modules/canbus/proto:canbus_conf_cc_proto", - "//modules/canbus/proto:vehicle_parameter_cc_proto", + "//cyber:install", ], ) install_files( name = "pb_canbus", - dest = "canbus", + dest = "modules/canbus", files = [ "//modules/common_msgs/chassis_msgs:chassis_py_pb2", ], @@ -107,26 +85,4 @@ filegroup( srcs = glob(["testdata/**"]), ) -install_src_files( - name = "install_src", - deps = [ - ":install_canbus_src", - ":install_canbus_hdrs" - ], -) - -install_src_files( - name = "install_canbus_src", - src_dir = ["."], - dest = "canbus/src", - filter = "*", -) - -install_src_files( - name = "install_canbus_hdrs", - src_dir = ["."], - dest = "canbus/include", - filter = "*.h", -) - cpplint() diff --git a/modules/canbus/canbus.BUILD b/modules/canbus/canbus.BUILD deleted file mode 100644 index 04d02d7de8f..00000000000 --- a/modules/canbus/canbus.BUILD +++ /dev/null @@ -1,11 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_library") - -cc_library( - name = "canbus", - includes = ["include"], - hdrs = glob(["include/**/*.h"]), - srcs = glob(["lib/**/*.so*"]), - include_prefix = "modules/canbus", - strip_include_prefix = "include", - visibility = ["//visibility:public"], -) \ No newline at end of file diff --git a/modules/canbus/canbus_component.cc b/modules/canbus/canbus_component.cc index dcb6a500818..0ca3f658f78 100644 --- a/modules/canbus/canbus_component.cc +++ b/modules/canbus/canbus_component.cc @@ -16,10 +16,9 @@ #include "modules/canbus/canbus_component.h" -#include "cyber/class_loader/class_loader.h" -#include "cyber/common/file.h" #include "cyber/time/time.h" #include "modules/canbus/common/canbus_gflags.h" +#include "modules/canbus/vehicle/vehicle_factory.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/common/util/util.h" #include "modules/drivers/canbus/can_client/can_client_factory.h" @@ -27,7 +26,6 @@ using apollo::common::ErrorCode; using apollo::control::ControlCommand; using apollo::cyber::Time; -using apollo::cyber::class_loader::ClassLoader; using apollo::drivers::canbus::CanClientFactory; using apollo::guardian::GuardianCommand; @@ -45,36 +43,66 @@ bool CanbusComponent::Init() { AERROR << "Unable to load canbus conf file: " << ConfigFilePath(); return false; } + AINFO << "The canbus conf file is loaded: " << FLAGS_canbus_conf_file; ADEBUG << "Canbus_conf:" << canbus_conf_.ShortDebugString(); - if (!apollo::cyber::common::PathExists(FLAGS_load_vehicle_library)) { - AERROR << FLAGS_load_vehicle_library << " No such vehicle library"; + // Init can client + auto can_factory = CanClientFactory::Instance(); + can_factory->RegisterCanClients(); + can_client_ = can_factory->CreateCANClient(canbus_conf_.can_card_parameter()); + if (!can_client_) { + AERROR << "Failed to create can client."; return false; } - AINFO << "Load the vehicle factory library: " << FLAGS_load_vehicle_library; + AINFO << "Can client is successfully created."; - ClassLoader loader(FLAGS_load_vehicle_library); - auto vehicle_object = loader.CreateClassObj( - FLAGS_load_vehicle_class_name); + VehicleFactory vehicle_factory; + vehicle_factory.RegisterVehicleFactory(); + auto vehicle_object = + vehicle_factory.CreateVehicle(canbus_conf_.vehicle_parameter()); if (!vehicle_object) { - AERROR << "Failed to create the vehicle factory: " - << FLAGS_load_vehicle_class_name; + AERROR << "Failed to create vehicle:"; + return false; + } + + message_manager_ = vehicle_object->CreateMessageManager(); + if (message_manager_ == nullptr) { + AERROR << "Failed to create message manager."; + return false; + } + AINFO << "Message manager is successfully created."; + + if (can_receiver_.Init(can_client_.get(), message_manager_.get(), + canbus_conf_.enable_receiver_log()) != ErrorCode::OK) { + AERROR << "Failed to init can receiver."; return false; } + AINFO << "The can receiver is successfully initialized."; - vehicle_object_ = vehicle_object; - if (vehicle_object_ == nullptr) { - AERROR << "Failed to create vehicle factory pointer."; + if (can_sender_.Init(can_client_.get(), canbus_conf_.enable_sender_log()) != + ErrorCode::OK) { + AERROR << "Failed to init can sender."; + return false; + } + AINFO << "The can sender is successfully initialized."; + + vehicle_controller_ = vehicle_object->CreateVehicleController(); + if (vehicle_controller_ == nullptr) { + AERROR << "Failed to create vehicle controller."; + return false; } - AINFO << "Successfully create vehicle factory: " - << FLAGS_load_vehicle_class_name; + AINFO << "The vehicle controller is successfully created."; - if (!vehicle_object_->Init(&canbus_conf_)) { - AERROR << "Fail to init vehicle factory."; + if (vehicle_controller_->Init(canbus_conf_.vehicle_parameter(), &can_sender_, + message_manager_.get()) != ErrorCode::OK) { + AERROR << "Failed to init vehicle controller."; return false; } - AINFO << "Vehicle factory is successfully initialized."; + + AINFO << "The vehicle controller is successfully" + << " initialized with canbus conf as : " + << canbus_conf_.vehicle_parameter().ShortDebugString(); cyber::ReaderConfig guardian_cmd_reader_config; guardian_cmd_reader_config.channel_name = FLAGS_guardian_topic; @@ -104,12 +132,34 @@ bool CanbusComponent::Init() { chassis_writer_ = node_->CreateWriter(FLAGS_chassis_topic); - if (!vehicle_object_->Start()) { - AERROR << "Fail to start canclient, cansender, canreceiver, canclient, " - "vehicle controller."; + chassis_detail_writer_ = + node_->CreateWriter(FLAGS_chassis_detail_topic); + + // 1. init and start the can card hardware + if (can_client_->Start() != ErrorCode::OK) { + AERROR << "Failed to start can client"; + return false; + } + AINFO << "Can client is started."; + + // 2. start receive first then send + if (can_receiver_.Start() != ErrorCode::OK) { + AERROR << "Failed to start can receiver."; + return false; + } + AINFO << "Can receiver is started."; + + // 3. start send + if (can_sender_.Start() != ErrorCode::OK) { + AERROR << "Failed to start can sender."; + return false; + } + + // 4. start controller + if (!vehicle_controller_->Start()) { + AERROR << "Failed to start vehicle controller."; + return false; } - AINFO << "Start canclient cansender, canreceiver, canclient, vehicle " - "controller successfully."; monitor_logger_buffer_.INFO("Canbus is started."); @@ -117,23 +167,32 @@ bool CanbusComponent::Init() { } void CanbusComponent::Clear() { - vehicle_object_->Stop(); + can_sender_.Stop(); + can_receiver_.Stop(); + can_client_->Stop(); + vehicle_controller_->Stop(); AINFO << "Cleanup Canbus component"; } void CanbusComponent::PublishChassis() { - Chassis chassis = vehicle_object_->publish_chassis(); + Chassis chassis = vehicle_controller_->chassis(); common::util::FillHeader(node_->Name(), &chassis); chassis_writer_->Write(chassis); ADEBUG << chassis.ShortDebugString(); } +void CanbusComponent::PublishChassisDetail() { + ChassisDetail chassis_detail; + message_manager_->GetSensorData(&chassis_detail); + ADEBUG << chassis_detail.ShortDebugString(); + chassis_detail_writer_->Write(chassis_detail); +} + bool CanbusComponent::Proc() { PublishChassis(); if (FLAGS_enable_chassis_detail_pub) { - vehicle_object_->PublishChassisDetail(); + PublishChassisDetail(); } - vehicle_object_->UpdateHeartbeat(); return true; } @@ -156,7 +215,12 @@ void CanbusComponent::OnControlCommand(const ControlCommand &control_command) { 1e6) << " micro seconds"; - vehicle_object_->UpdateCommand(&control_command); + if (vehicle_controller_->Update(control_command) != ErrorCode::OK) { + AERROR << "Failed to process callback function OnControlCommand because " + "vehicle_controller_->Update error."; + return; + } + can_sender_.Update(); } void CanbusComponent::OnGuardianCommand( diff --git a/modules/canbus/canbus_component.h b/modules/canbus/canbus_component.h index 5b7febad26b..2cb54ef11ee 100644 --- a/modules/canbus/canbus_component.h +++ b/modules/canbus/canbus_component.h @@ -25,17 +25,19 @@ #include #include -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" -#include "modules/common_msgs/guardian_msgs/guardian.pb.h" - #include "cyber/common/macros.h" #include "cyber/component/timer_component.h" #include "cyber/cyber.h" #include "cyber/timer/timer.h" -#include "modules/canbus/vehicle/abstract_vehicle_factory.h" + +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" +#include "modules/common_msgs/drivers_msgs/can_card_parameter.pb.h" +#include "modules/common_msgs/guardian_msgs/guardian.pb.h" + #include "modules/canbus/vehicle/vehicle_controller.h" #include "modules/common/monitor_log/monitor_log_buffer.h" #include "modules/common/status/status.h" +#include "modules/common_msgs/control_msgs/control_cmd.pb.h" #include "modules/drivers/canbus/can_client/can_client.h" #include "modules/drivers/canbus/can_comm/can_receiver.h" #include "modules/drivers/canbus/can_comm/can_sender.h" @@ -81,6 +83,7 @@ class CanbusComponent final : public apollo::cyber::TimerComponent { void Clear() override; void PublishChassis(); + void PublishChassisDetail(); void OnControlCommand(const apollo::control::ControlCommand &control_command); void OnGuardianCommand( const apollo::guardian::GuardianCommand &guardian_command); @@ -88,16 +91,19 @@ class CanbusComponent final : public apollo::cyber::TimerComponent { void RegisterCanClients(); CanbusConf canbus_conf_; - std::shared_ptr<::apollo::canbus::AbstractVehicleFactory> vehicle_object_ = - nullptr; std::shared_ptr> guardian_cmd_reader_; std::shared_ptr> control_command_reader_; - + std::unique_ptr can_client_; + CanSender can_sender_; + apollo::drivers::canbus::CanReceiver can_receiver_; + std::unique_ptr> message_manager_; + std::unique_ptr vehicle_controller_; int64_t last_timestamp_ = 0; ::apollo::common::monitor::MonitorLogBuffer monitor_logger_buffer_; std::shared_ptr> chassis_writer_; + std::shared_ptr> chassis_detail_writer_; }; CYBER_REGISTER_COMPONENT(CanbusComponent) diff --git a/modules/canbus/common/BUILD b/modules/canbus/common/BUILD index d4f35a5c032..8b10a3bd429 100644 --- a/modules/canbus/common/BUILD +++ b/modules/canbus/common/BUILD @@ -1,37 +1,13 @@ -load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library") +load("@rules_cc//cc:defs.bzl", "cc_library") load("//tools:cpplint.bzl", "cpplint") -load("//tools/install:install.bzl", "install") package(default_visibility = ["//visibility:public"]) -CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] - -install( - name = "install", - library_dest = "canbus/lib", - targets = [":libcanbus_gflags.so"], - visibility = ["//visibility:public"], -) - -cc_binary( - name = "libcanbus_gflags.so", - srcs = [ - "canbus_gflags.cc", - "canbus_gflags.h", - ], - linkshared = True, - linkstatic = True, - deps = [ - "@com_github_gflags_gflags//:gflags", - ], -) - cc_library( - name = "canbus_gflags", - srcs = ["libcanbus_gflags.so"], + name = "canbus_common", + srcs = ["canbus_gflags.cc"], hdrs = ["canbus_gflags.h"], - alwayslink = True, - copts = CANBUS_COPTS, + copts = ["-DMODULE_NAME=\\\"canbus\\\""], deps = [ "@com_github_gflags_gflags//:gflags", ], diff --git a/modules/canbus/common/canbus_gflags.cc b/modules/canbus/common/canbus_gflags.cc index d8e7fbac276..9cb79b512da 100644 --- a/modules/canbus/common/canbus_gflags.cc +++ b/modules/canbus/common/canbus_gflags.cc @@ -49,10 +49,3 @@ DEFINE_int32(control_cmd_pending_queue_size, 10, // enable forward Ultrasonic AEB DEFINE_bool(enable_aeb, true, "Enable forward Ultrasonic AEB"); - -// vehicle factory dynamic library path and class name -DEFINE_string(load_vehicle_library, - "/opt/apollo/neo/lib/canbus-dev/vehicle/libch_vehicle_factory.so", - "Default load vehicle library"); -DEFINE_string(load_vehicle_class_name, "ChVehicleFactory", - "Default vehicle factory name"); diff --git a/modules/canbus/common/canbus_gflags.h b/modules/canbus/common/canbus_gflags.h index 2dbf566c7bc..556e4701aa8 100644 --- a/modules/canbus/common/canbus_gflags.h +++ b/modules/canbus/common/canbus_gflags.h @@ -43,7 +43,3 @@ DECLARE_int32(control_cmd_pending_queue_size); // enable forward Ultrasonic AEB DECLARE_bool(enable_aeb); - -// vehicle factory dynamic library path and class name -DECLARE_string(load_vehicle_library); -DECLARE_string(load_vehicle_class_name); diff --git a/modules/canbus/conf/canbus.conf b/modules/canbus/conf/canbus.conf index c93ca3fb2ac..9b46fbe767d 100644 --- a/modules/canbus/conf/canbus.conf +++ b/modules/canbus/conf/canbus.conf @@ -1,6 +1,4 @@ --flagfile=/apollo/modules/common/data/global_flagfile.txt --canbus_conf_file=/apollo/modules/canbus/conf/canbus_conf.pb.txt ---load_vehicle_library=/opt/apollo/neo/packages/canbus-vehicle-lincoln-dev/latest/lib/liblincoln_vehicle_factory_lib.so ---load_vehicle_class_name=LincolnVehicleFactory --noenable_chassis_detail_pub --noreceive_guardian diff --git a/modules/canbus/cyberfile.xml b/modules/canbus/cyberfile.xml deleted file mode 100644 index b80fd3aab28..00000000000 --- a/modules/canbus/cyberfile.xml +++ /dev/null @@ -1,30 +0,0 @@ - - canbus - local - - Canbus accepts and executes control module commands and collects the car's chassis status as feedback to control. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/canbus - - cyber-dev - common-dev - 3rd-gflags-dev - 3rd-gtest-dev - common-msgs-dev - drivers-dev - - 3rd-rules-python-dev - 3rd-grpc-dev - 3rd-bazel-skylib-dev - 3rd-rules-proto-dev - 3rd-py-dev - - diff --git a/modules/canbus/proto/BUILD b/modules/canbus/proto/BUILD index 118554cc010..16ea8eba92b 100644 --- a/modules/canbus/proto/BUILD +++ b/modules/canbus/proto/BUILD @@ -1,68 +1,56 @@ ## 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/install:install.bzl", "install", "install_files", "install_src_files") load("//tools:python_rules.bzl", "py_proto_library") package(default_visibility = ["//visibility:public"]) cc_proto_library( - name = "canbus_conf_cc_proto", + name = "vehicle_parameter_cc_proto", deps = [ - ":canbus_conf_proto", + ":vehicle_parameter_proto", ], ) proto_library( - name = "canbus_conf_proto", - srcs = ["canbus_conf.proto"], + name = "vehicle_parameter_proto", + srcs = ["vehicle_parameter.proto"], deps = [ - "//modules/common_msgs/drivers_msgs:can_card_parameter_proto", - ":vehicle_parameter_proto", + "//modules/common_msgs/chassis_msgs:chassis_proto", + "//modules/common_msgs/config_msgs:vehicle_config_proto", ], ) py_proto_library( - name = "canbus_conf_py_pb2", + name = "vehicle_parameter_py_pb2", deps = [ - ":canbus_conf_proto", - "//modules/common_msgs/drivers_msgs:can_card_parameter_py_pb2", - ":vehicle_parameter_py_pb2", + "//modules/common_msgs/chassis_msgs:chassis_py_pb2", + ":vehicle_parameter_proto", + "//modules/common_msgs/config_msgs:vehicle_config_py_pb2", ], ) cc_proto_library( - name = "vehicle_parameter_cc_proto", + name = "canbus_conf_cc_proto", deps = [ - ":vehicle_parameter_proto", + ":canbus_conf_proto", ], ) proto_library( - name = "vehicle_parameter_proto", - srcs = ["vehicle_parameter.proto"], + name = "canbus_conf_proto", + srcs = ["canbus_conf.proto"], deps = [ - "//modules/common_msgs/chassis_msgs:chassis_proto", - "//modules/common_msgs/config_msgs:vehicle_config_proto", + ":vehicle_parameter_proto", + "//modules/common_msgs/drivers_msgs:can_card_parameter_proto", ], ) py_proto_library( - name = "vehicle_parameter_py_pb2", + name = "canbus_conf_py_pb2", deps = [ - ":vehicle_parameter_proto", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/config_msgs:vehicle_config_py_pb2", - ], -) - -install_files( - name = "py_pb_canbus", - dest = "canbus/python/modules/canbus/proto", - files = [ + ":canbus_conf_proto", ":vehicle_parameter_py_pb2", - ":canbus_conf_py_pb2" - ] + "//modules/common_msgs/drivers_msgs:can_card_parameter_py_pb2", + ], ) - - diff --git a/modules/canbus/testdata/conf/canbus_conf_test.pb.txt b/modules/canbus/testdata/conf/canbus_conf_test.pb.txt deleted file mode 100644 index 91e3b680813..00000000000 --- a/modules/canbus/testdata/conf/canbus_conf_test.pb.txt +++ /dev/null @@ -1,12 +0,0 @@ -vehicle_parameter { - max_enable_fail_attempt: 5 - driving_mode: COMPLETE_AUTO_DRIVE -} - -can_card_parameter { - brand:SOCKET_CAN_RAW - type: PCI_CARD - channel_id: CHANNEL_ID_ZERO -} - -enable_debug_mode: false \ No newline at end of file diff --git a/modules/canbus/testdata/conf/ch_canbus_conf_test.pb.txt b/modules/canbus/testdata/conf/ch_canbus_conf_test.pb.txt index 6fe29139476..1e390bd1d64 100644 --- a/modules/canbus/testdata/conf/ch_canbus_conf_test.pb.txt +++ b/modules/canbus/testdata/conf/ch_canbus_conf_test.pb.txt @@ -5,11 +5,9 @@ vehicle_parameter { } can_card_parameter { - brand: SOCKET_CAN_RAW + brand:ESD_CAN type: PCI_CARD channel_id: CHANNEL_ID_ZERO } -enable_debug_mode: true -enable_receiver_log: true -enable_sender_log: false +enable_debug_mode: false diff --git a/modules/canbus/testdata/conf/devkit_canbus_conf_test.pb.txt b/modules/canbus/testdata/conf/devkit_canbus_conf_test.pb.txt index c77056ce223..4d152222591 100755 --- a/modules/canbus/testdata/conf/devkit_canbus_conf_test.pb.txt +++ b/modules/canbus/testdata/conf/devkit_canbus_conf_test.pb.txt @@ -5,7 +5,7 @@ vehicle_parameter { } can_card_parameter { - brand:SOCKET_CAN_RAW + brand:ESD_CAN type: PCI_CARD channel_id: CHANNEL_ID_ZERO } diff --git a/modules/canbus/testdata/conf/ge3_canbus_conf_test.pb.txt b/modules/canbus/testdata/conf/ge3_canbus_conf_test.pb.txt index 8ee5076f130..a64268d2f26 100644 --- a/modules/canbus/testdata/conf/ge3_canbus_conf_test.pb.txt +++ b/modules/canbus/testdata/conf/ge3_canbus_conf_test.pb.txt @@ -5,7 +5,7 @@ vehicle_parameter { } can_card_parameter { - brand:SOCKET_CAN_RAW + brand:ESD_CAN type: PCI_CARD channel_id: CHANNEL_ID_ZERO } diff --git a/modules/canbus/testdata/conf/gem_canbus_conf_test.pb.txt b/modules/canbus/testdata/conf/gem_canbus_conf_test.pb.txt index 19227630e51..5144808ae6b 100644 --- a/modules/canbus/testdata/conf/gem_canbus_conf_test.pb.txt +++ b/modules/canbus/testdata/conf/gem_canbus_conf_test.pb.txt @@ -5,7 +5,7 @@ vehicle_parameter { } can_card_parameter { - brand:SOCKET_CAN_RAW + brand:ESD_CAN type: PCI_CARD channel_id: CHANNEL_ID_ZERO } diff --git a/modules/canbus/testdata/conf/lexus_canbus_conf_test.pb.txt b/modules/canbus/testdata/conf/lexus_canbus_conf_test.pb.txt index c103b83f42d..c8cc7e70c56 100644 --- a/modules/canbus/testdata/conf/lexus_canbus_conf_test.pb.txt +++ b/modules/canbus/testdata/conf/lexus_canbus_conf_test.pb.txt @@ -5,7 +5,7 @@ vehicle_parameter { } can_card_parameter { - brand:SOCKET_CAN_RAW + brand:ESD_CAN type: PCI_CARD channel_id: CHANNEL_ID_ZERO } diff --git a/modules/canbus/testdata/conf/mkz_canbus_conf_test.pb.txt b/modules/canbus/testdata/conf/mkz_canbus_conf_test.pb.txt index 1a4fbb05a86..7b13c4de260 100644 --- a/modules/canbus/testdata/conf/mkz_canbus_conf_test.pb.txt +++ b/modules/canbus/testdata/conf/mkz_canbus_conf_test.pb.txt @@ -5,7 +5,7 @@ vehicle_parameter { } can_card_parameter { - brand:SOCKET_CAN_RAW + brand:ESD_CAN type: PCI_CARD channel_id: CHANNEL_ID_ZERO } diff --git a/modules/canbus/testdata/conf/transit_canbus_conf_test.pb.txt b/modules/canbus/testdata/conf/transit_canbus_conf_test.pb.txt index e4e92780fac..84da5150ebf 100644 --- a/modules/canbus/testdata/conf/transit_canbus_conf_test.pb.txt +++ b/modules/canbus/testdata/conf/transit_canbus_conf_test.pb.txt @@ -5,7 +5,7 @@ vehicle_parameter { } can_card_parameter { - brand:SOCKET_CAN_RAW + brand:ESD_CAN type: PCI_CARD channel_id: CHANNEL_ID_ZERO } diff --git a/modules/canbus/testdata/conf/wey_canbus_conf_test.pb.txt b/modules/canbus/testdata/conf/wey_canbus_conf_test.pb.txt index 48f655360ae..9ebe4288ad0 100644 --- a/modules/canbus/testdata/conf/wey_canbus_conf_test.pb.txt +++ b/modules/canbus/testdata/conf/wey_canbus_conf_test.pb.txt @@ -5,7 +5,7 @@ vehicle_parameter { } can_card_parameter { - brand:SOCKET_CAN_RAW + brand:ESD_CAN type: PCI_CARD channel_id: CHANNEL_ID_ZERO } diff --git a/modules/canbus/testdata/conf/zhongyun_canbus_conf_test.pb.txt b/modules/canbus/testdata/conf/zhongyun_canbus_conf_test.pb.txt index 9f6ec582558..33b0dd9a6d9 100644 --- a/modules/canbus/testdata/conf/zhongyun_canbus_conf_test.pb.txt +++ b/modules/canbus/testdata/conf/zhongyun_canbus_conf_test.pb.txt @@ -5,7 +5,7 @@ vehicle_parameter { } can_card_parameter { - brand:SOCKET_CAN_RAW + brand:ESD_CAN type: PCI_CARD channel_id: CHANNEL_ID_ZERO } diff --git a/modules/canbus/tools/BUILD b/modules/canbus/tools/BUILD index c0bfe31da9c..4f3a96ce807 100644 --- a/modules/canbus/tools/BUILD +++ b/modules/canbus/tools/BUILD @@ -1,26 +1,15 @@ load("@rules_cc//cc:defs.bzl", "cc_binary") load("//tools:cpplint.bzl", "cpplint") -load("//tools/install:install.bzl", "install") package(default_visibility = ["//visibility:public"]) -install( - name = "install", - runtime_dest = "canbus/bin", - targets = [ - ":canbus_tester", - ":teleop", - ], - visibility = ["//visibility:public"], -) - cc_binary( name = "canbus_tester", srcs = ["canbus_tester.cc"], deps = [ "//cyber", - "//modules/canbus/common:canbus_gflags", - "//modules/common_msgs/control_msgs:control_cmd_cc_proto", + "//modules/canbus:canbus_component_lib", + "//modules/canbus/common:canbus_common", "//modules/common/adapters:adapter_gflags", "@com_github_gflags_gflags//:gflags", ], @@ -31,12 +20,14 @@ cc_binary( srcs = ["teleop.cc"], deps = [ "//cyber", + "//modules/canbus/common:canbus_common", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/canbus/vehicle:vehicle_controller_base", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/common_msgs/control_msgs:control_cmd_cc_proto", "//modules/common/adapters:adapter_gflags", "//modules/common/configs:vehicle_config_helper", - "//modules/common/util:util_tool", + "//modules/common/util:message_util", + "//modules/common_msgs/control_msgs:control_cmd_cc_proto", + "@com_github_gflags_gflags//:gflags", ], ) diff --git a/modules/canbus/tools/teleop.cc b/modules/canbus/tools/teleop.cc index 1b56d4f9a11..41262a1da53 100644 --- a/modules/canbus/tools/teleop.cc +++ b/modules/canbus/tools/teleop.cc @@ -26,12 +26,12 @@ #include "cyber/cyber.h" #include "cyber/init.h" #include "cyber/time/time.h" -#include "modules/canbus/vehicle/vehicle_controller.h" #include "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" +#include "modules/canbus/vehicle/vehicle_controller.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/common/configs/vehicle_config_helper.h" #include "modules/common/util/message_util.h" +#include "modules/common_msgs/control_msgs/control_cmd.pb.h" // gflags DEFINE_double(throttle_inc_delta, 2.0, @@ -55,9 +55,9 @@ using apollo::cyber::Reader; using apollo::cyber::Time; using apollo::cyber::Writer; -const uint32_t KEYCODE_O = 0x4F; // 'O' not number +const uint32_t KEYCODE_O = 0x4F; // '0' -const uint32_t KEYCODE_UP1 = 0x57; // 'W' +const uint32_t KEYCODE_UP1 = 0x57; // 'w' const uint32_t KEYCODE_UP2 = 0x77; // 'w' const uint32_t KEYCODE_DN1 = 0x53; // 'S' const uint32_t KEYCODE_DN2 = 0x73; // 's' @@ -66,9 +66,7 @@ const uint32_t KEYCODE_LF2 = 0x61; // 'a' const uint32_t KEYCODE_RT1 = 0x44; // 'D' const uint32_t KEYCODE_RT2 = 0x64; // 'd' -// set hand brake or parking brake -const uint32_t KEYCODE_PKBK1 = 0x50; // 'P' -const uint32_t KEYCODE_PKBK2 = 0x70; // 'p' +const uint32_t KEYCODE_PKBK = 0x50; // hand brake or parking brake // set throttle, gear, and brake const uint32_t KEYCODE_SETT1 = 0x54; // 'T' @@ -77,27 +75,20 @@ const uint32_t KEYCODE_SETG1 = 0x47; // 'G' const uint32_t KEYCODE_SETG2 = 0x67; // 'g' const uint32_t KEYCODE_SETB1 = 0x42; // 'B' const uint32_t KEYCODE_SETB2 = 0x62; // 'b' -const uint32_t KEYCODE_ZERO = 0x30; // '0' number +const uint32_t KEYCODE_ZERO = 0x30; // '0' -// set turn signal const uint32_t KEYCODE_SETQ1 = 0x51; // 'Q' const uint32_t KEYCODE_SETQ2 = 0x71; // 'q' -// set low beam -const uint32_t KEYCODE_SETL1 = 0x4C; // 'L' -const uint32_t KEYCODE_SETL2 = 0x6C; // 'l' - // change action -const uint32_t KEYCODE_MODE1 = 0x4D; // 'M' -const uint32_t KEYCODE_MODE2 = 0x6D; // 'm' +const uint32_t KEYCODE_MODE = 0x6D; // 'm' // emergency stop -const uint32_t KEYCODE_ESTOP1 = 0x45; // 'E' -const uint32_t KEYCODE_ESTOP2 = 0x65; // 'e' +const uint32_t KEYCODE_ESTOP = 0x45; // 'E' // help -const uint32_t KEYCODE_HELP1 = 0x48; // 'H' -const uint32_t KEYCODE_HELP2 = 0x68; // 'h' +const uint32_t KEYCODE_HELP = 0x68; // 'h' +const uint32_t KEYCODE_HELP2 = 0x48; // 'H' class Teleop { public: @@ -108,11 +99,10 @@ class Teleop { static void PrintKeycode() { system("clear"); printf("===================== KEYBOARD MAP ===================\n"); - printf("HELP: [%c] |\n", KEYCODE_HELP2); - printf("Set Action: [%c]+Num\n", KEYCODE_MODE2); + printf("HELP: [%c] |\n", KEYCODE_HELP); + printf("Set Action : [%c]+Num\n", KEYCODE_MODE); printf(" 0 RESET ACTION\n"); printf(" 1 START ACTION\n"); - printf(" 2 VIN_REQ ACTION\n"); printf("\n-----------------------------------------------------------\n"); printf("Set Gear: [%c]+Num\n", KEYCODE_SETG1); printf(" 0 GEAR_NEUTRAL\n"); @@ -123,16 +113,14 @@ class Teleop { printf(" 5 GEAR_INVALID\n"); printf(" 6 GEAR_NONE\n"); printf("\n-----------------------------------------------------------\n"); - printf("Throttle/Speed up: [%c] | \n", - KEYCODE_UP1); - printf("Brake/Speed down: [%c] | \n", - KEYCODE_DN1); + printf("Throttle/Speed up: [%c] | Set Throttle: [%c]+Num\n", + KEYCODE_UP1, KEYCODE_SETT1); + printf("Brake/Speed down: [%c] | Set Brake: [%c]+Num\n", + KEYCODE_DN1, KEYCODE_SETB1); printf("Steer LEFT: [%c] | Steer RIGHT: [%c]\n", KEYCODE_LF1, KEYCODE_RT1); - printf("Parking Brake: [%c] | Emergency Stop [%c]\n", - KEYCODE_PKBK1, KEYCODE_ESTOP1); - printf("Left/Right Lamp: [%c] | Low beam [%c]\n", - KEYCODE_SETQ1, KEYCODE_SETL1); + printf("Parking Brake: [%c] | Emergency Stop [%c]\n", + KEYCODE_PKBK, KEYCODE_ESTOP); printf("\n-----------------------------------------------------------\n"); printf("Exit: Ctrl + C, then press enter to normal terminal\n"); printf("===========================================================\n"); @@ -150,7 +138,6 @@ class Teleop { struct termios raw_; int32_t kfd_ = 0; bool parking_brake = false; - bool low_beam = false; Chassis::GearPosition gear = Chassis::GEAR_INVALID; PadMessage pad_msg; ControlCommand &control_command_ = control_command(); @@ -239,44 +226,42 @@ class Teleop { AINFO << "Acceleration = " << control_command_.acceleration(); } break; - case KEYCODE_LF1: // steer left + case KEYCODE_LF1: // left case KEYCODE_LF2: steering = control_command_.steering_target(); steering = GetCommand(steering, FLAGS_steer_inc_delta); control_command_.set_steering_target(steering); AINFO << "Steering Target = " << steering; break; - case KEYCODE_RT1: // steer right + case KEYCODE_RT1: // right case KEYCODE_RT2: steering = control_command_.steering_target(); steering = GetCommand(steering, -FLAGS_steer_inc_delta); control_command_.set_steering_target(steering); AINFO << "Steering Target = " << steering; break; - case KEYCODE_PKBK1: // hand brake - case KEYCODE_PKBK2: + case KEYCODE_PKBK: // hand brake parking_brake = !control_command_.parking_brake(); control_command_.set_parking_brake(parking_brake); AINFO << "Parking Brake Toggled: " << parking_brake; break; - case KEYCODE_ESTOP1: - case KEYCODE_ESTOP2: + case KEYCODE_ESTOP: control_command_.set_brake(50.0); AINFO << "Estop Brake : " << control_command_.brake(); break; - case KEYCODE_SETT1: // set throttle 0-50 + case KEYCODE_SETT1: // set throttle case KEYCODE_SETT2: // read keyboard again if (read(kfd_, &c, 1) < 0) { exit(-1); } level = c - KEYCODE_ZERO; - control_command_.set_throttle(level * 5.0); + control_command_.set_throttle(level * 10.0); control_command_.set_brake(0.0); AINFO << "Throttle = " << control_command_.throttle() << ", Brake = " << control_command_.brake(); break; - case KEYCODE_SETG1: // set gear + case KEYCODE_SETG1: case KEYCODE_SETG2: // read keyboard again if (read(kfd_, &c, 1) < 0) { @@ -287,7 +272,7 @@ class Teleop { control_command_.set_gear_location(gear); AINFO << "Gear set to : " << level; break; - case KEYCODE_SETB1: // set brake 0-50 + case KEYCODE_SETB1: case KEYCODE_SETB2: // read keyboard again if (read(kfd_, &c, 1) < 0) { @@ -295,43 +280,34 @@ class Teleop { } level = c - KEYCODE_ZERO; control_command_.set_throttle(0.0); - control_command_.set_brake(level * 5.0); + control_command_.set_brake(level * 10.0); AINFO << "Throttle = " << control_command_.throttle() << ", Brake = " << control_command_.brake(); break; - case KEYCODE_SETQ1: // set turn signal + case KEYCODE_SETQ1: case KEYCODE_SETQ2: + if (read(kfd_, &c, 1) < 0) { + exit(-1); + } static int cnt = 0; ++cnt; - if (cnt > 3) { + if (cnt > 2) { cnt = 0; } + if (cnt == 0) { control_command_.mutable_signal()->set_turn_signal( VehicleSignal::TURN_NONE); - AINFO << "Set Lamp OFF"; } else if (cnt == 1) { control_command_.mutable_signal()->set_turn_signal( VehicleSignal::TURN_LEFT); - AINFO << "Set Turn Left"; } else if (cnt == 2) { control_command_.mutable_signal()->set_turn_signal( VehicleSignal::TURN_RIGHT); - AINFO << "Set Turn Right"; - } else if (cnt == 3) { - control_command_.mutable_signal()->set_turn_signal( - VehicleSignal::TURN_HAZARD_WARNING); - AINFO << "Set Turn Hazard Warning Lamp ON"; } + break; - case KEYCODE_SETL1: // set low beam - case KEYCODE_SETL2: - low_beam = !control_command_.signal().low_beam(); - control_command_.mutable_signal()->set_low_beam(low_beam); - AINFO << "Low Beam Toggled: " << low_beam; - break; - case KEYCODE_MODE1: // set action - case KEYCODE_MODE2: + case KEYCODE_MODE: // read keyboard again if (read(kfd_, &c, 1) < 0) { exit(-1); @@ -342,7 +318,7 @@ class Teleop { sleep(1); control_command_.clear_pad_msg(); break; - case KEYCODE_HELP1: // set help + case KEYCODE_HELP: case KEYCODE_HELP2: PrintKeycode(); break; @@ -393,10 +369,6 @@ class Teleop { action = apollo::control::DrivingAction::START; AINFO << "SET Action START"; break; - case 2: - action = apollo::control::DrivingAction::VIN_REQ; - AINFO << "SET Action VIN_REQ"; - break; default: AINFO << "unknown action: " << int_action << " use default RESET"; break; @@ -434,7 +406,6 @@ class Teleop { control_command_.set_engine_on_off(false); control_command_.set_driving_mode(Chassis::COMPLETE_MANUAL); control_command_.set_gear_location(Chassis::GEAR_INVALID); - control_command_.mutable_signal()->set_low_beam(false); control_command_.mutable_signal()->set_turn_signal( VehicleSignal::TURN_NONE); } diff --git a/modules/canbus/vehicle/BUILD b/modules/canbus/vehicle/BUILD index 21414f7a8da..5d82e1acf91 100644 --- a/modules/canbus/vehicle/BUILD +++ b/modules/canbus/vehicle/BUILD @@ -7,16 +7,20 @@ CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] cc_library( name = "vehicle_controller_base", + srcs = ["vehicle_controller.cc"], hdrs = ["vehicle_controller.h"], copts = CANBUS_COPTS, deps = [ "//modules/canbus/proto:canbus_conf_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/canbus/proto:vehicle_parameter_cc_proto", "//modules/common/configs:vehicle_config_helper", "//modules/common_msgs/basic_msgs:error_code_cc_proto", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", "//modules/common_msgs/control_msgs:control_cmd_cc_proto", - "//modules/drivers/canbus:sensor_canbus_lib", + "//modules/drivers/canbus/can_client", + "//modules/drivers/canbus/can_comm:can_sender", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", ], ) @@ -26,11 +30,42 @@ cc_library( hdrs = ["abstract_vehicle_factory.h"], copts = CANBUS_COPTS, deps = [ - "//cyber", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/canbus/vehicle:vehicle_controller_base", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], ) +cc_library( + name = "vehicle_factory", + srcs = ["vehicle_factory.cc"], + hdrs = ["vehicle_factory.h"], + copts = CANBUS_COPTS, + deps = [ + ":abstract_vehicle_factory", + "//modules/canbus/vehicle/ch:ch_vehicle_factory", + "//modules/canbus/vehicle/devkit:devkit_vehicle_factory", + "//modules/canbus/vehicle/ge3:ge3_vehicle_factory", + "//modules/canbus/vehicle/gem:gem_vehicle_factory", + "//modules/canbus/vehicle/lexus:lexus_vehicle_factory", + "//modules/canbus/vehicle/lincoln:lincoln_vehicle_factory", + "//modules/canbus/vehicle/neolix_edu:neolix_edu_vehicle_factory", + "//modules/canbus/vehicle/transit:transit_vehicle_factory", + "//modules/canbus/vehicle/wey:wey_vehicle_factory", + "//modules/canbus/vehicle/zhongyun:zhongyun_vehicle_factory", + "//modules/common/util:factory", + ], +) + +cc_test( + name = "vehicle_factory_test", + size = "small", + srcs = ["vehicle_factory_test.cc"], + deps = [ + ":vehicle_factory", + "@com_google_googletest//:gtest_main", + ], +) + cpplint() diff --git a/modules/canbus/vehicle/abstract_vehicle_factory.cc b/modules/canbus/vehicle/abstract_vehicle_factory.cc index 24b26cb68aa..5c3c1a0c19c 100644 --- a/modules/canbus/vehicle/abstract_vehicle_factory.cc +++ b/modules/canbus/vehicle/abstract_vehicle_factory.cc @@ -19,8 +19,6 @@ namespace apollo { namespace canbus { -void AbstractVehicleFactory::UpdateHeartbeat() {} - void AbstractVehicleFactory::SetVehicleParameter( const VehicleParameter &vehicle_parameter) { vehicle_parameter_ = vehicle_parameter; diff --git a/modules/canbus/vehicle/abstract_vehicle_factory.h b/modules/canbus/vehicle/abstract_vehicle_factory.h index afc607335aa..7885f5e7383 100644 --- a/modules/canbus/vehicle/abstract_vehicle_factory.h +++ b/modules/canbus/vehicle/abstract_vehicle_factory.h @@ -22,15 +22,11 @@ #include +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -#include "cyber/class_loader/class_loader_register_macro.h" #include "modules/canbus/vehicle/vehicle_controller.h" #include "modules/drivers/canbus/can_comm/message_manager.h" -using apollo::control::ControlCommand; - /** * @namespace apollo::canbus * @brief apollo::canbus @@ -53,53 +49,27 @@ class AbstractVehicleFactory { virtual ~AbstractVehicleFactory() = default; /** - * @brief set VehicleParameter. - */ - void SetVehicleParameter(const VehicleParameter &vehicle_paramter); - - /** - * @brief init vehicle factory - * @returns true if successfully initialized - */ - virtual bool Init(const CanbusConf *canbus_conf) = 0; - - /** - * @brief start canclient, cansender, canreceiver, vehicle controller - * @returns true if successfully started - */ - virtual bool Start() = 0; - - /** - * @brief stop canclient, cansender, canreceiver, vehicle controller - */ - virtual void Stop() = 0; - - /** - * @brief update control command + * @brief the interface of creating a VehicleController class + * @returns a unique pointer that points to the created VehicleController + * object. */ - virtual void UpdateCommand(const ControlCommand *control_command) = 0; + virtual std::unique_ptr CreateVehicleController() = 0; /** - * @brief publish chassis messages + * @brief the interface of creating a MessageManager class + * @returns a unique pointer that points to the created MessageManager object. */ - virtual Chassis publish_chassis() = 0; + virtual std::unique_ptr> + CreateMessageManager() = 0; /** - * @brief publish chassis for vehicle messages - */ - virtual void PublishChassisDetail() = 0; - - /** - * @brief create cansender heartbeat + * @brief set VehicleParameter. */ - virtual void UpdateHeartbeat(); + void SetVehicleParameter(const VehicleParameter &vehicle_paramter); private: VehicleParameter vehicle_parameter_; }; -#define CYBER_REGISTER_VEHICLEFACTORY(name) \ - CLASS_LOADER_REGISTER_CLASS(name, AbstractVehicleFactory) - } // namespace canbus } // namespace apollo diff --git a/modules/canbus/vehicle/ch/BUILD b/modules/canbus/vehicle/ch/BUILD new file mode 100644 index 00000000000..424c095d31a --- /dev/null +++ b/modules/canbus/vehicle/ch/BUILD @@ -0,0 +1,76 @@ +load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") +load("//tools:cpplint.bzl", "cpplint") + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "ch_vehicle_factory", + srcs = ["ch_vehicle_factory.cc"], + hdrs = ["ch_vehicle_factory.h"], + deps = [ + ":ch_controller", + ":ch_message_manager", + "//modules/canbus/vehicle:abstract_vehicle_factory", + ], +) + +cc_library( + name = "ch_message_manager", + srcs = ["ch_message_manager.cc"], + hdrs = ["ch_message_manager.h"], + deps = [ + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_library( + name = "ch_controller", + srcs = ["ch_controller.cc"], + hdrs = ["ch_controller.h"], + deps = [ + ":ch_message_manager", + "//modules/canbus/proto:canbus_conf_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_cc_proto", + "//modules/canbus/proto:vehicle_parameter_cc_proto", + "//modules/canbus/vehicle:vehicle_controller_base", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", + "//modules/common_msgs/basic_msgs:error_code_cc_proto", + "//modules/common_msgs/control_msgs:control_cmd_cc_proto", + ], +) + +cc_test( + name = "ch_controller_test", + size = "small", + srcs = ["ch_controller_test.cc"], + data = ["//modules/canbus:test_data"], + deps = [ + ":ch_controller", + "@com_google_googletest//:gtest_main", + ], +) + +cc_test( + name = "ch_message_manager_test", + size = "small", + srcs = ["ch_message_manager_test.cc"], + deps = [ + "//modules/canbus/vehicle/ch:ch_message_manager", + "@com_google_googletest//:gtest_main", + ], +) + +cc_test( + name = "ch_vehicle_factory_test", + size = "small", + srcs = ["ch_vehicle_factory_test.cc"], + deps = [ + ":ch_vehicle_factory", + "@com_google_googletest//:gtest_main", + ], +) + +cpplint() diff --git a/modules/canbus_vehicle/ch/ch_controller.cc b/modules/canbus/vehicle/ch/ch_controller.cc similarity index 65% rename from modules/canbus_vehicle/ch/ch_controller.cc rename to modules/canbus/vehicle/ch/ch_controller.cc index fbff96bca12..d62dfbbfc3d 100644 --- a/modules/canbus_vehicle/ch/ch_controller.cc +++ b/modules/canbus/vehicle/ch/ch_controller.cc @@ -14,15 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/ch_controller.h" - -#include +#include "modules/canbus/vehicle/ch/ch_controller.h" #include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "cyber/common/log.h" #include "cyber/time/time.h" -#include "modules/canbus_vehicle/ch/ch_message_manager.h" +#include "modules/canbus/vehicle/ch/ch_message_manager.h" #include "modules/canbus/vehicle/vehicle_controller.h" #include "modules/drivers/canbus/can_comm/can_sender.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" @@ -43,8 +41,8 @@ const int32_t CHECK_RESPONSE_SPEED_UNIT_FLAG = 2; ErrorCode ChController::Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Ch>* const can_sender, - MessageManager<::apollo::canbus::Ch>* const message_manager) { + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) { if (is_initialized_) { AINFO << "ChController has already been initiated."; return ErrorCode::CANBUS_ERROR; @@ -106,21 +104,12 @@ ErrorCode ChController::Init( return ErrorCode::CANBUS_ERROR; } - vehicle_mode_command_116_ = dynamic_cast( - message_manager_->GetMutableProtocolDataById(Vehiclemodecommand116::ID)); - if (vehicle_mode_command_116_ == nullptr) { - AERROR << "Vehiclemodecommand116 does not exist in the ChMessageManager!"; - return ErrorCode::CANBUS_ERROR; - } - can_sender_->AddMessage(Brakecommand111::ID, brake_command_111_, false); can_sender_->AddMessage(Gearcommand114::ID, gear_command_114_, false); can_sender_->AddMessage(Steercommand112::ID, steer_command_112_, false); can_sender_->AddMessage(Throttlecommand110::ID, throttle_command_110_, false); can_sender_->AddMessage(Turnsignalcommand113::ID, turnsignal_command_113_, false); - can_sender_->AddMessage(Vehiclemodecommand116::ID, vehicle_mode_command_116_, - false); // need sleep to ensure all messages received AINFO << "ChController is initialized."; @@ -158,66 +147,69 @@ void ChController::Stop() { Chassis ChController::chassis() { chassis_.Clear(); - Ch chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); // 21, 22, previously 1, 2 - // if (driving_mode() == Chassis::EMERGENCY_MODE) { - // set_chassis_error_code(Chassis::NO_ERROR); - // } + if (driving_mode() == Chassis::EMERGENCY_MODE) { + set_chassis_error_code(Chassis::NO_ERROR); + } chassis_.set_driving_mode(driving_mode()); chassis_.set_error_code(chassis_error_code()); + // 3 chassis_.set_engine_started(true); // 4 engine rpm ch has no engine rpm // chassis_.set_engine_rpm(0); // 5 ch has no wheel spd. - if (chassis_detail.has_ecu_status_1_515() && - chassis_detail.ecu_status_1_515().has_speed()) { + if (chassis_detail.ch().has_ecu_status_1_515() && + chassis_detail.ch().ecu_status_1_515().has_speed()) { chassis_.set_speed_mps( - static_cast(chassis_detail.ecu_status_1_515().speed())); + static_cast(chassis_detail.ch().ecu_status_1_515().speed())); } else { chassis_.set_speed_mps(0); } + // 6 ch has no odometer // chassis_.set_odometer_m(0); // 7 ch has no fuel. do not set; // chassis_.set_fuel_range_m(0); // 8 throttle - if (chassis_detail.has_throttle_status__510() && - chassis_detail.throttle_status__510().has_throttle_pedal_sts()) { + if (chassis_detail.ch().has_throttle_status__510() && + chassis_detail.ch().throttle_status__510().has_throttle_pedal_sts()) { chassis_.set_throttle_percentage(static_cast( - chassis_detail.throttle_status__510().throttle_pedal_sts())); + chassis_detail.ch().throttle_status__510().throttle_pedal_sts())); } else { chassis_.set_throttle_percentage(0); } // 9 brake - if (chassis_detail.has_brake_status__511() && - chassis_detail.brake_status__511().has_brake_pedal_sts()) { + if (chassis_detail.ch().has_brake_status__511() && + chassis_detail.ch().brake_status__511().has_brake_pedal_sts()) { chassis_.set_brake_percentage(static_cast( - chassis_detail.brake_status__511().brake_pedal_sts())); + chassis_detail.ch().brake_status__511().brake_pedal_sts())); } else { chassis_.set_brake_percentage(0); } - // 10 gear - if (chassis_detail.has_gear_status_514() && - chassis_detail.gear_status_514().has_gear_sts()) { + + // 23, previously 10 gear + if (chassis_detail.ch().has_gear_status_514() && + chassis_detail.ch().gear_status_514().has_gear_sts()) { Chassis::GearPosition gear_pos = Chassis::GEAR_INVALID; - if (chassis_detail.gear_status_514().gear_sts() == + if (chassis_detail.ch().gear_status_514().gear_sts() == Gear_status_514::GEAR_STS_NEUTRAL) { gear_pos = Chassis::GEAR_NEUTRAL; } - if (chassis_detail.gear_status_514().gear_sts() == + if (chassis_detail.ch().gear_status_514().gear_sts() == Gear_status_514::GEAR_STS_REVERSE) { gear_pos = Chassis::GEAR_REVERSE; } - if (chassis_detail.gear_status_514().gear_sts() == + if (chassis_detail.ch().gear_status_514().gear_sts() == Gear_status_514::GEAR_STS_DRIVE) { gear_pos = Chassis::GEAR_DRIVE; } - if (chassis_detail.gear_status_514().gear_sts() == + if (chassis_detail.ch().gear_status_514().gear_sts() == Gear_status_514::GEAR_STS_PARK) { gear_pos = Chassis::GEAR_PARKING; } @@ -227,106 +219,40 @@ Chassis ChController::chassis() { chassis_.set_gear_location(Chassis::GEAR_NONE); } // 11 steering - if (chassis_detail.has_steer_status__512() && - chassis_detail.steer_status__512().has_steer_angle_sts()) { + if (chassis_detail.ch().has_steer_status__512() && + chassis_detail.ch().steer_status__512().has_steer_angle_sts()) { chassis_.set_steering_percentage(static_cast( - chassis_detail.steer_status__512().steer_angle_sts() * 100.0 / + chassis_detail.ch().steer_status__512().steer_angle_sts() * 100.0 / vehicle_params_.max_steer_angle())); } else { chassis_.set_steering_percentage(0); } - // 12 battery soc - if (chassis_detail.has_ecu_status_2_516() && - chassis_detail.ecu_status_2_516().has_battery_soc()) { - chassis_.set_battery_soc_percentage( - chassis_detail.ecu_status_2_516().battery_soc()); + + // 26 + if (chassis_error_mask_) { + chassis_.set_chassis_error_mask(chassis_error_mask_); } - // 13 - // 14 give engage_advice based on error_code and battery low soc warn - if (!chassis_error_mask_ && chassis_.battery_soc_percentage() > 15.0) { + + if (chassis_detail.has_surround()) { + chassis_.mutable_surround()->CopyFrom(chassis_detail.surround()); + } + + // give engage_advice based on error_code and canbus feedback + if (!chassis_error_mask_ && (chassis_.throttle_percentage() == 0.0)) { chassis_.mutable_engage_advice()->set_advice( apollo::common::EngageAdvice::READY_TO_ENGAGE); } else { chassis_.mutable_engage_advice()->set_advice( apollo::common::EngageAdvice::DISALLOW_ENGAGE); - if (chassis_.battery_soc_percentage() > 0) { - chassis_.mutable_engage_advice()->set_reason( - "Battery soc percentage is lower than 15%, please charge it " - "quickly!"); - } + chassis_.mutable_engage_advice()->set_reason( + "CANBUS not ready, throttle percentage is not zero!"); } - // 15 set vin - // vin set 17 bits, like LSBN1234567890123 is prased as - // vin17(L),vin16(S),vin15(B),.....,vin03(1)vin02(2),vin01(3) - std::string vin = ""; - if (chassis_detail.has_vin_resp1_51b()) { - Vin_resp1_51b vin_51b = chassis_detail.vin_resp1_51b(); - vin += vin_51b.vin01(); - vin += vin_51b.vin02(); - vin += vin_51b.vin03(); - vin += vin_51b.vin04(); - vin += vin_51b.vin05(); - vin += vin_51b.vin06(); - vin += vin_51b.vin07(); - vin += vin_51b.vin08(); - } - if (chassis_detail.has_vin_resp2_51c()) { - Vin_resp2_51c vin_51c = chassis_detail.vin_resp2_51c(); - vin += vin_51c.vin09(); - vin += vin_51c.vin10(); - vin += vin_51c.vin11(); - vin += vin_51c.vin12(); - vin += vin_51c.vin13(); - vin += vin_51c.vin14(); - vin += vin_51c.vin15(); - vin += vin_51c.vin16(); - } - if (chassis_detail.has_vin_resp3_51d()) { - Vin_resp3_51d vin_51d = chassis_detail.vin_resp3_51d(); - vin += vin_51d.vin17(); - } - std::reverse(vin.begin(), vin.end()); - chassis_.mutable_vehicle_id()->set_vin(vin); - - // 16 front bumper event - if (chassis_detail.has_brake_status__511() && - chassis_detail.brake_status__511().has_front_bump_env()) { - if (chassis_detail.brake_status__511().front_bump_env() == - Brake_status__511::FRONT_BUMP_ENV_FRONT_BUMPER_ENV) { - chassis_.set_front_bumper_event(Chassis::BUMPER_PRESSED); - } else { - chassis_.set_front_bumper_event(Chassis::BUMPER_NORMAL); - } - } else { - chassis_.set_front_bumper_event(Chassis::BUMPER_INVALID); - } - // 17 back bumper event - if (chassis_detail.has_brake_status__511() && - chassis_detail.brake_status__511().has_back_bump_env()) { - if (chassis_detail.brake_status__511().back_bump_env() == - Brake_status__511::BACK_BUMP_ENV_BACK_BUMPER_ENV) { - chassis_.set_back_bumper_event(Chassis::BUMPER_PRESSED); - } else { - chassis_.set_back_bumper_event(Chassis::BUMPER_NORMAL); - } - } else { - chassis_.set_back_bumper_event(Chassis::BUMPER_INVALID); - } - // 18 add checkresponse signal - if (chassis_detail.has_brake_status__511() && - chassis_detail.brake_status__511().has_brake_pedal_en_sts()) { - chassis_.mutable_check_response()->set_is_esp_online( - chassis_detail.brake_status__511().brake_pedal_en_sts() == 1); - } - if (chassis_detail.has_steer_status__512() && - chassis_detail.steer_status__512().has_steer_angle_en_sts()) { - chassis_.mutable_check_response()->set_is_eps_online( - chassis_detail.steer_status__512().steer_angle_en_sts() == 1); - } - if (chassis_detail.has_throttle_status__510() && - chassis_detail.throttle_status__510().has_throttle_pedal_en_sts()) { - chassis_.mutable_check_response()->set_is_vcu_online( - chassis_detail.throttle_status__510().throttle_pedal_en_sts() == 1); + + // 27 battery soc + if (chassis_detail.ch().has_ecu_status_2_516() && + chassis_detail.ch().ecu_status_2_516().has_battery_soc()) { + chassis_.set_battery_soc_percentage( + chassis_detail.ch().ecu_status_2_516().battery_soc()); } return chassis_; @@ -349,14 +275,12 @@ ErrorCode ChController::EnableAutoMode() { Throttle_command_110::THROTTLE_PEDAL_EN_CTRL_ENABLE); steer_command_112_->set_steer_angle_en_ctrl( Steer_command_112::STEER_ANGLE_EN_CTRL_ENABLE); - AINFO << "set enable"; - + AINFO << "\n\n\n set enable \n\n\n"; can_sender_->Update(); const int32_t flag = CHECK_RESPONSE_STEER_UNIT_FLAG | CHECK_RESPONSE_SPEED_UNIT_FLAG; if (!CheckResponse(flag, true)) { - AERROR << "Failed to switch to COMPLETE_AUTO_DRIVE mode. Please check the " - "emergency button or chassis."; + AERROR << "Failed to switch to COMPLETE_AUTO_DRIVE mode."; Emergency(); set_chassis_error_code(Chassis::CHASSIS_ERROR); return ErrorCode::CANBUS_ERROR; @@ -413,7 +337,7 @@ void ChController::Gear(Chassis::GearPosition gear_position) { break; } case Chassis::GEAR_INVALID: { - // AERROR << "Gear command is invalid!"; + AERROR << "Gear command is invalid!"; gear_command_114_->set_gear_cmd(Gear_command_114::GEAR_CMD_NEUTRAL); break; } @@ -442,8 +366,8 @@ void ChController::Brake(double pedal) { // drive with old acceleration // gas:0.00~99.99 unit: void ChController::Throttle(double pedal) { - if (!(driving_mode() == Chassis::COMPLETE_AUTO_DRIVE || - driving_mode() == Chassis::AUTO_SPEED_ONLY)) { + if (driving_mode() != Chassis::COMPLETE_AUTO_DRIVE && + driving_mode() != Chassis::AUTO_SPEED_ONLY) { AINFO << "The current drive mode does not need to set acceleration."; return; } @@ -453,10 +377,10 @@ void ChController::Throttle(double pedal) { void ChController::Acceleration(double acc) {} -// ch default, 23 ~ -23, left:+, right:- +// ch default, -23 ~ 23, left:+, right:- // need to be compatible with control module, so reverse // steering with old angle speed -// angle:99.99~0.00~-99.99, unit:, left:+, right:- +// angle:-99.99~0.00~99.99, unit:, left:-, right:+ void ChController::Steer(double angle) { if (!(driving_mode() == Chassis::COMPLETE_AUTO_DRIVE || driving_mode() == Chassis::AUTO_STEER_ONLY)) { @@ -485,113 +409,49 @@ void ChController::Steer(double angle, double angle_spd) { void ChController::SetEpbBreak(const ControlCommand& command) {} -void ChController::SetBeam(const ControlCommand& command) { - // Set low beam - if (command.signal().low_beam()) { - turnsignal_command_113_->set_low_beam_cmd( - Turnsignal_command_113::LOW_BEAM_CMD_ON); - } else { - turnsignal_command_113_->set_low_beam_cmd( - Turnsignal_command_113::LOW_BEAM_CMD_OFF); - } -} +void ChController::SetBeam(const ControlCommand& command) {} void ChController::SetHorn(const ControlCommand& command) {} -void ChController::SetTurningSignal(const ControlCommand& command) { - // Set Turn Signal - auto signal = command.signal().turn_signal(); - if (signal == common::VehicleSignal::TURN_LEFT) { - turnsignal_command_113_->set_turn_signal_cmd( - Turnsignal_command_113::TURN_SIGNAL_CMD_LEFT); - } else if (signal == common::VehicleSignal::TURN_RIGHT) { - turnsignal_command_113_->set_turn_signal_cmd( - Turnsignal_command_113::TURN_SIGNAL_CMD_RIGHT); - } else if (signal == common::VehicleSignal::TURN_HAZARD_WARNING) { - turnsignal_command_113_->set_turn_signal_cmd( - Turnsignal_command_113::TURN_SIGNAL_CMD_HAZARD_WARNING_LAMPSTS); - } else { - turnsignal_command_113_->set_turn_signal_cmd( - Turnsignal_command_113::TURN_SIGNAL_CMD_NONE); - } -} - -bool ChController::VerifyID() { - if (!CheckVin()) { - AERROR << "Failed to get the vin. Get vin again."; - GetVin(); - return false; - } else { - ResetVin(); - return true; - } -} - -bool ChController::CheckVin() { - if (chassis_.vehicle_id().vin().size() >= 7) { - AINFO << "Vin check success! Vehicel vin is " - << chassis_.vehicle_id().vin(); - return true; - } else { - AINFO << "Vin check failed! Current vin size is " - << chassis_.vehicle_id().vin().size(); - return false; - } -} - -void ChController::GetVin() { - vehicle_mode_command_116_->set_vin_req_cmd( - Vehicle_mode_command_116::VIN_REQ_CMD_VIN_REQ_ENABLE); - AINFO << "Get vin"; - can_sender_->Update(); -} - -void ChController::ResetVin() { - vehicle_mode_command_116_->set_vin_req_cmd( - Vehicle_mode_command_116::VIN_REQ_CMD_VIN_REQ_DISABLE); - AINFO << "Reset vin"; - can_sender_->Update(); -} +void ChController::SetTurningSignal(const ControlCommand& command) {} void ChController::ResetProtocol() { message_manager_->ResetSendMessages(); } bool ChController::CheckChassisError() { - Ch chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); - if (!chassis_detail.has_check_response()) { + if (!chassis_detail.has_ch()) { AERROR_EVERY(100) << "ChassisDetail has NO ch vehicle info." << chassis_detail.DebugString(); return false; } + Ch ch = chassis_detail.ch(); // steer motor fault - if (chassis_detail.has_steer_status__512()) { + if (ch.has_steer_status__512()) { if (Steer_status__512::STEER_ERR_STEER_MOTOR_ERR == - chassis_detail.steer_status__512().steer_err()) { + ch.steer_status__512().steer_err()) { + return true; + } + if (Steer_status__512::SENSOR_ERR_STEER_SENSOR_ERR == + ch.steer_status__512().sensor_err()) { return true; } - // cancel the sensor err check because of discarding the steer sensor - // if (Steer_status__512::SENSOR_ERR_STEER_SENSOR_ERR == - // ch.steer_status__512().sensor_err()) { - // return false; - // } } // drive error - if (chassis_detail.has_throttle_status__510()) { + if (ch.has_throttle_status__510()) { if (Throttle_status__510::DRIVE_MOTOR_ERR_DRV_MOTOR_ERR == - chassis_detail.throttle_status__510().drive_motor_err()) { + ch.throttle_status__510().drive_motor_err()) { + return true; + } + if (Throttle_status__510::BATTERY_BMS_ERR_BATTERY_ERR == + ch.throttle_status__510().battery_bms_err()) { return true; } - // cancel the battery err check bacause of always causing this error block - // the vehicle use - // if (Throttle_status__510::BATTERY_BMS_ERR_BATTERY_ERR == - // chassis_detail.throttle_status__510().battery_bms_err()) { - // return false; - // } } // brake error - if (chassis_detail.has_brake_status__511()) { + if (ch.has_brake_status__511()) { if (Brake_status__511::BRAKE_ERR_BRAKE_SYSTEM_ERR == - chassis_detail.brake_status__511().brake_err()) { + ch.brake_status__511().brake_err()) { return true; } } @@ -626,7 +486,6 @@ void ChController::SecurityDogThreadFunc() { ++horizontal_ctrl_fail; if (horizontal_ctrl_fail >= kMaxFailAttempt) { emergency_mode = true; - AINFO << "Driving_mode is into emergency by steer manual intervention"; set_chassis_error_code(Chassis::MANUAL_INTERVENTION); } } else { @@ -640,7 +499,6 @@ void ChController::SecurityDogThreadFunc() { ++vertical_ctrl_fail; if (vertical_ctrl_fail >= kMaxFailAttempt) { emergency_mode = true; - AINFO << "Driving_mode is into emergency by speed manual intervention"; set_chassis_error_code(Chassis::MANUAL_INTERVENTION); } } else { @@ -654,7 +512,6 @@ void ChController::SecurityDogThreadFunc() { if (emergency_mode && mode != Chassis::EMERGENCY_MODE) { set_driving_mode(Chassis::EMERGENCY_MODE); message_manager_->ResetSendMessages(); - can_sender_->Update(); } end = ::apollo::cyber::Time::Now().ToMicrosecond(); std::chrono::duration elapsed{end - start}; @@ -666,10 +523,9 @@ void ChController::SecurityDogThreadFunc() { } } } - bool ChController::CheckResponse(const int32_t flags, bool need_wait) { int32_t retry_num = 20; - Ch chassis_detail; + ChassisDetail chassis_detail; bool is_eps_online = false; bool is_vcu_online = false; bool is_esp_online = false; diff --git a/modules/canbus_vehicle/ch/ch_controller.h b/modules/canbus/vehicle/ch/ch_controller.h similarity index 83% rename from modules/canbus_vehicle/ch/ch_controller.h rename to modules/canbus/vehicle/ch/ch_controller.h index 017754ee617..35a3f04cfb2 100644 --- a/modules/canbus_vehicle/ch/ch_controller.h +++ b/modules/canbus/vehicle/ch/ch_controller.h @@ -26,18 +26,18 @@ #include "modules/common_msgs/basic_msgs/error_code.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" -#include "modules/canbus_vehicle/ch/protocol/brake_command_111.h" -#include "modules/canbus_vehicle/ch/protocol/gear_command_114.h" -#include "modules/canbus_vehicle/ch/protocol/steer_command_112.h" -#include "modules/canbus_vehicle/ch/protocol/throttle_command_110.h" -#include "modules/canbus_vehicle/ch/protocol/turnsignal_command_113.h" -#include "modules/canbus_vehicle/ch/protocol/vehicle_mode_command_116.h" +#include "modules/canbus/vehicle/ch/protocol/brake_command_111.h" +#include "modules/canbus/vehicle/ch/protocol/control_command_115.h" +#include "modules/canbus/vehicle/ch/protocol/gear_command_114.h" +#include "modules/canbus/vehicle/ch/protocol/steer_command_112.h" +#include "modules/canbus/vehicle/ch/protocol/throttle_command_110.h" +#include "modules/canbus/vehicle/ch/protocol/turnsignal_command_113.h" namespace apollo { namespace canbus { namespace ch { -class ChController final : public VehicleController<::apollo::canbus::Ch> { +class ChController final : public VehicleController { public: ChController() {} @@ -45,8 +45,8 @@ class ChController final : public VehicleController<::apollo::canbus::Ch> { ::apollo::common::ErrorCode Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Ch>* const can_sender, - MessageManager<::apollo::canbus::Ch>* const message_manager) + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) override; bool Start() override; @@ -85,8 +85,6 @@ class ChController final : public VehicleController<::apollo::canbus::Ch> { // gas:0.00~99.99 unit: void Throttle(double throttle) override; - // drive with acceleration/deceleration - // acc:-7.0~5.0 unit:m/s^2 void Acceleration(double acc) override; // steering with old angle speed @@ -105,13 +103,8 @@ class ChController final : public VehicleController<::apollo::canbus::Ch> { void SetTurningSignal( const ::apollo::control::ControlCommand& command) override; - // response vid - bool VerifyID() override; void ResetProtocol(); bool CheckChassisError(); - bool CheckVin(); - void GetVin(); - void ResetVin(); private: void SecurityDogThreadFunc(); @@ -124,11 +117,11 @@ class ChController final : public VehicleController<::apollo::canbus::Ch> { private: // control protocol Brakecommand111* brake_command_111_ = nullptr; + Controlcommand115* control_command_115_ = nullptr; Gearcommand114* gear_command_114_ = nullptr; Steercommand112* steer_command_112_ = nullptr; Throttlecommand110* throttle_command_110_ = nullptr; Turnsignalcommand113* turnsignal_command_113_ = nullptr; - Vehiclemodecommand116* vehicle_mode_command_116_ = nullptr; Chassis chassis_; std::unique_ptr thread_; diff --git a/modules/canbus_vehicle/ch/ch_controller_test.cc b/modules/canbus/vehicle/ch/ch_controller_test.cc similarity index 93% rename from modules/canbus_vehicle/ch/ch_controller_test.cc rename to modules/canbus/vehicle/ch/ch_controller_test.cc index ba0e44697c3..616b43b66f3 100644 --- a/modules/canbus_vehicle/ch/ch_controller_test.cc +++ b/modules/canbus/vehicle/ch/ch_controller_test.cc @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/ch_controller.h" +#include "modules/canbus/vehicle/ch/ch_controller.h" #include "cyber/common/file.h" #include "gtest/gtest.h" #include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/canbus_vehicle/ch/proto/ch.pb.h" -#include "modules/canbus_vehicle/ch/ch_message_manager.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" +#include "modules/canbus/vehicle/ch/ch_message_manager.h" #include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" #include "modules/drivers/canbus/can_comm/can_sender.h" @@ -49,7 +49,7 @@ class ChControllerTest : public ::testing::Test { ChController controller_; ControlCommand control_cmd_; VehicleSignal vehicle_signal_; - CanSender<::apollo::canbus::Ch> sender_; + CanSender<::apollo::canbus::ChassisDetail> sender_; ChMessageManager msg_manager_; CanbusConf canbus_conf_; VehicleParameter params_; diff --git a/modules/canbus_vehicle/ch/ch_message_manager.cc b/modules/canbus/vehicle/ch/ch_message_manager.cc similarity index 51% rename from modules/canbus_vehicle/ch/ch_message_manager.cc rename to modules/canbus/vehicle/ch/ch_message_manager.cc index 6580c6c303c..3fbc7e63301 100644 --- a/modules/canbus_vehicle/ch/ch_message_manager.cc +++ b/modules/canbus/vehicle/ch/ch_message_manager.cc @@ -14,28 +14,21 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/ch_message_manager.h" - -#include "modules/canbus_vehicle/ch/protocol/throttle_command_110.h" -#include "modules/canbus_vehicle/ch/protocol/brake_command_111.h" -#include "modules/canbus_vehicle/ch/protocol/steer_command_112.h" -#include "modules/canbus_vehicle/ch/protocol/turnsignal_command_113.h" -#include "modules/canbus_vehicle/ch/protocol/gear_command_114.h" -#include "modules/canbus_vehicle/ch/protocol/vehicle_mode_command_116.h" - -#include "modules/canbus_vehicle/ch/protocol/throttle_status__510.h" -#include "modules/canbus_vehicle/ch/protocol/brake_status__511.h" -#include "modules/canbus_vehicle/ch/protocol/steer_status__512.h" -#include "modules/canbus_vehicle/ch/protocol/turnsignal_status__513.h" -#include "modules/canbus_vehicle/ch/protocol/gear_status_514.h" -#include "modules/canbus_vehicle/ch/protocol/ecu_status_1_515.h" -#include "modules/canbus_vehicle/ch/protocol/ecu_status_2_516.h" -#include "modules/canbus_vehicle/ch/protocol/ecu_status_3_517.h" -#include "modules/canbus_vehicle/ch/protocol/ecu_status_4_518.h" -#include "modules/canbus_vehicle/ch/protocol/vin_resp1_51b.h" -#include "modules/canbus_vehicle/ch/protocol/vin_resp2_51c.h" -#include "modules/canbus_vehicle/ch/protocol/vin_resp3_51d.h" -#include "modules/canbus_vehicle/ch/protocol/wheelspeed_report_51e.h" +#include "modules/canbus/vehicle/ch/ch_message_manager.h" +#include "modules/canbus/vehicle/ch/protocol/brake_command_111.h" +#include "modules/canbus/vehicle/ch/protocol/brake_status__511.h" +#include "modules/canbus/vehicle/ch/protocol/control_command_115.h" +#include "modules/canbus/vehicle/ch/protocol/ecu_status_1_515.h" +#include "modules/canbus/vehicle/ch/protocol/ecu_status_2_516.h" +#include "modules/canbus/vehicle/ch/protocol/ecu_status_3_517.h" +#include "modules/canbus/vehicle/ch/protocol/gear_command_114.h" +#include "modules/canbus/vehicle/ch/protocol/gear_status_514.h" +#include "modules/canbus/vehicle/ch/protocol/steer_command_112.h" +#include "modules/canbus/vehicle/ch/protocol/steer_status__512.h" +#include "modules/canbus/vehicle/ch/protocol/throttle_command_110.h" +#include "modules/canbus/vehicle/ch/protocol/throttle_status__510.h" +#include "modules/canbus/vehicle/ch/protocol/turnsignal_command_113.h" +#include "modules/canbus/vehicle/ch/protocol/turnsignal_status__513.h" namespace apollo { namespace canbus { @@ -44,26 +37,21 @@ namespace ch { ChMessageManager::ChMessageManager() { // Control Messages AddSendProtocolData(); + AddSendProtocolData(); AddSendProtocolData(); AddSendProtocolData(); AddSendProtocolData(); AddSendProtocolData(); - AddSendProtocolData(); // Report Messages AddRecvProtocolData(); AddRecvProtocolData(); AddRecvProtocolData(); AddRecvProtocolData(); - AddRecvProtocolData(); AddRecvProtocolData(); AddRecvProtocolData(); AddRecvProtocolData(); AddRecvProtocolData(); - AddRecvProtocolData(); - AddRecvProtocolData(); - AddRecvProtocolData(); - AddRecvProtocolData(); } ChMessageManager::~ChMessageManager() {} diff --git a/modules/canbus_vehicle/ch/ch_message_manager.h b/modules/canbus/vehicle/ch/ch_message_manager.h similarity index 90% rename from modules/canbus_vehicle/ch/ch_message_manager.h rename to modules/canbus/vehicle/ch/ch_message_manager.h index 7bcca1b34cd..74f080e7682 100644 --- a/modules/canbus_vehicle/ch/ch_message_manager.h +++ b/modules/canbus/vehicle/ch/ch_message_manager.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/ch/proto/ch.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/message_manager.h" namespace apollo { @@ -31,7 +31,7 @@ namespace ch { using ::apollo::drivers::canbus::MessageManager; class ChMessageManager - : public MessageManager<::apollo::canbus::Ch> { + : public MessageManager<::apollo::canbus::ChassisDetail> { public: ChMessageManager(); virtual ~ChMessageManager(); diff --git a/modules/canbus_vehicle/ch/ch_message_manager_test.cc b/modules/canbus/vehicle/ch/ch_message_manager_test.cc similarity index 70% rename from modules/canbus_vehicle/ch/ch_message_manager_test.cc rename to modules/canbus/vehicle/ch/ch_message_manager_test.cc index 231adb09d11..2ae2cd75a37 100644 --- a/modules/canbus_vehicle/ch/ch_message_manager_test.cc +++ b/modules/canbus/vehicle/ch/ch_message_manager_test.cc @@ -14,26 +14,27 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/ch_message_manager.h" +#include "modules/canbus/vehicle/ch/ch_message_manager.h" #include "gtest/gtest.h" -#include "modules/canbus_vehicle/ch/protocol/brake_command_111.h" -#include "modules/canbus_vehicle/ch/protocol/brake_status__511.h" -#include "modules/canbus_vehicle/ch/protocol/ecu_status_1_515.h" -#include "modules/canbus_vehicle/ch/protocol/ecu_status_2_516.h" -#include "modules/canbus_vehicle/ch/protocol/ecu_status_3_517.h" -#include "modules/canbus_vehicle/ch/protocol/gear_command_114.h" -#include "modules/canbus_vehicle/ch/protocol/gear_status_514.h" -#include "modules/canbus_vehicle/ch/protocol/steer_command_112.h" -#include "modules/canbus_vehicle/ch/protocol/steer_status__512.h" -#include "modules/canbus_vehicle/ch/protocol/throttle_command_110.h" -#include "modules/canbus_vehicle/ch/protocol/throttle_status__510.h" -#include "modules/canbus_vehicle/ch/protocol/turnsignal_command_113.h" -#include "modules/canbus_vehicle/ch/protocol/turnsignal_status__513.h" +#include "modules/canbus/vehicle/ch/protocol/brake_command_111.h" +#include "modules/canbus/vehicle/ch/protocol/brake_status__511.h" +#include "modules/canbus/vehicle/ch/protocol/control_command_115.h" +#include "modules/canbus/vehicle/ch/protocol/ecu_status_1_515.h" +#include "modules/canbus/vehicle/ch/protocol/ecu_status_2_516.h" +#include "modules/canbus/vehicle/ch/protocol/ecu_status_3_517.h" +#include "modules/canbus/vehicle/ch/protocol/gear_command_114.h" +#include "modules/canbus/vehicle/ch/protocol/gear_status_514.h" +#include "modules/canbus/vehicle/ch/protocol/steer_command_112.h" +#include "modules/canbus/vehicle/ch/protocol/steer_status__512.h" +#include "modules/canbus/vehicle/ch/protocol/throttle_command_110.h" +#include "modules/canbus/vehicle/ch/protocol/throttle_status__510.h" +#include "modules/canbus/vehicle/ch/protocol/turnsignal_command_113.h" +#include "modules/canbus/vehicle/ch/protocol/turnsignal_status__513.h" namespace apollo { namespace canbus { namespace ch { -using ::apollo::canbus::Ch; +using ::apollo::canbus::ChassisDetail; using ::apollo::drivers::canbus::ProtocolData; class ChMessageManagerTest : public ::testing::Test { @@ -43,7 +44,7 @@ class ChMessageManagerTest : public ::testing::Test { TEST_F(ChMessageManagerTest, Brakecommand111) { ChMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Brakecommand111::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Brakecommand111::ID); @@ -51,15 +52,23 @@ TEST_F(ChMessageManagerTest, Brakecommand111) { TEST_F(ChMessageManagerTest, Brakestatus511) { ChMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Brakestatus511::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Brakestatus511::ID); } +TEST_F(ChMessageManagerTest, Controlcommand115) { + ChMessageManager manager; + ProtocolData *pd = + manager.GetMutableProtocolDataById(Controlcommand115::ID); + EXPECT_NE(pd, nullptr); + EXPECT_EQ(static_cast(pd)->ID, Controlcommand115::ID); +} + TEST_F(ChMessageManagerTest, Ecustatus1515) { ChMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Ecustatus1515::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Ecustatus1515::ID); @@ -67,7 +76,7 @@ TEST_F(ChMessageManagerTest, Ecustatus1515) { TEST_F(ChMessageManagerTest, Ecustatus2516) { ChMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Ecustatus2516::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Ecustatus2516::ID); @@ -75,7 +84,7 @@ TEST_F(ChMessageManagerTest, Ecustatus2516) { TEST_F(ChMessageManagerTest, Ecustatus3517) { ChMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Ecustatus3517::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Ecustatus3517::ID); @@ -83,7 +92,7 @@ TEST_F(ChMessageManagerTest, Ecustatus3517) { TEST_F(ChMessageManagerTest, Gearcommand114) { ChMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Gearcommand114::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Gearcommand114::ID); @@ -91,7 +100,7 @@ TEST_F(ChMessageManagerTest, Gearcommand114) { TEST_F(ChMessageManagerTest, Gearstatus514) { ChMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Gearstatus514::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Gearstatus514::ID); @@ -99,7 +108,7 @@ TEST_F(ChMessageManagerTest, Gearstatus514) { TEST_F(ChMessageManagerTest, Steercommand112) { ChMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Steercommand112::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Steercommand112::ID); @@ -107,7 +116,7 @@ TEST_F(ChMessageManagerTest, Steercommand112) { TEST_F(ChMessageManagerTest, Steerstatus512) { ChMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Steerstatus512::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Steerstatus512::ID); @@ -115,7 +124,7 @@ TEST_F(ChMessageManagerTest, Steerstatus512) { TEST_F(ChMessageManagerTest, Throttlecommand110) { ChMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Throttlecommand110::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Throttlecommand110::ID); @@ -123,7 +132,7 @@ TEST_F(ChMessageManagerTest, Throttlecommand110) { TEST_F(ChMessageManagerTest, Throttlestatus510) { ChMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Throttlestatus510::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Throttlestatus510::ID); @@ -131,7 +140,7 @@ TEST_F(ChMessageManagerTest, Throttlestatus510) { TEST_F(ChMessageManagerTest, Turnsignalcommand113) { ChMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Turnsignalcommand113::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, @@ -140,7 +149,7 @@ TEST_F(ChMessageManagerTest, Turnsignalcommand113) { TEST_F(ChMessageManagerTest, Turnsignalstatus513) { ChMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Turnsignalstatus513::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, diff --git a/modules/tools/gen_vehicle_protocol/template/control_protocol.h.tpl b/modules/canbus/vehicle/ch/ch_vehicle_factory.cc similarity index 58% rename from modules/tools/gen_vehicle_protocol/template/control_protocol.h.tpl rename to modules/canbus/vehicle/ch/ch_vehicle_factory.cc index 58e05d1e0c5..dad3bcc1f90 100644 --- a/modules/tools/gen_vehicle_protocol/template/control_protocol.h.tpl +++ b/modules/canbus/vehicle/ch/ch_vehicle_factory.cc @@ -14,38 +14,25 @@ * limitations under the License. *****************************************************************************/ -#pragma once +#include "modules/canbus/vehicle/ch/ch_vehicle_factory.h" -#include "modules/drivers/canbus/can_comm/protocol_data.h" -#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" +#include "cyber/common/log.h" +#include "modules/canbus/vehicle/ch/ch_controller.h" +#include "modules/canbus/vehicle/ch/ch_message_manager.h" +#include "modules/common/util/util.h" namespace apollo { namespace canbus { -namespace %(car_type_lower)s { -class %(classname)s : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::ChassisDetail> { - public: - static const int32_t ID; +std::unique_ptr ChVehicleFactory::CreateVehicleController() { + return std::unique_ptr(new ch::ChController()); +} - %(classname)s(); +std::unique_ptr> +ChVehicleFactory::CreateMessageManager() { + return std::unique_ptr>( + new ch::ChMessageManager()); +} - uint32_t GetPeriod() const override; - - void UpdateData(uint8_t* data) override; - - void Reset() override; -%(declare_public_func_list)s - - private: -%(declare_private_func_list)s - - private: -%(declare_private_var_list)s -}; - -} // namespace %(car_type_lower)s } // namespace canbus } // namespace apollo - - diff --git a/modules/tools/gen_vehicle_protocol/template/vehicle_factory.h.tpl b/modules/canbus/vehicle/ch/ch_vehicle_factory.h similarity index 79% rename from modules/tools/gen_vehicle_protocol/template/vehicle_factory.h.tpl rename to modules/canbus/vehicle/ch/ch_vehicle_factory.h index a2c067761dd..427deabe366 100644 --- a/modules/tools/gen_vehicle_protocol/template/vehicle_factory.h.tpl +++ b/modules/canbus/vehicle/ch/ch_vehicle_factory.h @@ -15,7 +15,7 @@ *****************************************************************************/ /** - * @file %(car_type_lower)s_vehicle_factory.h + * @file ch_vehicle_factory.h */ #pragma once @@ -35,26 +35,26 @@ namespace apollo { namespace canbus { /** - * @class %(car_type_cap)sVehicleFactory + * @class ChVehicleFactory * * @brief this class is inherited from AbstractVehicleFactory. It can be used to - * create controller and message manager for %(car_type_lower)s vehicle. + * create controller and message manager for ch vehicle. */ -class %(car_type_cap)sVehicleFactory : public AbstractVehicleFactory { +class ChVehicleFactory : public AbstractVehicleFactory { public: /** - * @brief destructor - */ - virtual ~%(car_type_cap)sVehicleFactory() = default; + * @brief destructor + */ + virtual ~ChVehicleFactory() = default; /** - * @brief create %(car_type_lower)s vehicle controller + * @brief create ch vehicle controller * @returns a unique_ptr that points to the created controller */ std::unique_ptr CreateVehicleController() override; /** - * @brief create %(car_type_lower)s message manager + * @brief create ch message manager * @returns a unique_ptr that points to the created message manager */ std::unique_ptr> @@ -63,5 +63,3 @@ class %(car_type_cap)sVehicleFactory : public AbstractVehicleFactory { } // namespace canbus } // namespace apollo - - diff --git a/modules/canbus_vehicle/ch/ch_vehicle_factory_test.cc b/modules/canbus/vehicle/ch/ch_vehicle_factory_test.cc similarity index 63% rename from modules/canbus_vehicle/ch/ch_vehicle_factory_test.cc rename to modules/canbus/vehicle/ch/ch_vehicle_factory_test.cc index 2e0a5d6ce9c..95bc4a7ea55 100644 --- a/modules/canbus_vehicle/ch/ch_vehicle_factory_test.cc +++ b/modules/canbus/vehicle/ch/ch_vehicle_factory_test.cc @@ -14,39 +14,32 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/ch_vehicle_factory.h" - +#include "modules/canbus/vehicle/ch/ch_vehicle_factory.h" #include "gtest/gtest.h" - -#include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "cyber/common/file.h" - namespace apollo { namespace canbus { class ChVehicleFactoryTest : public ::testing::Test { public: virtual void SetUp() { - std::string canbus_conf_file = - "/apollo/modules/canbus_vehicle/ch/testdata/ch_canbus_conf_test.pb.txt"; - cyber::common::GetProtoFromFile(canbus_conf_file, &canbus_conf_); - params_ = canbus_conf_.vehicle_parameter(); - params_.set_brand(apollo::common::CH); - ch_factory_.SetVehicleParameter(params_); + VehicleParameter parameter; + parameter.set_brand(apollo::common::CH); + ch_factory_.SetVehicleParameter(parameter); } virtual void TearDown() {} protected: ChVehicleFactory ch_factory_; - CanbusConf canbus_conf_; - VehicleParameter params_; }; -TEST_F(ChVehicleFactoryTest, Init) { - apollo::cyber::Init("vehicle_factory_test"); - EXPECT_EQ(ch_factory_.Init(&canbus_conf_), true); +TEST_F(ChVehicleFactoryTest, InitVehicleController) { + EXPECT_NE(ch_factory_.CreateVehicleController(), nullptr); +} + +TEST_F(ChVehicleFactoryTest, InitMessageManager) { + EXPECT_NE(ch_factory_.CreateMessageManager(), nullptr); } } // namespace canbus diff --git a/modules/canbus_vehicle/ch/protocol/BUILD b/modules/canbus/vehicle/ch/protocol/BUILD similarity index 65% rename from modules/canbus_vehicle/ch/protocol/BUILD rename to modules/canbus/vehicle/ch/protocol/BUILD index 256eca580fa..641d72de0d3 100644 --- a/modules/canbus_vehicle/ch/protocol/BUILD +++ b/modules/canbus/vehicle/ch/protocol/BUILD @@ -10,10 +10,10 @@ cc_library( deps = [ ":brake_command_111", ":brake_status__511", + ":control_command_115", ":ecu_status_1_515", ":ecu_status_2_516", ":ecu_status_3_517", - ":ecu_status_4_518", ":gear_command_114", ":gear_status_514", ":steer_command_112", @@ -22,11 +22,6 @@ cc_library( ":throttle_status__510", ":turnsignal_command_113", ":turnsignal_status__513", - ":vehicle_mode_command_116", - ":vin_resp1_51b", - ":vin_resp2_51c", - ":vin_resp3_51d", - ":wheelspeed_report_51e", ], ) @@ -36,7 +31,7 @@ cc_library( hdrs = ["brake_command_111.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -47,7 +42,7 @@ cc_test( size = "small", srcs = ["brake_command_111_test.cc"], deps = [ - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -58,7 +53,7 @@ cc_library( hdrs = ["brake_status__511.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -69,7 +64,29 @@ cc_test( size = "small", srcs = ["brake_status__511_test.cc"], deps = [ - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", + "@com_google_googletest//:gtest_main", + ], +) + +cc_library( + name = "control_command_115", + srcs = ["control_command_115.cc"], + hdrs = ["control_command_115.h"], + copts = CANBUS_COPTS, + deps = [ + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_test( + name = "control_command_115_test", + size = "small", + srcs = ["control_command_115_test.cc"], + deps = [ + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -80,7 +97,7 @@ cc_library( hdrs = ["ecu_status_1_515.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -91,7 +108,7 @@ cc_test( size = "small", srcs = ["ecu_status_1_515_test.cc"], deps = [ - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -102,7 +119,7 @@ cc_library( hdrs = ["ecu_status_2_516.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -113,7 +130,7 @@ cc_test( size = "small", srcs = ["ecu_status_2_516_test.cc"], deps = [ - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -124,7 +141,7 @@ cc_library( hdrs = ["ecu_status_3_517.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -135,30 +152,18 @@ cc_test( size = "small", srcs = ["ecu_status_3_517_test.cc"], deps = [ - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", "@com_google_googletest//:gtest_main", ], ) -cc_library( - name = "ecu_status_4_518", - srcs = ["ecu_status_4_518.cc"], - hdrs = ["ecu_status_4_518.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - cc_library( name = "gear_command_114", srcs = ["gear_command_114.cc"], hdrs = ["gear_command_114.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -169,7 +174,7 @@ cc_test( size = "small", srcs = ["gear_command_114_test.cc"], deps = [ - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -180,7 +185,7 @@ cc_library( hdrs = ["gear_status_514.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -191,7 +196,7 @@ cc_test( size = "small", srcs = ["gear_status_514_test.cc"], deps = [ - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -202,7 +207,7 @@ cc_library( hdrs = ["steer_command_112.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -213,7 +218,7 @@ cc_test( size = "small", srcs = ["steer_command_112_test.cc"], deps = [ - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -224,7 +229,7 @@ cc_library( hdrs = ["steer_status__512.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -235,7 +240,7 @@ cc_test( size = "small", srcs = ["steer_status__512_test.cc"], deps = [ - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -246,7 +251,7 @@ cc_library( hdrs = ["throttle_command_110.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -257,7 +262,7 @@ cc_test( size = "small", srcs = ["throttle_command_110_test.cc"], deps = [ - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -268,7 +273,7 @@ cc_library( hdrs = ["throttle_status__510.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -279,7 +284,7 @@ cc_test( size = "small", srcs = ["throttle_status__510_test.cc"], deps = [ - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -290,7 +295,7 @@ cc_library( hdrs = ["turnsignal_command_113.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -301,10 +306,9 @@ cc_test( size = "small", srcs = ["turnsignal_command_113_test.cc"], deps = [ - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_library( @@ -313,7 +317,7 @@ cc_library( hdrs = ["turnsignal_status__513.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -324,69 +328,9 @@ cc_test( size = "small", srcs = ["turnsignal_status__513_test.cc"], deps = [ - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", + "//modules/canbus/vehicle/ch/protocol:canbus_ch_protocol", "@com_google_googletest//:gtest_main", ], ) -cc_library( - name = "vehicle_mode_command_116", - srcs = ["vehicle_mode_command_116.cc"], - hdrs = ["vehicle_mode_command_116.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_library( - name = "vin_resp1_51b", - srcs = ["vin_resp1_51b.cc"], - hdrs = ["vin_resp1_51b.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_library( - name = "vin_resp2_51c", - srcs = ["vin_resp2_51c.cc"], - hdrs = ["vin_resp2_51c.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_library( - name = "vin_resp3_51d", - srcs = ["vin_resp3_51d.cc"], - hdrs = ["vin_resp3_51d.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_library( - name = "wheelspeed_report_51e", - srcs = ["wheelspeed_report_51e.cc"], - hdrs = ["wheelspeed_report_51e.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - cpplint() diff --git a/modules/canbus_vehicle/ch/protocol/brake_command_111.cc b/modules/canbus/vehicle/ch/protocol/brake_command_111.cc similarity index 73% rename from modules/canbus_vehicle/ch/protocol/brake_command_111.cc rename to modules/canbus/vehicle/ch/protocol/brake_command_111.cc index 0a4414cb44c..235fca85c91 100644 --- a/modules/canbus_vehicle/ch/protocol/brake_command_111.cc +++ b/modules/canbus/vehicle/ch/protocol/brake_command_111.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/brake_command_111.h" +#include "modules/canbus/vehicle/ch/protocol/brake_command_111.h" #include "modules/drivers/canbus/common/byte.h" namespace apollo { @@ -29,7 +29,7 @@ const int32_t Brakecommand111::ID = 0x111; Brakecommand111::Brakecommand111() { Reset(); } uint32_t Brakecommand111::GetPeriod() const { - // TODO(All) : modify every protocol's period manually + // modify every protocol's period manually static const uint32_t PERIOD = 20 * 1000; return PERIOD; } @@ -40,7 +40,7 @@ void Brakecommand111::UpdateData(uint8_t* data) { } void Brakecommand111::Reset() { - // TODO(All) : you should check this manually + // you should check this manually brake_pedal_en_ctrl_ = Brake_command_111::BRAKE_PEDAL_EN_CTRL_DISABLE; brake_pedal_cmd_ = 0; } @@ -51,18 +51,18 @@ Brakecommand111* Brakecommand111::set_brake_pedal_en_ctrl( return this; } -// config detail: {'bit': 0, 'description': 'brake pedal enable bit(Command)', -// 'enum': {0: 'BRAKE_PEDAL_EN_CTRL_DISABLE', 1: 'BRAKE_PEDAL_EN_CTRL_ENABLE'}, -// 'is_signed_var': False, 'len': 8, 'name': 'BRAKE_PEDAL_EN_CTRL', 'offset': -// 0.0, 'order': 'intel', 'physical_range': '[0|1]', 'physical_unit': '', -// 'precision': 1.0, 'type': 'enum'} +// config detail: {'description': 'brake pedal enable bit(Command)', 'enum': {0: +// 'BRAKE_PEDAL_EN_CTRL_DISABLE', 1: 'BRAKE_PEDAL_EN_CTRL_ENABLE'}, +// 'precision': 1.0, 'len': 8, 'name': 'BRAKE_PEDAL_EN_CTRL', 'is_signed_var': +// False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', +// 'order': 'intel', 'physical_unit': ''} void Brakecommand111::set_p_brake_pedal_en_ctrl( uint8_t* data, Brake_command_111::Brake_pedal_en_ctrlType brake_pedal_en_ctrl) { int x = brake_pedal_en_ctrl; Byte to_set(data + 0); - to_set.set_value(x, 0, 8); + to_set.set_value(static_cast(x), 0, 8); } Brakecommand111* Brakecommand111::set_brake_pedal_cmd(int brake_pedal_cmd) { @@ -70,10 +70,10 @@ Brakecommand111* Brakecommand111::set_brake_pedal_cmd(int brake_pedal_cmd) { return this; } -// config detail: {'bit': 8, 'description': 'Percentage of brake -// pedal(Command)', 'is_signed_var': False, 'len': 8, 'name': 'BRAKE_PEDAL_CMD', -// 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|100]', -// 'physical_unit': '%', 'precision': 1.0, 'type': 'int'} +// config detail: {'description': 'Percentage of brake pedal(Command)', +// 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': 'BRAKE_PEDAL_CMD', +// 'is_signed_var': False, 'physical_range': '[0|100]', 'bit': 8, 'type': 'int', +// 'order': 'intel', 'physical_unit': '%'} void Brakecommand111::set_p_brake_pedal_cmd(uint8_t* data, int brake_pedal_cmd) { brake_pedal_cmd = ProtocolData::BoundedValue(0, 100, brake_pedal_cmd); diff --git a/modules/canbus_vehicle/ch/protocol/brake_command_111.h b/modules/canbus/vehicle/ch/protocol/brake_command_111.h similarity index 54% rename from modules/canbus_vehicle/ch/protocol/brake_command_111.h rename to modules/canbus/vehicle/ch/protocol/brake_command_111.h index 8b6076a5bc6..4b2a33b900d 100644 --- a/modules/canbus_vehicle/ch/protocol/brake_command_111.h +++ b/modules/canbus/vehicle/ch/protocol/brake_command_111.h @@ -16,7 +16,8 @@ #pragma once -#include "modules/canbus_vehicle/ch/proto/ch.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" + #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +25,7 @@ namespace canbus { namespace ch { class Brakecommand111 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -36,34 +37,34 @@ class Brakecommand111 : public ::apollo::drivers::canbus::ProtocolData< void Reset() override; - // config detail: {'bit': 0, 'description': 'brake pedal enable bit(Command)', - // 'enum': {0: 'BRAKE_PEDAL_EN_CTRL_DISABLE', 1: - // 'BRAKE_PEDAL_EN_CTRL_ENABLE'}, 'is_signed_var': False, 'len': 8, 'name': - // 'BRAKE_PEDAL_EN_CTRL', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + // config detail: {'description': 'brake pedal enable bit(Command)', 'enum': + // {0: 'BRAKE_PEDAL_EN_CTRL_DISABLE', 1: 'BRAKE_PEDAL_EN_CTRL_ENABLE'}, + // 'precision': 1.0, 'len': 8, 'name': 'BRAKE_PEDAL_EN_CTRL', 'is_signed_var': + // False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', + // 'order': 'intel', 'physical_unit': ''} Brakecommand111* set_brake_pedal_en_ctrl( Brake_command_111::Brake_pedal_en_ctrlType brake_pedal_en_ctrl); - // config detail: {'bit': 8, 'description': 'Percentage of brake - // pedal(Command)', 'is_signed_var': False, 'len': 8, 'name': - // 'BRAKE_PEDAL_CMD', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|100]', 'physical_unit': '%', 'precision': 1.0, 'type': 'int'} + // config detail: {'description': 'Percentage of brake pedal(Command)', + // 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': 'BRAKE_PEDAL_CMD', + // 'is_signed_var': False, 'physical_range': '[0|100]', 'bit': 8, 'type': + // 'int', 'order': 'intel', 'physical_unit': '%'} Brakecommand111* set_brake_pedal_cmd(int brake_pedal_cmd); private: - // config detail: {'bit': 0, 'description': 'brake pedal enable bit(Command)', - // 'enum': {0: 'BRAKE_PEDAL_EN_CTRL_DISABLE', 1: - // 'BRAKE_PEDAL_EN_CTRL_ENABLE'}, 'is_signed_var': False, 'len': 8, 'name': - // 'BRAKE_PEDAL_EN_CTRL', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + // config detail: {'description': 'brake pedal enable bit(Command)', 'enum': + // {0: 'BRAKE_PEDAL_EN_CTRL_DISABLE', 1: 'BRAKE_PEDAL_EN_CTRL_ENABLE'}, + // 'precision': 1.0, 'len': 8, 'name': 'BRAKE_PEDAL_EN_CTRL', 'is_signed_var': + // False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', + // 'order': 'intel', 'physical_unit': ''} void set_p_brake_pedal_en_ctrl( uint8_t* data, Brake_command_111::Brake_pedal_en_ctrlType brake_pedal_en_ctrl); - // config detail: {'bit': 8, 'description': 'Percentage of brake - // pedal(Command)', 'is_signed_var': False, 'len': 8, 'name': - // 'BRAKE_PEDAL_CMD', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|100]', 'physical_unit': '%', 'precision': 1.0, 'type': 'int'} + // config detail: {'description': 'Percentage of brake pedal(Command)', + // 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': 'BRAKE_PEDAL_CMD', + // 'is_signed_var': False, 'physical_range': '[0|100]', 'bit': 8, 'type': + // 'int', 'order': 'intel', 'physical_unit': '%'} void set_p_brake_pedal_cmd(uint8_t* data, int brake_pedal_cmd); private: diff --git a/modules/canbus_vehicle/ch/protocol/brake_command_111_test.cc b/modules/canbus/vehicle/ch/protocol/brake_command_111_test.cc similarity index 95% rename from modules/canbus_vehicle/ch/protocol/brake_command_111_test.cc rename to modules/canbus/vehicle/ch/protocol/brake_command_111_test.cc index 815f7ce32bd..87cef21b2e9 100644 --- a/modules/canbus_vehicle/ch/protocol/brake_command_111_test.cc +++ b/modules/canbus/vehicle/ch/protocol/brake_command_111_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/brake_command_111.h" +#include "modules/canbus/vehicle/ch/protocol/brake_command_111.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/ch/protocol/brake_status__511.cc b/modules/canbus/vehicle/ch/protocol/brake_status__511.cc similarity index 51% rename from modules/canbus_vehicle/ch/protocol/brake_status__511.cc rename to modules/canbus/vehicle/ch/protocol/brake_status__511.cc index 27406ffe104..f660280aaca 100644 --- a/modules/canbus_vehicle/ch/protocol/brake_status__511.cc +++ b/modules/canbus/vehicle/ch/protocol/brake_status__511.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/brake_status__511.h" +#include "modules/canbus/vehicle/ch/protocol/brake_status__511.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,61 +29,44 @@ Brakestatus511::Brakestatus511() {} const int32_t Brakestatus511::ID = 0x511; void Brakestatus511::Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const { - chassis->mutable_brake_status__511()->set_overspd_env( - overspd_env(bytes, length)); - chassis->mutable_brake_status__511()->set_brake_pedal_en_sts( + ChassisDetail* chassis) const { + chassis->mutable_ch()->mutable_brake_status__511()->set_brake_pedal_en_sts( brake_pedal_en_sts(bytes, length)); - chassis->mutable_brake_status__511()->set_brake_pedal_sts( + chassis->mutable_ch()->mutable_brake_status__511()->set_brake_pedal_sts( brake_pedal_sts(bytes, length)); - chassis->mutable_brake_status__511()->set_brake_err( + chassis->mutable_ch()->mutable_brake_status__511()->set_brake_err( brake_err(bytes, length)); - chassis->mutable_brake_status__511()->set_emergency_btn_env( + chassis->mutable_ch()->mutable_brake_status__511()->set_emergency_btn_env( emergency_btn_env(bytes, length)); - chassis->mutable_brake_status__511()->set_front_bump_env( + chassis->mutable_ch()->mutable_brake_status__511()->set_front_bump_env( front_bump_env(bytes, length)); - chassis->mutable_brake_status__511()->set_back_bump_env( + chassis->mutable_ch()->mutable_brake_status__511()->set_back_bump_env( back_bump_env(bytes, length)); - chassis->mutable_brake_status__511()->set_brake_light_actual( - brake_light_actual(bytes, length)); - + chassis->mutable_ch()->mutable_brake_status__511()->set_overspd_env( + overspd_env(bytes, length)); chassis->mutable_check_response()->set_is_esp_online( brake_pedal_en_sts(bytes, length) == 1); } -// config detail: {'bit': 48, 'enum': {0: 'OVERSPD_ENV_NOENV', 1: -// 'OVERSPD_ENV_OVERSPEED_ENV'}, 'is_signed_var': False, 'len': 8, 'name': -// 'overspd_env', 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|1]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Brake_status__511::Overspd_envType Brakestatus511::overspd_env( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(0, 8); - - Brake_status__511::Overspd_envType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 0, 'description': 'brake pedal enable bit(Status)', -// 'enum': {0: 'BRAKE_PEDAL_EN_STS_DISABLE', 1: 'BRAKE_PEDAL_EN_STS_ENABLE', 2: -// 'BRAKE_PEDAL_EN_STS_TAKEOVER'}, 'is_signed_var': False, 'len': 8, 'name': -// 'brake_pedal_en_sts', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|2]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +// config detail: {'description': 'brake pedal enable bit(Status)', 'enum': {0: +// 'BRAKE_PEDAL_EN_STS_DISABLE', 1: 'BRAKE_PEDAL_EN_STS_ENABLE', 2: +// 'BRAKE_PEDAL_EN_STS_TAKEOVER'}, 'precision': 1.0, 'len': 8, 'name': +// 'brake_pedal_en_sts', 'is_signed_var': False, 'offset': 0.0, +// 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', 'order': 'intel', +// 'physical_unit': ''} Brake_status__511::Brake_pedal_en_stsType Brakestatus511::brake_pedal_en_sts( const std::uint8_t* bytes, int32_t length) const { Byte t0(bytes + 0); int32_t x = t0.get_byte(0, 8); - Brake_status__511::Brake_pedal_en_stsType ret = static_cast(x); return ret; } -// config detail: {'bit': 8, 'description': 'Percentage of brake pedal(Status)', -// 'is_signed_var': False, 'len': 8, 'name': 'brake_pedal_sts', 'offset': 0.0, -// 'order': 'intel', 'physical_range': '[0|100]', 'physical_unit': '%', -// 'precision': 1.0, 'type': 'int'} +// config detail: {'description': 'Percentage of brake pedal(Status)', 'offset': +// 0.0, 'precision': 1.0, 'len': 8, 'name': 'brake_pedal_sts', 'is_signed_var': +// False, 'physical_range': '[0|100]', 'bit': 8, 'type': 'int', 'order': +// 'intel', 'physical_unit': '%'} int Brakestatus511::brake_pedal_sts(const std::uint8_t* bytes, int32_t length) const { Byte t0(bytes + 1); @@ -93,10 +76,10 @@ int Brakestatus511::brake_pedal_sts(const std::uint8_t* bytes, return ret; } -// config detail: {'bit': 16, 'enum': {0: 'BRAKE_ERR_NOERR', 1: -// 'BRAKE_ERR_BRAKE_SYSTEM_ERR'}, 'is_signed_var': False, 'len': 8, 'name': -// 'brake_err', 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|1]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +// config detail: {'name': 'brake_err', 'enum': {0: 'BRAKE_ERR_NOERR', 1: +// 'BRAKE_ERR_BRAKE_SYSTEM_ERR'}, 'precision': 1.0, 'len': 8, 'is_signed_var': +// False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 16, 'type': 'enum', +// 'order': 'intel', 'physical_unit': ''} Brake_status__511::Brake_errType Brakestatus511::brake_err( const std::uint8_t* bytes, int32_t length) const { Byte t0(bytes + 2); @@ -107,11 +90,11 @@ Brake_status__511::Brake_errType Brakestatus511::brake_err( return ret; } -// config detail: {'bit': 24, 'enum': {0: 'EMERGENCY_BTN_ENV_NOENV', 1: -// 'EMERGENCY_BTN_ENV_EMERGENCY_BUTTON_ENV'}, 'is_signed_var': False, 'len': 8, -// 'name': 'emergency_btn_env', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'enum'} +// config detail: {'name': 'emergency_btn_env', 'enum': {0: +// 'EMERGENCY_BTN_ENV_NOENV', 1: 'EMERGENCY_BTN_ENV_EMERGENCY_BUTTON_ENV'}, +// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'offset': 0.0, +// 'physical_range': '[0|1]', 'bit': 24, 'type': 'enum', 'order': 'intel', +// 'physical_unit': ''} Brake_status__511::Emergency_btn_envType Brakestatus511::emergency_btn_env( const std::uint8_t* bytes, int32_t length) const { Byte t0(bytes + 3); @@ -122,10 +105,10 @@ Brake_status__511::Emergency_btn_envType Brakestatus511::emergency_btn_env( return ret; } -// config detail: {'bit': 32, 'enum': {0: 'FRONT_BUMP_ENV_NOENV', 1: -// 'FRONT_BUMP_ENV_FRONT_BUMPER_ENV'}, 'is_signed_var': False, 'len': 8, 'name': -// 'front_bump_env', 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|1]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +// config detail: {'name': 'front_bump_env', 'enum': {0: 'FRONT_BUMP_ENV_NOENV', +// 1: 'FRONT_BUMP_ENV_FRONT_BUMPER_ENV'}, 'precision': 1.0, 'len': 8, +// 'is_signed_var': False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 32, +// 'type': 'enum', 'order': 'intel', 'physical_unit': ''} Brake_status__511::Front_bump_envType Brakestatus511::front_bump_env( const std::uint8_t* bytes, int32_t length) const { Byte t0(bytes + 4); @@ -136,10 +119,10 @@ Brake_status__511::Front_bump_envType Brakestatus511::front_bump_env( return ret; } -// config detail: {'bit': 40, 'enum': {0: 'BACK_BUMP_ENV_NOENV', 1: -// 'BACK_BUMP_ENV_BACK_BUMPER_ENV'}, 'is_signed_var': False, 'len': 8, 'name': -// 'back_bump_env', 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|1]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +// config detail: {'name': 'back_bump_env', 'enum': {0: 'BACK_BUMP_ENV_NOENV', +// 1: 'BACK_BUMP_ENV_BACK_BUMPER_ENV'}, 'precision': 1.0, 'len': 8, +// 'is_signed_var': False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 40, +// 'type': 'enum', 'order': 'intel', 'physical_unit': ''} Brake_status__511::Back_bump_envType Brakestatus511::back_bump_env( const std::uint8_t* bytes, int32_t length) const { Byte t0(bytes + 5); @@ -150,18 +133,17 @@ Brake_status__511::Back_bump_envType Brakestatus511::back_bump_env( return ret; } -// config detail: {'bit': 56, 'enum': {0: 'BRAKE_LIGHT_ACTUAL_BRAKELIGHT_OFF', -// 1: 'BRAKE_LIGHT_ACTUAL_BRAKELIGHT_ON'}, 'is_signed_var': False, 'len': 1, -// 'name': 'brake_light_actual', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'enum'} -Brake_status__511::Brake_light_actualType Brakestatus511::brake_light_actual( +// config detail: {'name': 'overspd_env', 'enum': {0: 'OVERSPD_ENV_NOENV', 1: +// 'OVERSPD_ENV_OVERSPEED_ENV'}, 'precision': 1.0, 'len': 8, 'is_signed_var': +// False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 48, 'type': 'enum', +// 'order': 'intel', 'physical_unit': ''} +Brake_status__511::Overspd_envType Brakestatus511::overspd_env( const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 1); + Byte t0(bytes + 6); + int32_t x = t0.get_byte(0, 8); - Brake_status__511::Brake_light_actualType ret = - static_cast(x); + Brake_status__511::Overspd_envType ret = + static_cast(x); return ret; } } // namespace ch diff --git a/modules/canbus/vehicle/ch/protocol/brake_status__511.h b/modules/canbus/vehicle/ch/protocol/brake_status__511.h new file mode 100644 index 00000000000..cfbb1795701 --- /dev/null +++ b/modules/canbus/vehicle/ch/protocol/brake_status__511.h @@ -0,0 +1,90 @@ +/****************************************************************************** + * 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 "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" +#include "modules/drivers/canbus/can_comm/protocol_data.h" + +namespace apollo { +namespace canbus { +namespace ch { + +class Brakestatus511 : public ::apollo::drivers::canbus::ProtocolData< + ::apollo::canbus::ChassisDetail> { + public: + static const int32_t ID; + Brakestatus511(); + void Parse(const std::uint8_t* bytes, int32_t length, + ChassisDetail* chassis) const override; + + private: + // config detail: {'description': 'brake pedal enable bit(Status)', 'enum': + // {0: 'BRAKE_PEDAL_EN_STS_DISABLE', 1: 'BRAKE_PEDAL_EN_STS_ENABLE', 2: + // 'BRAKE_PEDAL_EN_STS_TAKEOVER'}, 'precision': 1.0, 'len': 8, 'name': + // 'BRAKE_PEDAL_EN_STS', 'is_signed_var': False, 'offset': 0.0, + // 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', 'order': 'intel', + // 'physical_unit': ''} + Brake_status__511::Brake_pedal_en_stsType brake_pedal_en_sts( + const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'description': 'Percentage of brake pedal(Status)', + // 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': 'BRAKE_PEDAL_STS', + // 'is_signed_var': False, 'physical_range': '[0|100]', 'bit': 8, 'type': + // 'int', 'order': 'intel', 'physical_unit': '%'} + int brake_pedal_sts(const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'name': 'BRAKE_ERR', 'enum': {0: 'BRAKE_ERR_NOERR', 1: + // 'BRAKE_ERR_BRAKE_SYSTEM_ERR'}, 'precision': 1.0, 'len': 8, 'is_signed_var': + // False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 16, 'type': 'enum', + // 'order': 'intel', 'physical_unit': ''} + Brake_status__511::Brake_errType brake_err(const std::uint8_t* bytes, + const int32_t length) const; + + // config detail: {'name': 'EMERGENCY_BTN_ENV', 'enum': {0: + // 'EMERGENCY_BTN_ENV_NOENV', 1: 'EMERGENCY_BTN_ENV_EMERGENCY_BUTTON_ENV'}, + // 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'offset': 0.0, + // 'physical_range': '[0|1]', 'bit': 24, 'type': 'enum', 'order': 'intel', + // 'physical_unit': ''} + Brake_status__511::Emergency_btn_envType emergency_btn_env( + const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'name': 'FRONT_BUMP_ENV', 'enum': {0: + // 'FRONT_BUMP_ENV_NOENV', 1: 'FRONT_BUMP_ENV_FRONT_BUMPER_ENV'}, + // 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'offset': 0.0, + // 'physical_range': '[0|1]', 'bit': 32, 'type': 'enum', 'order': 'intel', + // 'physical_unit': ''} + Brake_status__511::Front_bump_envType front_bump_env( + const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'name': 'BACK_BUMP_ENV', 'enum': {0: 'BACK_BUMP_ENV_NOENV', + // 1: 'BACK_BUMP_ENV_BACK_BUMPER_ENV'}, 'precision': 1.0, 'len': 8, + // 'is_signed_var': False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': + // 40, 'type': 'enum', 'order': 'intel', 'physical_unit': ''} + Brake_status__511::Back_bump_envType back_bump_env( + const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'name': 'OVERSPD_ENV', 'enum': {0: 'OVERSPD_ENV_NOENV', 1: + // 'OVERSPD_ENV_OVERSPEED_ENV'}, 'precision': 1.0, 'len': 8, 'is_signed_var': + // False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 48, 'type': 'enum', + // 'order': 'intel', 'physical_unit': ''} + Brake_status__511::Overspd_envType overspd_env(const std::uint8_t* bytes, + const int32_t length) const; +}; + +} // namespace ch +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/brake_status__511_test.cc b/modules/canbus/vehicle/ch/protocol/brake_status__511_test.cc similarity index 74% rename from modules/canbus_vehicle/ch/protocol/brake_status__511_test.cc rename to modules/canbus/vehicle/ch/protocol/brake_status__511_test.cc index da8751117c1..86a9878f462 100644 --- a/modules/canbus_vehicle/ch/protocol/brake_status__511_test.cc +++ b/modules/canbus/vehicle/ch/protocol/brake_status__511_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/brake_status__511.h" +#include "modules/canbus/vehicle/ch/protocol/brake_status__511.h" #include "gtest/gtest.h" namespace apollo { @@ -28,7 +28,7 @@ class Brakestatus511Test : public ::testing::Test { TEST_F(Brakestatus511Test, General) { uint8_t data[8] = {0x01, 0x02, 0x01, 0x00, 0x01, 0x01, 0x00, 0x01}; int32_t length = 8; - Ch cd; + ChassisDetail cd; Brakestatus511 brake; brake.Parse(data, length, &cd); @@ -41,13 +41,13 @@ TEST_F(Brakestatus511Test, General) { EXPECT_EQ(data[6], 0b00000000); EXPECT_EQ(data[7], 0b00000001); - EXPECT_EQ(cd.brake_status__511().brake_pedal_en_sts(), 1); - EXPECT_EQ(cd.brake_status__511().brake_pedal_sts(), 2); - EXPECT_EQ(cd.brake_status__511().brake_err(), 1); - EXPECT_EQ(cd.brake_status__511().emergency_btn_env(), 0); - EXPECT_EQ(cd.brake_status__511().front_bump_env(), 1); - EXPECT_EQ(cd.brake_status__511().back_bump_env(), 1); - EXPECT_EQ(cd.brake_status__511().overspd_env(), 0); + EXPECT_EQ(cd.ch().brake_status__511().brake_pedal_en_sts(), 1); + EXPECT_EQ(cd.ch().brake_status__511().brake_pedal_sts(), 2); + EXPECT_EQ(cd.ch().brake_status__511().brake_err(), 1); + EXPECT_EQ(cd.ch().brake_status__511().emergency_btn_env(), 0); + EXPECT_EQ(cd.ch().brake_status__511().front_bump_env(), 1); + EXPECT_EQ(cd.ch().brake_status__511().back_bump_env(), 1); + EXPECT_EQ(cd.ch().brake_status__511().overspd_env(), 0); } } // namespace ch diff --git a/modules/canbus_vehicle/ch/protocol/control_command_115.cc b/modules/canbus/vehicle/ch/protocol/control_command_115.cc similarity index 97% rename from modules/canbus_vehicle/ch/protocol/control_command_115.cc rename to modules/canbus/vehicle/ch/protocol/control_command_115.cc index 508cb79375f..25a453e400f 100644 --- a/modules/canbus_vehicle/ch/protocol/control_command_115.cc +++ b/modules/canbus/vehicle/ch/protocol/control_command_115.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/control_command_115.h" +#include "modules/canbus/vehicle/ch/protocol/control_command_115.h" #include "modules/drivers/canbus/common/byte.h" namespace apollo { diff --git a/modules/canbus_vehicle/ch/protocol/control_command_115.h b/modules/canbus/vehicle/ch/protocol/control_command_115.h similarity index 94% rename from modules/canbus_vehicle/ch/protocol/control_command_115.h rename to modules/canbus/vehicle/ch/protocol/control_command_115.h index 07d18358971..2d1dbab4a3f 100644 --- a/modules/canbus_vehicle/ch/protocol/control_command_115.h +++ b/modules/canbus/vehicle/ch/protocol/control_command_115.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ch/proto/ch.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace ch { class Controlcommand115 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/ch/protocol/control_command_115_test.cc b/modules/canbus/vehicle/ch/protocol/control_command_115_test.cc similarity index 95% rename from modules/canbus_vehicle/ch/protocol/control_command_115_test.cc rename to modules/canbus/vehicle/ch/protocol/control_command_115_test.cc index 1fe7f829b3f..3e0a8294692 100644 --- a/modules/canbus_vehicle/ch/protocol/control_command_115_test.cc +++ b/modules/canbus/vehicle/ch/protocol/control_command_115_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/control_command_115.h" +#include "modules/canbus/vehicle/ch/protocol/control_command_115.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus/vehicle/ch/protocol/ecu_status_1_515.cc b/modules/canbus/vehicle/ch/protocol/ecu_status_1_515.cc new file mode 100644 index 00000000000..dcd6c9e4d37 --- /dev/null +++ b/modules/canbus/vehicle/ch/protocol/ecu_status_1_515.cc @@ -0,0 +1,133 @@ +/****************************************************************************** + * 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/canbus/vehicle/ch/protocol/ecu_status_1_515.h" +#include "glog/logging.h" +#include "modules/drivers/canbus/common/byte.h" +#include "modules/drivers/canbus/common/canbus_consts.h" + +namespace apollo { +namespace canbus { +namespace ch { + +using ::apollo::drivers::canbus::Byte; + +Ecustatus1515::Ecustatus1515() {} +const int32_t Ecustatus1515::ID = 0x515; + +void Ecustatus1515::Parse(const std::uint8_t* bytes, int32_t length, + ChassisDetail* chassis) const { + chassis->mutable_ch()->mutable_ecu_status_1_515()->set_speed( + speed(bytes, length)); + chassis->mutable_ch()->mutable_ecu_status_1_515()->set_acc_speed( + acc_speed(bytes, length)); + chassis->mutable_ch()->mutable_ecu_status_1_515()->set_ctrl_sts( + ctrl_sts(bytes, length)); + chassis->mutable_ch()->mutable_ecu_status_1_515()->set_chassis_sts( + chassis_sts(bytes, length)); + chassis->mutable_ch()->mutable_ecu_status_1_515()->set_chassis_err( + chassis_err(bytes, length)); +} + +// config detail: {'description': 'Current speed (Steering status)', 'offset': +// 0.0, 'precision': 0.01, 'len': 16, 'name': 'speed', 'is_signed_var': True, +// 'physical_range': '[0|0]', 'bit': 0, 'type': 'double', 'order': 'intel', +// 'physical_unit': 'm/s'} +double Ecustatus1515::speed(const std::uint8_t* bytes, int32_t length) const { + Byte t0(bytes + 1); + int32_t x = t0.get_byte(0, 8); + + Byte t1(bytes + 0); + int32_t t = t1.get_byte(0, 8); + x <<= 8; + x |= t; + + x <<= 16; + x >>= 16; + + double ret = x * 0.010000; + return ret; +} + +// config detail: {'description': 'Current acceleration (Steering status)', +// 'offset': 0.0, 'precision': 0.001, 'len': 16, 'name': 'acc_speed', +// 'is_signed_var': True, 'physical_range': '[0|0]', 'bit': 16, 'type': +// 'double', 'order': 'intel', 'physical_unit': 'm/s^2'} +double Ecustatus1515::acc_speed(const std::uint8_t* bytes, + int32_t length) const { + Byte t0(bytes + 3); + int32_t x = t0.get_byte(0, 8); + + Byte t1(bytes + 2); + int32_t t = t1.get_byte(0, 8); + x <<= 8; + x |= t; + + x <<= 16; + x >>= 16; + + double ret = x * 0.001000; + return ret; +} + +// config detail: {'description': 'Current Auto-mode state (Chassis status)', +// 'enum': {0: 'CTRL_STS_OUT_OF_CONTROL', 1: 'CTRL_STS_UNDER_CONTROL'}, +// 'precision': 1.0, 'len': 8, 'name': 'ctrl_sts', 'is_signed_var': False, +// 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 32, 'type': 'enum', 'order': +// 'intel', 'physical_unit': ''} +Ecu_status_1_515::Ctrl_stsType Ecustatus1515::ctrl_sts( + const std::uint8_t* bytes, int32_t length) const { + Byte t0(bytes + 4); + int32_t x = t0.get_byte(0, 8); + + Ecu_status_1_515::Ctrl_stsType ret = + static_cast(x); + return ret; +} + +// config detail: {'description': 'Current chassis state (Chassis status)', +// 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': 'chassis_sts', +// 'is_signed_var': False, 'physical_range': '[0|255]', 'bit': 40, 'type': +// 'int', 'order': 'intel', 'physical_unit': ''} +int Ecustatus1515::chassis_sts(const std::uint8_t* bytes, + int32_t length) const { + Byte t0(bytes + 5); + int32_t x = t0.get_byte(0, 8); + + int ret = x; + return ret; +} + +// config detail: {'description': 'Chassis error code (Chassis status)', +// 'offset': 0.0, 'precision': 1.0, 'len': 16, 'name': 'chassis_err', +// 'is_signed_var': False, 'physical_range': '[0|65535]', 'bit': 48, 'type': +// 'int', 'order': 'intel', 'physical_unit': ''} +int Ecustatus1515::chassis_err(const std::uint8_t* bytes, + int32_t length) const { + Byte t0(bytes + 7); + int32_t x = t0.get_byte(0, 8); + + Byte t1(bytes + 6); + int32_t t = t1.get_byte(0, 8); + x <<= 8; + x |= t; + + int ret = x; + return ret; +} +} // namespace ch +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus/vehicle/ch/protocol/ecu_status_1_515.h b/modules/canbus/vehicle/ch/protocol/ecu_status_1_515.h new file mode 100644 index 00000000000..958de1d761b --- /dev/null +++ b/modules/canbus/vehicle/ch/protocol/ecu_status_1_515.h @@ -0,0 +1,70 @@ +/****************************************************************************** + * 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 "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" +#include "modules/drivers/canbus/can_comm/protocol_data.h" + +namespace apollo { +namespace canbus { +namespace ch { + +class Ecustatus1515 : public ::apollo::drivers::canbus::ProtocolData< + ::apollo::canbus::ChassisDetail> { + public: + static const int32_t ID; + Ecustatus1515(); + void Parse(const std::uint8_t* bytes, int32_t length, + ChassisDetail* chassis) const override; + + private: + // config detail: {'description': 'Current speed (Steering status)', 'offset': + // 0.0, 'precision': 0.01, 'len': 16, 'name': 'SPEED', 'is_signed_var': True, + // 'physical_range': '[0|0]', 'bit': 0, 'type': 'double', 'order': 'intel', + // 'physical_unit': 'm/s'} + double speed(const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'description': 'Current acceleration (Steering status)', + // 'offset': 0.0, 'precision': 0.001, 'len': 16, 'name': 'ACC_SPEED', + // 'is_signed_var': True, 'physical_range': '[0|0]', 'bit': 16, 'type': + // 'double', 'order': 'intel', 'physical_unit': 'm/s^2'} + double acc_speed(const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'description': 'Current Auto-mode state (Chassis status)', + // 'enum': {0: 'CTRL_STS_OUT_OF_CONTROL', 1: 'CTRL_STS_UNDER_CONTROL'}, + // 'precision': 1.0, 'len': 8, 'name': 'CTRL_STS', 'is_signed_var': False, + // 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 32, 'type': 'enum', + // 'order': 'intel', 'physical_unit': ''} + Ecu_status_1_515::Ctrl_stsType ctrl_sts(const std::uint8_t* bytes, + const int32_t length) const; + + // config detail: {'description': 'Current chassis state (Chassis status)', + // 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': 'CHASSIS_STS', + // 'is_signed_var': False, 'physical_range': '[0|255]', 'bit': 40, 'type': + // 'int', 'order': 'intel', 'physical_unit': ''} + int chassis_sts(const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'description': 'Chassis error code (Chassis status)', + // 'offset': 0.0, 'precision': 1.0, 'len': 16, 'name': 'CHASSIS_ERR', + // 'is_signed_var': False, 'physical_range': '[0|65535]', 'bit': 48, 'type': + // 'int', 'order': 'intel', 'physical_unit': ''} + int chassis_err(const std::uint8_t* bytes, const int32_t length) const; +}; + +} // namespace ch +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/ecu_status_1_515_test.cc b/modules/canbus/vehicle/ch/protocol/ecu_status_1_515_test.cc similarity index 58% rename from modules/canbus_vehicle/ch/protocol/ecu_status_1_515_test.cc rename to modules/canbus/vehicle/ch/protocol/ecu_status_1_515_test.cc index 4115a094663..9aaa246034c 100644 --- a/modules/canbus_vehicle/ch/protocol/ecu_status_1_515_test.cc +++ b/modules/canbus/vehicle/ch/protocol/ecu_status_1_515_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/ecu_status_1_515.h" +#include "modules/canbus/vehicle/ch/protocol/ecu_status_1_515.h" #include "gtest/gtest.h" namespace apollo { @@ -26,9 +26,9 @@ class Ecustatus1515Test : public ::testing::Test { }; TEST_F(Ecustatus1515Test, General) { - uint8_t data[8] = {0x01, 0x02, 0x03, 0x04, 0x01, 0x12, 0x12, 0x14}; + uint8_t data[8] = {0x01, 0x02, 0x03, 0x04, 0x01, 0x12, 0x13, 0x14}; int32_t length = 8; - Ch cd; + ChassisDetail cd; Ecustatus1515 ecustatus; ecustatus.Parse(data, length, &cd); @@ -38,23 +38,14 @@ TEST_F(Ecustatus1515Test, General) { EXPECT_EQ(data[3], 0b00000100); EXPECT_EQ(data[4], 0b00000001); EXPECT_EQ(data[5], 0b00010010); - EXPECT_EQ(data[6], 0b00010010); + EXPECT_EQ(data[6], 0b00010011); EXPECT_EQ(data[7], 0b00010100); - EXPECT_DOUBLE_EQ(cd.ecu_status_1_515().speed(), 5.1299999999999999); - EXPECT_DOUBLE_EQ(cd.ecu_status_1_515().acc_speed(), 1.0269999999999999); - EXPECT_EQ(cd.ecu_status_1_515().ctrl_sts(), 1); - EXPECT_EQ(cd.ecu_status_1_515().chassis_sts(), 18); - EXPECT_EQ(cd.ecu_status_1_515().chassis_err(), 5138); - EXPECT_EQ(cd.ecu_status_1_515().chassis_mcu_err(), 0); - EXPECT_EQ(cd.ecu_status_1_515().chassis_mcu_can(), 0); - EXPECT_EQ(cd.ecu_status_1_515().chassis_hw_lost(), 0); - EXPECT_EQ(cd.ecu_status_1_515().chassis_eps_err(), 0); - EXPECT_EQ(cd.ecu_status_1_515().chassis_eps_can(), 0); - EXPECT_EQ(cd.ecu_status_1_515().chassis_ehb_err(), 1); - EXPECT_EQ(cd.ecu_status_1_515().chassis_ehb_can(), 0); - EXPECT_EQ(cd.ecu_status_1_515().chassis_bms_can(), 0); - EXPECT_EQ(cd.ecu_status_1_515().chassis_ads_err(), 2); + EXPECT_DOUBLE_EQ(cd.ch().ecu_status_1_515().speed(), 5.1299999999999999); + EXPECT_DOUBLE_EQ(cd.ch().ecu_status_1_515().acc_speed(), 1.0269999999999999); + EXPECT_EQ(cd.ch().ecu_status_1_515().ctrl_sts(), 1); + EXPECT_EQ(cd.ch().ecu_status_1_515().chassis_sts(), 18); + EXPECT_EQ(cd.ch().ecu_status_1_515().chassis_err(), 5139); } } // namespace ch diff --git a/modules/canbus_vehicle/ch/protocol/ecu_status_2_516.cc b/modules/canbus/vehicle/ch/protocol/ecu_status_2_516.cc similarity index 88% rename from modules/canbus_vehicle/ch/protocol/ecu_status_2_516.cc rename to modules/canbus/vehicle/ch/protocol/ecu_status_2_516.cc index 60e389b5d46..0aee00650f4 100644 --- a/modules/canbus_vehicle/ch/protocol/ecu_status_2_516.cc +++ b/modules/canbus/vehicle/ch/protocol/ecu_status_2_516.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/ecu_status_2_516.h" +#include "modules/canbus/vehicle/ch/protocol/ecu_status_2_516.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,19 +29,17 @@ Ecustatus2516::Ecustatus2516() {} const int32_t Ecustatus2516::ID = 0x516; void Ecustatus2516::Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const { - chassis->mutable_ecu_status_2_516()->set_battery_soc( + ChassisDetail* chassis) const { + chassis->mutable_ch()->mutable_ecu_status_2_516()->set_battery_soc( battery_soc(bytes, length)); - chassis->mutable_ecu_status_2_516()->set_battery_capacity( + chassis->mutable_ch()->mutable_ecu_status_2_516()->set_battery_capacity( battery_capacity(bytes, length)); - chassis->mutable_ecu_status_2_516()->set_battery_voltage( + chassis->mutable_ch()->mutable_ecu_status_2_516()->set_battery_voltage( battery_voltage(bytes, length)); - chassis->mutable_ecu_status_2_516()->set_battery_current( + chassis->mutable_ch()->mutable_ecu_status_2_516()->set_battery_current( battery_current(bytes, length)); - chassis->mutable_ecu_status_2_516()->set_battery_temperature( + chassis->mutable_ch()->mutable_ecu_status_2_516()->set_battery_temperature( battery_temperature(bytes, length)); - chassis->mutable_ecu_status_2_516()->set_is_battery_soc_low( - battery_soc(bytes, length) <= 15); } // config detail: {'bit': 0, 'description': 'Percentage of battery remaining diff --git a/modules/canbus_vehicle/ch/protocol/ecu_status_2_516.h b/modules/canbus/vehicle/ch/protocol/ecu_status_2_516.h similarity index 94% rename from modules/canbus_vehicle/ch/protocol/ecu_status_2_516.h rename to modules/canbus/vehicle/ch/protocol/ecu_status_2_516.h index 7907a30fbab..19b09dc1a94 100644 --- a/modules/canbus_vehicle/ch/protocol/ecu_status_2_516.h +++ b/modules/canbus/vehicle/ch/protocol/ecu_status_2_516.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ch/proto/ch.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace ch { class Ecustatus2516 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Ecustatus2516(); void Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'bit': 0, 'description': 'Percentage of battery remaining diff --git a/modules/canbus_vehicle/ch/protocol/ecu_status_2_516_test.cc b/modules/canbus/vehicle/ch/protocol/ecu_status_2_516_test.cc similarity index 78% rename from modules/canbus_vehicle/ch/protocol/ecu_status_2_516_test.cc rename to modules/canbus/vehicle/ch/protocol/ecu_status_2_516_test.cc index 719fbad4bf4..54ce74ef725 100644 --- a/modules/canbus_vehicle/ch/protocol/ecu_status_2_516_test.cc +++ b/modules/canbus/vehicle/ch/protocol/ecu_status_2_516_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/ecu_status_2_516.h" +#include "modules/canbus/vehicle/ch/protocol/ecu_status_2_516.h" #include "gtest/gtest.h" namespace apollo { @@ -28,7 +28,7 @@ class Ecustatus2516Test : public ::testing::Test { TEST_F(Ecustatus2516Test, General) { uint8_t data[8] = {0x01, 0x02, 0x03, 0x04, 0x01, 0x12, 0x13, 0x14}; int32_t length = 8; - Ch cd; + ChassisDetail cd; Ecustatus2516 ecustatus; ecustatus.Parse(data, length, &cd); @@ -41,12 +41,12 @@ TEST_F(Ecustatus2516Test, General) { EXPECT_EQ(data[6], 0b00010011); EXPECT_EQ(data[7], 0b00010100); - EXPECT_EQ(cd.ecu_status_2_516().battery_soc(), 1); - EXPECT_EQ(cd.ecu_status_2_516().battery_capacity(), 2); - EXPECT_DOUBLE_EQ(cd.ecu_status_2_516().battery_voltage(), 102.7); - EXPECT_DOUBLE_EQ(cd.ecu_status_2_516().battery_current(), + EXPECT_EQ(cd.ch().ecu_status_2_516().battery_soc(), 1); + EXPECT_EQ(cd.ch().ecu_status_2_516().battery_capacity(), 2); + EXPECT_DOUBLE_EQ(cd.ch().ecu_status_2_516().battery_voltage(), 102.7); + EXPECT_DOUBLE_EQ(cd.ch().ecu_status_2_516().battery_current(), 460.90000000000003); - EXPECT_EQ(cd.ecu_status_2_516().battery_temperature(), 5139); + EXPECT_EQ(cd.ch().ecu_status_2_516().battery_temperature(), 5139); } } // namespace ch diff --git a/modules/canbus/vehicle/ch/protocol/ecu_status_3_517.cc b/modules/canbus/vehicle/ch/protocol/ecu_status_3_517.cc new file mode 100644 index 00000000000..523c247d4cc --- /dev/null +++ b/modules/canbus/vehicle/ch/protocol/ecu_status_3_517.cc @@ -0,0 +1,156 @@ +/****************************************************************************** + * 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/canbus/vehicle/ch/protocol/ecu_status_3_517.h" +#include "glog/logging.h" +#include "modules/drivers/canbus/common/byte.h" +#include "modules/drivers/canbus/common/canbus_consts.h" + +namespace apollo { +namespace canbus { +namespace ch { + +using ::apollo::drivers::canbus::Byte; + +Ecustatus3517::Ecustatus3517() {} +const int32_t Ecustatus3517::ID = 0x517; + +void Ecustatus3517::Parse(const std::uint8_t* bytes, int32_t length, + ChassisDetail* chassis) const { + chassis->mutable_ch()->mutable_ecu_status_3_517()->set_ultrasound_dist_1( + ultrasound_dist_1(bytes, length)); + chassis->mutable_ch()->mutable_ecu_status_3_517()->set_ultrasound_dist_2( + ultrasound_dist_2(bytes, length)); + chassis->mutable_ch()->mutable_ecu_status_3_517()->set_ultrasound_dist_3( + ultrasound_dist_3(bytes, length)); + chassis->mutable_ch()->mutable_ecu_status_3_517()->set_ultrasound_dist_4( + ultrasound_dist_4(bytes, length)); + chassis->mutable_ch()->mutable_ecu_status_3_517()->set_ultrasound_dist_5( + ultrasound_dist_5(bytes, length)); + chassis->mutable_ch()->mutable_ecu_status_3_517()->set_ultrasound_dist_6( + ultrasound_dist_6(bytes, length)); + chassis->mutable_ch()->mutable_ecu_status_3_517()->set_ultrasound_dist_7( + ultrasound_dist_7(bytes, length)); + chassis->mutable_ch()->mutable_ecu_status_3_517()->set_ultrasound_dist_8( + ultrasound_dist_8(bytes, length)); +} + +// config detail: {'description': 'Ultrasonic detection distance 1 (Ultrasound +// status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': +// 'ultrasound_dist_1', 'is_signed_var': False, 'physical_range': '[0|0]', +// 'bit': 0, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} +int Ecustatus3517::ultrasound_dist_1(const std::uint8_t* bytes, + int32_t length) const { + Byte t0(bytes + 0); + int32_t x = t0.get_byte(0, 8); + + int ret = x; + return ret; +} + +// config detail: {'description': 'Ultrasonic detection distance 2 (Ultrasound +// status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': +// 'ultrasound_dist_2', 'is_signed_var': False, 'physical_range': '[0|0]', +// 'bit': 8, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} +int Ecustatus3517::ultrasound_dist_2(const std::uint8_t* bytes, + int32_t length) const { + Byte t0(bytes + 1); + int32_t x = t0.get_byte(0, 8); + + int ret = x; + return ret; +} + +// config detail: {'description': 'Ultrasonic detection distance 3 (Ultrasound +// status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': +// 'ultrasound_dist_3', 'is_signed_var': False, 'physical_range': '[0|0]', +// 'bit': 16, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} +int Ecustatus3517::ultrasound_dist_3(const std::uint8_t* bytes, + int32_t length) const { + Byte t0(bytes + 2); + int32_t x = t0.get_byte(0, 8); + + int ret = x; + return ret; +} + +// config detail: {'description': 'Ultrasonic detection distance 4 (Ultrasound +// status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': +// 'ultrasound_dist_4', 'is_signed_var': False, 'physical_range': '[0|0]', +// 'bit': 24, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} +int Ecustatus3517::ultrasound_dist_4(const std::uint8_t* bytes, + int32_t length) const { + Byte t0(bytes + 3); + int32_t x = t0.get_byte(0, 8); + + int ret = x; + return ret; +} + +// config detail: {'description': 'Ultrasonic detection distance 5 (Ultrasound +// status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': +// 'ultrasound_dist_5', 'is_signed_var': False, 'physical_range': '[0|0]', +// 'bit': 32, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} +int Ecustatus3517::ultrasound_dist_5(const std::uint8_t* bytes, + int32_t length) const { + Byte t0(bytes + 4); + int32_t x = t0.get_byte(0, 8); + + int ret = x; + return ret; +} + +// config detail: {'description': 'Ultrasonic detection distance 6 (Ultrasound +// status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': +// 'ultrasound_dist_6', 'is_signed_var': False, 'physical_range': '[0|0]', +// 'bit': 40, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} +int Ecustatus3517::ultrasound_dist_6(const std::uint8_t* bytes, + int32_t length) const { + Byte t0(bytes + 5); + int32_t x = t0.get_byte(0, 8); + + int ret = x; + return ret; +} + +// config detail: {'description': 'Ultrasonic detection distance 7 (Ultrasound +// status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': +// 'ultrasound_dist_7', 'is_signed_var': False, 'physical_range': '[0|0]', +// 'bit': 48, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} +int Ecustatus3517::ultrasound_dist_7(const std::uint8_t* bytes, + int32_t length) const { + Byte t0(bytes + 6); + int32_t x = t0.get_byte(0, 8); + + int ret = x; + return ret; +} + +// config detail: {'description': 'Ultrasonic detection distance 8 (Ultrasound +// status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': +// 'ultrasound_dist_8', 'is_signed_var': False, 'physical_range': '[0|0]', +// 'bit': 56, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} +int Ecustatus3517::ultrasound_dist_8(const std::uint8_t* bytes, + int32_t length) const { + Byte t0(bytes + 7); + int32_t x = t0.get_byte(0, 8); + + int ret = x; + return ret; +} +} // namespace ch +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus/vehicle/ch/protocol/ecu_status_3_517.h b/modules/canbus/vehicle/ch/protocol/ecu_status_3_517.h new file mode 100644 index 00000000000..ec6d50b75d6 --- /dev/null +++ b/modules/canbus/vehicle/ch/protocol/ecu_status_3_517.h @@ -0,0 +1,86 @@ +/****************************************************************************** + * 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 "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" +#include "modules/drivers/canbus/can_comm/protocol_data.h" + +namespace apollo { +namespace canbus { +namespace ch { + +class Ecustatus3517 : public ::apollo::drivers::canbus::ProtocolData< + ::apollo::canbus::ChassisDetail> { + public: + static const int32_t ID; + Ecustatus3517(); + void Parse(const std::uint8_t* bytes, int32_t length, + ChassisDetail* chassis) const override; + + private: + // config detail: {'description': 'Ultrasonic detection distance 1 (Ultrasound + // status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': + // 'ULTRASOUND_DIST_1', 'is_signed_var': False, 'physical_range': '[0|0]', + // 'bit': 0, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} + int ultrasound_dist_1(const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'description': 'Ultrasonic detection distance 2 (Ultrasound + // status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': + // 'ULTRASOUND_DIST_2', 'is_signed_var': False, 'physical_range': '[0|0]', + // 'bit': 8, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} + int ultrasound_dist_2(const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'description': 'Ultrasonic detection distance 3 (Ultrasound + // status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': + // 'ULTRASOUND_DIST_3', 'is_signed_var': False, 'physical_range': '[0|0]', + // 'bit': 16, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} + int ultrasound_dist_3(const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'description': 'Ultrasonic detection distance 4 (Ultrasound + // status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': + // 'ULTRASOUND_DIST_4', 'is_signed_var': False, 'physical_range': '[0|0]', + // 'bit': 24, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} + int ultrasound_dist_4(const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'description': 'Ultrasonic detection distance 5 (Ultrasound + // status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': + // 'ULTRASOUND_DIST_5', 'is_signed_var': False, 'physical_range': '[0|0]', + // 'bit': 32, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} + int ultrasound_dist_5(const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'description': 'Ultrasonic detection distance 6 (Ultrasound + // status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': + // 'ULTRASOUND_DIST_6', 'is_signed_var': False, 'physical_range': '[0|0]', + // 'bit': 40, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} + int ultrasound_dist_6(const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'description': 'Ultrasonic detection distance 7 (Ultrasound + // status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': + // 'ULTRASOUND_DIST_7', 'is_signed_var': False, 'physical_range': '[0|0]', + // 'bit': 48, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} + int ultrasound_dist_7(const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'description': 'Ultrasonic detection distance 8 (Ultrasound + // status)', 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': + // 'ULTRASOUND_DIST_8', 'is_signed_var': False, 'physical_range': '[0|0]', + // 'bit': 56, 'type': 'int', 'order': 'intel', 'physical_unit': 'cm'} + int ultrasound_dist_8(const std::uint8_t* bytes, const int32_t length) const; +}; + +} // namespace ch +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/ecu_status_3_517_test.cc b/modules/canbus/vehicle/ch/protocol/ecu_status_3_517_test.cc similarity index 71% rename from modules/canbus_vehicle/ch/protocol/ecu_status_3_517_test.cc rename to modules/canbus/vehicle/ch/protocol/ecu_status_3_517_test.cc index 607ad0bbb66..3e25956653d 100644 --- a/modules/canbus_vehicle/ch/protocol/ecu_status_3_517_test.cc +++ b/modules/canbus/vehicle/ch/protocol/ecu_status_3_517_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/ecu_status_3_517.h" +#include "modules/canbus/vehicle/ch/protocol/ecu_status_3_517.h" #include "gtest/gtest.h" namespace apollo { @@ -28,7 +28,7 @@ class Ecustatus3517Test : public ::testing::Test { TEST_F(Ecustatus3517Test, General) { uint8_t data[8] = {0x01, 0x02, 0x03, 0x04, 0x01, 0x12, 0x13, 0x14}; int32_t length = 8; - Ch cd; + ChassisDetail cd; Ecustatus3517 ecustatus; ecustatus.Parse(data, length, &cd); @@ -41,15 +41,14 @@ TEST_F(Ecustatus3517Test, General) { EXPECT_EQ(data[6], 0b00010011); EXPECT_EQ(data[7], 0b00010100); - EXPECT_EQ(cd.ecu_status_3_517().ultrasound_dist_1(), 2); - EXPECT_EQ(cd.ecu_status_3_517().ultrasound_dist_2(), 4); - EXPECT_EQ(cd.ecu_status_3_517().ultrasound_dist_3(), 6); - EXPECT_EQ(cd.ecu_status_3_517().ultrasound_dist_4(), 8); - EXPECT_EQ(cd.ecu_status_3_517().ultrasound_dist_5(), 2); - // todo:// check expect 36 or 18 ? - EXPECT_EQ(cd.ecu_status_3_517().ultrasound_dist_6(), 18); - EXPECT_EQ(cd.ecu_status_3_517().ultrasound_dist_7(), 38); - EXPECT_EQ(cd.ecu_status_3_517().ultrasound_dist_8(), 40); + EXPECT_EQ(cd.ch().ecu_status_3_517().ultrasound_dist_1(), 1); + EXPECT_EQ(cd.ch().ecu_status_3_517().ultrasound_dist_2(), 2); + EXPECT_EQ(cd.ch().ecu_status_3_517().ultrasound_dist_3(), 3); + EXPECT_EQ(cd.ch().ecu_status_3_517().ultrasound_dist_4(), 4); + EXPECT_EQ(cd.ch().ecu_status_3_517().ultrasound_dist_5(), 1); + EXPECT_EQ(cd.ch().ecu_status_3_517().ultrasound_dist_6(), 18); + EXPECT_EQ(cd.ch().ecu_status_3_517().ultrasound_dist_7(), 19); + EXPECT_EQ(cd.ch().ecu_status_3_517().ultrasound_dist_8(), 20); } } // namespace ch diff --git a/modules/canbus_vehicle/ch/protocol/gear_command_114.cc b/modules/canbus/vehicle/ch/protocol/gear_command_114.cc similarity index 80% rename from modules/canbus_vehicle/ch/protocol/gear_command_114.cc rename to modules/canbus/vehicle/ch/protocol/gear_command_114.cc index e23f4f093b5..f835b0b67dc 100644 --- a/modules/canbus_vehicle/ch/protocol/gear_command_114.cc +++ b/modules/canbus/vehicle/ch/protocol/gear_command_114.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/gear_command_114.h" +#include "modules/canbus/vehicle/ch/protocol/gear_command_114.h" #include "modules/drivers/canbus/common/byte.h" namespace apollo { @@ -29,7 +29,7 @@ const int32_t Gearcommand114::ID = 0x114; Gearcommand114::Gearcommand114() { Reset(); } uint32_t Gearcommand114::GetPeriod() const { - // TODO(All) : modify every protocol's period manually + // modify every protocol's period manually static const uint32_t PERIOD = 20 * 1000; return PERIOD; } @@ -39,7 +39,7 @@ void Gearcommand114::UpdateData(uint8_t* data) { } void Gearcommand114::Reset() { - // TODO(All) : you should check this manually + // you should check this manually gear_cmd_ = Gear_command_114::GEAR_CMD_NEUTRAL; } @@ -49,11 +49,11 @@ Gearcommand114* Gearcommand114::set_gear_cmd( return this; } -// config detail: {'bit': 0, 'description': 'PRND control(Command)', 'enum': {1: +// config detail: {'description': 'PRND control(Command)', 'enum': {1: // 'GEAR_CMD_PARK', 2: 'GEAR_CMD_REVERSE', 3: 'GEAR_CMD_NEUTRAL', 4: -// 'GEAR_CMD_DRIVE'}, 'is_signed_var': False, 'len': 8, 'name': 'GEAR_CMD', -// 'offset': 0.0, 'order': 'intel', 'physical_range': '[1|4]', 'physical_unit': -// '', 'precision': 1.0, 'type': 'enum'} +// 'GEAR_CMD_DRIVE'}, 'precision': 1.0, 'len': 8, 'name': 'GEAR_CMD', +// 'is_signed_var': False, 'offset': 0.0, 'physical_range': '[1|4]', 'bit': 0, +// 'type': 'enum', 'order': 'intel', 'physical_unit': ''} void Gearcommand114::set_p_gear_cmd(uint8_t* data, Gear_command_114::Gear_cmdType gear_cmd) { int x = gear_cmd; diff --git a/modules/canbus_vehicle/ch/protocol/gear_command_114.h b/modules/canbus/vehicle/ch/protocol/gear_command_114.h similarity index 62% rename from modules/canbus_vehicle/ch/protocol/gear_command_114.h rename to modules/canbus/vehicle/ch/protocol/gear_command_114.h index 945f3013946..19b29e01435 100644 --- a/modules/canbus_vehicle/ch/protocol/gear_command_114.h +++ b/modules/canbus/vehicle/ch/protocol/gear_command_114.h @@ -16,7 +16,8 @@ #pragma once -#include "modules/canbus_vehicle/ch/proto/ch.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" + #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +25,7 @@ namespace canbus { namespace ch { class Gearcommand114 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -36,19 +37,19 @@ class Gearcommand114 : public ::apollo::drivers::canbus::ProtocolData< void Reset() override; - // config detail: {'bit': 0, 'description': 'PRND control(Command)', 'enum': - // {1: 'GEAR_CMD_PARK', 2: 'GEAR_CMD_REVERSE', 3: 'GEAR_CMD_NEUTRAL', 4: - // 'GEAR_CMD_DRIVE'}, 'is_signed_var': False, 'len': 8, 'name': 'GEAR_CMD', - // 'offset': 0.0, 'order': 'intel', 'physical_range': '[1|4]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + // config detail: {'description': 'PRND control(Command)', 'enum': {1: + // 'GEAR_CMD_PARK', 2: 'GEAR_CMD_REVERSE', 3: 'GEAR_CMD_NEUTRAL', 4: + // 'GEAR_CMD_DRIVE'}, 'precision': 1.0, 'len': 8, 'name': 'GEAR_CMD', + // 'is_signed_var': False, 'offset': 0.0, 'physical_range': '[1|4]', 'bit': 0, + // 'type': 'enum', 'order': 'intel', 'physical_unit': ''} Gearcommand114* set_gear_cmd(Gear_command_114::Gear_cmdType gear_cmd); private: - // config detail: {'bit': 0, 'description': 'PRND control(Command)', 'enum': - // {1: 'GEAR_CMD_PARK', 2: 'GEAR_CMD_REVERSE', 3: 'GEAR_CMD_NEUTRAL', 4: - // 'GEAR_CMD_DRIVE'}, 'is_signed_var': False, 'len': 8, 'name': 'GEAR_CMD', - // 'offset': 0.0, 'order': 'intel', 'physical_range': '[1|4]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + // config detail: {'description': 'PRND control(Command)', 'enum': {1: + // 'GEAR_CMD_PARK', 2: 'GEAR_CMD_REVERSE', 3: 'GEAR_CMD_NEUTRAL', 4: + // 'GEAR_CMD_DRIVE'}, 'precision': 1.0, 'len': 8, 'name': 'GEAR_CMD', + // 'is_signed_var': False, 'offset': 0.0, 'physical_range': '[1|4]', 'bit': 0, + // 'type': 'enum', 'order': 'intel', 'physical_unit': ''} void set_p_gear_cmd(uint8_t* data, Gear_command_114::Gear_cmdType gear_cmd); private: diff --git a/modules/canbus_vehicle/ch/protocol/gear_command_114_test.cc b/modules/canbus/vehicle/ch/protocol/gear_command_114_test.cc similarity index 95% rename from modules/canbus_vehicle/ch/protocol/gear_command_114_test.cc rename to modules/canbus/vehicle/ch/protocol/gear_command_114_test.cc index 256aa7e5f5b..d6f7ef88e65 100644 --- a/modules/canbus_vehicle/ch/protocol/gear_command_114_test.cc +++ b/modules/canbus/vehicle/ch/protocol/gear_command_114_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/gear_command_114.h" +#include "modules/canbus/vehicle/ch/protocol/gear_command_114.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/ch/protocol/gear_status_514.cc b/modules/canbus/vehicle/ch/protocol/gear_status_514.cc similarity index 77% rename from modules/canbus_vehicle/ch/protocol/gear_status_514.cc rename to modules/canbus/vehicle/ch/protocol/gear_status_514.cc index ca1b9266538..a3cb89b316b 100644 --- a/modules/canbus_vehicle/ch/protocol/gear_status_514.cc +++ b/modules/canbus/vehicle/ch/protocol/gear_status_514.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/gear_status_514.h" +#include "modules/canbus/vehicle/ch/protocol/gear_status_514.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,16 +29,16 @@ Gearstatus514::Gearstatus514() {} const int32_t Gearstatus514::ID = 0x514; void Gearstatus514::Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const { - chassis->mutable_gear_status_514()->set_gear_sts( + ChassisDetail* chassis) const { + chassis->mutable_ch()->mutable_gear_status_514()->set_gear_sts( gear_sts(bytes, length)); } -// config detail: {'bit': 0, 'description': 'PRND control(Status)', 'enum': {1: +// config detail: {'description': 'PRND control(Status)', 'enum': {1: // 'GEAR_STS_PARK', 2: 'GEAR_STS_REVERSE', 3: 'GEAR_STS_NEUTRAL', 4: -// 'GEAR_STS_DRIVE'}, 'is_signed_var': False, 'len': 8, 'name': 'gear_sts', -// 'offset': 0.0, 'order': 'intel', 'physical_range': '[1|4]', 'physical_unit': -// '', 'precision': 1.0, 'type': 'enum'} +// 'GEAR_STS_DRIVE'}, 'precision': 1.0, 'len': 8, 'name': 'gear_sts', +// 'is_signed_var': False, 'offset': 0.0, 'physical_range': '[1|4]', 'bit': 0, +// 'type': 'enum', 'order': 'intel', 'physical_unit': ''} Gear_status_514::Gear_stsType Gearstatus514::gear_sts(const std::uint8_t* bytes, int32_t length) const { Byte t0(bytes + 0); diff --git a/modules/canbus_vehicle/ch/protocol/gear_status_514.h b/modules/canbus/vehicle/ch/protocol/gear_status_514.h similarity index 70% rename from modules/canbus_vehicle/ch/protocol/gear_status_514.h rename to modules/canbus/vehicle/ch/protocol/gear_status_514.h index 6a3843098d0..9f2d7a7ca8f 100644 --- a/modules/canbus_vehicle/ch/protocol/gear_status_514.h +++ b/modules/canbus/vehicle/ch/protocol/gear_status_514.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ch/proto/ch.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,19 +24,19 @@ namespace canbus { namespace ch { class Gearstatus514 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Gearstatus514(); void Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const override; + ChassisDetail* chassis) const override; private: - // config detail: {'bit': 0, 'description': 'PRND control(Status)', 'enum': - // {1: 'GEAR_STS_PARK', 2: 'GEAR_STS_REVERSE', 3: 'GEAR_STS_NEUTRAL', 4: - // 'GEAR_STS_DRIVE'}, 'is_signed_var': False, 'len': 8, 'name': 'GEAR_STS', - // 'offset': 0.0, 'order': 'intel', 'physical_range': '[1|4]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + // config detail: {'description': 'PRND control(Status)', 'enum': {1: + // 'GEAR_STS_PARK', 2: 'GEAR_STS_REVERSE', 3: 'GEAR_STS_NEUTRAL', 4: + // 'GEAR_STS_DRIVE'}, 'precision': 1.0, 'len': 8, 'name': 'GEAR_STS', + // 'is_signed_var': False, 'offset': 0.0, 'physical_range': '[1|4]', 'bit': 0, + // 'type': 'enum', 'order': 'intel', 'physical_unit': ''} Gear_status_514::Gear_stsType gear_sts(const std::uint8_t* bytes, const int32_t length) const; }; diff --git a/modules/canbus_vehicle/ch/protocol/gear_status_514_test.cc b/modules/canbus/vehicle/ch/protocol/gear_status_514_test.cc similarity index 91% rename from modules/canbus_vehicle/ch/protocol/gear_status_514_test.cc rename to modules/canbus/vehicle/ch/protocol/gear_status_514_test.cc index f72fdb5e2ad..952c476d9a4 100644 --- a/modules/canbus_vehicle/ch/protocol/gear_status_514_test.cc +++ b/modules/canbus/vehicle/ch/protocol/gear_status_514_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/gear_status_514.h" +#include "modules/canbus/vehicle/ch/protocol/gear_status_514.h" #include "gtest/gtest.h" namespace apollo { @@ -28,7 +28,7 @@ class Gearstatus514Test : public ::testing::Test { TEST_F(Gearstatus514Test, General) { uint8_t data[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; int32_t length = 8; - Ch cd; + ChassisDetail cd; Gearstatus514 gearstatus; gearstatus.Parse(data, length, &cd); @@ -41,7 +41,7 @@ TEST_F(Gearstatus514Test, General) { EXPECT_EQ(data[6], 0b00010011); EXPECT_EQ(data[7], 0b00010100); - EXPECT_EQ(cd.gear_status_514().gear_sts(), 1); + EXPECT_EQ(cd.ch().gear_status_514().gear_sts(), 1); } } // namespace ch diff --git a/modules/canbus_vehicle/ch/protocol/steer_command_112.cc b/modules/canbus/vehicle/ch/protocol/steer_command_112.cc similarity index 76% rename from modules/canbus_vehicle/ch/protocol/steer_command_112.cc rename to modules/canbus/vehicle/ch/protocol/steer_command_112.cc index f9929d3b12f..f20bee3028e 100644 --- a/modules/canbus_vehicle/ch/protocol/steer_command_112.cc +++ b/modules/canbus/vehicle/ch/protocol/steer_command_112.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/steer_command_112.h" +#include "modules/canbus/vehicle/ch/protocol/steer_command_112.h" #include "modules/drivers/canbus/common/byte.h" namespace apollo { @@ -29,7 +29,7 @@ const int32_t Steercommand112::ID = 0x112; Steercommand112::Steercommand112() { Reset(); } uint32_t Steercommand112::GetPeriod() const { - // TODO(All) : modify every protocol's period manually + // modify every protocol's period manually static const uint32_t PERIOD = 20 * 1000; return PERIOD; } @@ -40,7 +40,7 @@ void Steercommand112::UpdateData(uint8_t* data) { } void Steercommand112::Reset() { - // TODO(All) : you should check this manually + // you should check this manually steer_angle_en_ctrl_ = Steer_command_112::STEER_ANGLE_EN_CTRL_DISABLE; steer_angle_cmd_ = 0.0; } @@ -51,11 +51,11 @@ Steercommand112* Steercommand112::set_steer_angle_en_ctrl( return this; } -// config detail: {'bit': 0, 'description': 'steering angle enable -// bit(Command)', 'enum': {0: 'STEER_ANGLE_EN_CTRL_DISABLE', 1: -// 'STEER_ANGLE_EN_CTRL_ENABLE'}, 'is_signed_var': False, 'len': 8, 'name': -// 'STEER_ANGLE_EN_CTRL', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +// config detail: {'description': 'steering angle enable bit(Command)', 'enum': +// {0: 'STEER_ANGLE_EN_CTRL_DISABLE', 1: 'STEER_ANGLE_EN_CTRL_ENABLE'}, +// 'precision': 1.0, 'len': 8, 'name': 'STEER_ANGLE_EN_CTRL', 'is_signed_var': +// False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', +// 'order': 'intel', 'physical_unit': ''} void Steercommand112::set_p_steer_angle_en_ctrl( uint8_t* data, Steer_command_112::Steer_angle_en_ctrlType steer_angle_en_ctrl) { @@ -70,10 +70,10 @@ Steercommand112* Steercommand112::set_steer_angle_cmd(double steer_angle_cmd) { return this; } -// config detail: {'bit': 8, 'description': 'Current steering angle(Command)', -// 'is_signed_var': True, 'len': 16, 'name': 'STEER_ANGLE_CMD', 'offset': 0.0, -// 'order': 'intel', 'physical_range': '[-0.524|0.524]', 'physical_unit': -// 'radian', 'precision': 0.001, 'type': 'double'} +// config detail: {'description': 'Current steering angle(Command)', 'offset': +// 0.0, 'precision': 0.001, 'len': 16, 'name': 'STEER_ANGLE_CMD', +// 'is_signed_var': True, 'physical_range': '[-0.524|0.524]', 'bit': 8, 'type': +// 'double', 'order': 'intel', 'physical_unit': 'radian'} void Steercommand112::set_p_steer_angle_cmd(uint8_t* data, double steer_angle_cmd) { steer_angle_cmd = ProtocolData::BoundedValue(-0.524, 0.524, steer_angle_cmd); diff --git a/modules/canbus_vehicle/ch/protocol/steer_command_112.h b/modules/canbus/vehicle/ch/protocol/steer_command_112.h similarity index 54% rename from modules/canbus_vehicle/ch/protocol/steer_command_112.h rename to modules/canbus/vehicle/ch/protocol/steer_command_112.h index 8ca5ee66639..92b2bb376ed 100644 --- a/modules/canbus_vehicle/ch/protocol/steer_command_112.h +++ b/modules/canbus/vehicle/ch/protocol/steer_command_112.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ch/proto/ch.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace ch { class Steercommand112 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -36,34 +36,36 @@ class Steercommand112 : public ::apollo::drivers::canbus::ProtocolData< void Reset() override; - // config detail: {'bit': 0, 'description': 'steering angle enable - // bit(Command)', 'enum': {0: 'STEER_ANGLE_EN_CTRL_DISABLE', 1: - // 'STEER_ANGLE_EN_CTRL_ENABLE'}, 'is_signed_var': False, 'len': 8, 'name': - // 'STEER_ANGLE_EN_CTRL', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + // config detail: {'description': 'steering angle enable bit(Command)', + // 'enum': {0: 'STEER_ANGLE_EN_CTRL_DISABLE', 1: + // 'STEER_ANGLE_EN_CTRL_ENABLE'}, 'precision': 1.0, 'len': 8, 'name': + // 'STEER_ANGLE_EN_CTRL', 'is_signed_var': False, 'offset': 0.0, + // 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', 'order': 'intel', + // 'physical_unit': ''} Steercommand112* set_steer_angle_en_ctrl( Steer_command_112::Steer_angle_en_ctrlType steer_angle_en_ctrl); - // config detail: {'bit': 8, 'description': 'Current steering angle(Command)', - // 'is_signed_var': True, 'len': 16, 'name': 'STEER_ANGLE_CMD', 'offset': 0.0, - // 'order': 'intel', 'physical_range': '[-0.524|0.524]', 'physical_unit': - // 'radian', 'precision': 0.001, 'type': 'double'} + // config detail: {'description': 'Current steering angle(Command)', 'offset': + // 0.0, 'precision': 0.001, 'len': 16, 'name': 'STEER_ANGLE_CMD', + // 'is_signed_var': True, 'physical_range': '[-0.524|0.524]', 'bit': 8, + // 'type': 'double', 'order': 'intel', 'physical_unit': 'radian'} Steercommand112* set_steer_angle_cmd(double steer_angle_cmd); private: - // config detail: {'bit': 0, 'description': 'steering angle enable - // bit(Command)', 'enum': {0: 'STEER_ANGLE_EN_CTRL_DISABLE', 1: - // 'STEER_ANGLE_EN_CTRL_ENABLE'}, 'is_signed_var': False, 'len': 8, 'name': - // 'STEER_ANGLE_EN_CTRL', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + // config detail: {'description': 'steering angle enable bit(Command)', + // 'enum': {0: 'STEER_ANGLE_EN_CTRL_DISABLE', 1: + // 'STEER_ANGLE_EN_CTRL_ENABLE'}, 'precision': 1.0, 'len': 8, 'name': + // 'STEER_ANGLE_EN_CTRL', 'is_signed_var': False, 'offset': 0.0, + // 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', 'order': 'intel', + // 'physical_unit': ''} void set_p_steer_angle_en_ctrl( uint8_t* data, Steer_command_112::Steer_angle_en_ctrlType steer_angle_en_ctrl); - // config detail: {'bit': 8, 'description': 'Current steering angle(Command)', - // 'is_signed_var': True, 'len': 16, 'name': 'STEER_ANGLE_CMD', 'offset': 0.0, - // 'order': 'intel', 'physical_range': '[-0.524|0.524]', 'physical_unit': - // 'radian', 'precision': 0.001, 'type': 'double'} + // config detail: {'description': 'Current steering angle(Command)', 'offset': + // 0.0, 'precision': 0.001, 'len': 16, 'name': 'STEER_ANGLE_CMD', + // 'is_signed_var': True, 'physical_range': '[-0.524|0.524]', 'bit': 8, + // 'type': 'double', 'order': 'intel', 'physical_unit': 'radian'} void set_p_steer_angle_cmd(uint8_t* data, double steer_angle_cmd); private: diff --git a/modules/canbus_vehicle/ch/protocol/steer_command_112_test.cc b/modules/canbus/vehicle/ch/protocol/steer_command_112_test.cc similarity index 95% rename from modules/canbus_vehicle/ch/protocol/steer_command_112_test.cc rename to modules/canbus/vehicle/ch/protocol/steer_command_112_test.cc index f673921bd96..43c7f19e13c 100644 --- a/modules/canbus_vehicle/ch/protocol/steer_command_112_test.cc +++ b/modules/canbus/vehicle/ch/protocol/steer_command_112_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/steer_command_112.h" +#include "modules/canbus/vehicle/ch/protocol/steer_command_112.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/ch/protocol/steer_status__512.cc b/modules/canbus/vehicle/ch/protocol/steer_status__512.cc similarity index 62% rename from modules/canbus_vehicle/ch/protocol/steer_status__512.cc rename to modules/canbus/vehicle/ch/protocol/steer_status__512.cc index 0e2c5eaf768..7111705e8f9 100644 --- a/modules/canbus_vehicle/ch/protocol/steer_status__512.cc +++ b/modules/canbus/vehicle/ch/protocol/steer_status__512.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/steer_status__512.h" +#include "modules/canbus/vehicle/ch/protocol/steer_status__512.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,24 +29,25 @@ Steerstatus512::Steerstatus512() {} const int32_t Steerstatus512::ID = 0x512; void Steerstatus512::Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const { - chassis->mutable_steer_status__512()->set_steer_angle_en_sts( + ChassisDetail* chassis) const { + chassis->mutable_ch()->mutable_steer_status__512()->set_steer_angle_en_sts( steer_angle_en_sts(bytes, length)); - chassis->mutable_steer_status__512()->set_steer_angle_sts( + chassis->mutable_ch()->mutable_steer_status__512()->set_steer_angle_sts( steer_angle_sts(bytes, length)); - chassis->mutable_steer_status__512()->set_steer_err( + chassis->mutable_ch()->mutable_steer_status__512()->set_steer_err( steer_err(bytes, length)); - chassis->mutable_steer_status__512()->set_sensor_err( + chassis->mutable_ch()->mutable_steer_status__512()->set_sensor_err( sensor_err(bytes, length)); chassis->mutable_check_response()->set_is_eps_online( steer_angle_en_sts(bytes, length) == 1); } -// config detail: {'bit': 0, 'description': 'steering angle enable bit(Status)', -// 'enum': {0: 'STEER_ANGLE_EN_STS_DISABLE', 1: 'STEER_ANGLE_EN_STS_ENABLE', 2: -// 'STEER_ANGLE_EN_STS_TAKEOVER'}, 'is_signed_var': False, 'len': 8, 'name': -// 'steer_angle_en_sts', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|2]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +// config detail: {'description': 'steering angle enable bit(Status)', 'enum': +// {0: 'STEER_ANGLE_EN_STS_DISABLE', 1: 'STEER_ANGLE_EN_STS_ENABLE', 2: +// 'STEER_ANGLE_EN_STS_TAKEOVER'}, 'precision': 1.0, 'len': 8, 'name': +// 'steer_angle_en_sts', 'is_signed_var': False, 'offset': 0.0, +// 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', 'order': 'intel', +// 'physical_unit': ''} Steer_status__512::Steer_angle_en_stsType Steerstatus512::steer_angle_en_sts( const std::uint8_t* bytes, int32_t length) const { Byte t0(bytes + 0); @@ -57,10 +58,10 @@ Steer_status__512::Steer_angle_en_stsType Steerstatus512::steer_angle_en_sts( return ret; } -// config detail: {'bit': 8, 'description': 'Current steering angle(Status)', -// 'is_signed_var': True, 'len': 16, 'name': 'steer_angle_sts', 'offset': 0.0, -// 'order': 'intel', 'physical_range': '[-0.524|0.524]', 'physical_unit': -// 'radian', 'precision': 0.001, 'type': 'double'} +// config detail: {'description': 'Current steering angle(Status)', 'offset': +// 0.0, 'precision': 0.001, 'len': 16, 'name': 'steer_angle_sts', +// 'is_signed_var': True, 'physical_range': '[-0.524|0.524]', 'bit': 8, 'type': +// 'double', 'order': 'intel', 'physical_unit': 'radian'} double Steerstatus512::steer_angle_sts(const std::uint8_t* bytes, int32_t length) const { Byte t0(bytes + 2); @@ -78,10 +79,10 @@ double Steerstatus512::steer_angle_sts(const std::uint8_t* bytes, return ret; } -// config detail: {'bit': 24, 'enum': {0: 'STEER_ERR_NOERR', 1: -// 'STEER_ERR_STEER_MOTOR_ERR'}, 'is_signed_var': False, 'len': 8, 'name': -// 'steer_err', 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|1]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +// config detail: {'name': 'steer_err', 'enum': {0: 'STEER_ERR_NOERR', 1: +// 'STEER_ERR_STEER_MOTOR_ERR'}, 'precision': 1.0, 'len': 8, 'is_signed_var': +// False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 24, 'type': 'enum', +// 'order': 'intel', 'physical_unit': ''} Steer_status__512::Steer_errType Steerstatus512::steer_err( const std::uint8_t* bytes, int32_t length) const { Byte t0(bytes + 3); @@ -92,10 +93,10 @@ Steer_status__512::Steer_errType Steerstatus512::steer_err( return ret; } -// config detail: {'bit': 32, 'enum': {0: 'SENSOR_ERR_NOERR', 1: -// 'SENSOR_ERR_STEER_SENSOR_ERR'}, 'is_signed_var': False, 'len': 8, 'name': -// 'sensor_err', 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|1]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +// config detail: {'name': 'sensor_err', 'enum': {0: 'SENSOR_ERR_NOERR', 1: +// 'SENSOR_ERR_STEER_SENSOR_ERR'}, 'precision': 1.0, 'len': 8, 'is_signed_var': +// False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 32, 'type': 'enum', +// 'order': 'intel', 'physical_unit': ''} Steer_status__512::Sensor_errType Steerstatus512::sensor_err( const std::uint8_t* bytes, int32_t length) const { Byte t0(bytes + 4); diff --git a/modules/canbus_vehicle/ch/protocol/steer_status__512.h b/modules/canbus/vehicle/ch/protocol/steer_status__512.h similarity index 53% rename from modules/canbus_vehicle/ch/protocol/steer_status__512.h rename to modules/canbus/vehicle/ch/protocol/steer_status__512.h index 88f63a0e001..947ce364fa2 100644 --- a/modules/canbus_vehicle/ch/protocol/steer_status__512.h +++ b/modules/canbus/vehicle/ch/protocol/steer_status__512.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ch/proto/ch.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,40 +24,40 @@ namespace canbus { namespace ch { class Steerstatus512 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Steerstatus512(); void Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const override; + ChassisDetail* chassis) const override; private: - // config detail: {'bit': 0, 'description': 'steering angle enable - // bit(Status)', 'enum': {0: 'STEER_ANGLE_EN_STS_DISABLE', 1: - // 'STEER_ANGLE_EN_STS_ENABLE', 2: 'STEER_ANGLE_EN_STS_TAKEOVER'}, - // 'is_signed_var': False, 'len': 8, 'name': 'STEER_ANGLE_EN_STS', 'offset': - // 0.0, 'order': 'intel', 'physical_range': '[0|2]', 'physical_unit': '', - // 'precision': 1.0, 'type': 'enum'} + // config detail: {'description': 'steering angle enable bit(Status)', 'enum': + // {0: 'STEER_ANGLE_EN_STS_DISABLE', 1: 'STEER_ANGLE_EN_STS_ENABLE', 2: + // 'STEER_ANGLE_EN_STS_TAKEOVER'}, 'precision': 1.0, 'len': 8, 'name': + // 'STEER_ANGLE_EN_STS', 'is_signed_var': False, 'offset': 0.0, + // 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', 'order': 'intel', + // 'physical_unit': ''} Steer_status__512::Steer_angle_en_stsType steer_angle_en_sts( const std::uint8_t* bytes, const int32_t length) const; - // config detail: {'bit': 8, 'description': 'Current steering angle(Status)', - // 'is_signed_var': True, 'len': 16, 'name': 'STEER_ANGLE_STS', 'offset': 0.0, - // 'order': 'intel', 'physical_range': '[-0.524|0.524]', 'physical_unit': - // 'radian', 'precision': 0.001, 'type': 'double'} + // config detail: {'description': 'Current steering angle(Status)', 'offset': + // 0.0, 'precision': 0.001, 'len': 16, 'name': 'STEER_ANGLE_STS', + // 'is_signed_var': True, 'physical_range': '[-0.524|0.524]', 'bit': 8, + // 'type': 'double', 'order': 'intel', 'physical_unit': 'radian'} double steer_angle_sts(const std::uint8_t* bytes, const int32_t length) const; - // config detail: {'bit': 24, 'enum': {0: 'STEER_ERR_NOERR', 1: - // 'STEER_ERR_STEER_MOTOR_ERR'}, 'is_signed_var': False, 'len': 8, 'name': - // 'STEER_ERR', 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|1]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + // config detail: {'name': 'STEER_ERR', 'enum': {0: 'STEER_ERR_NOERR', 1: + // 'STEER_ERR_STEER_MOTOR_ERR'}, 'precision': 1.0, 'len': 8, 'is_signed_var': + // False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 24, 'type': 'enum', + // 'order': 'intel', 'physical_unit': ''} Steer_status__512::Steer_errType steer_err(const std::uint8_t* bytes, const int32_t length) const; - // config detail: {'bit': 32, 'enum': {0: 'SENSOR_ERR_NOERR', 1: - // 'SENSOR_ERR_STEER_SENSOR_ERR'}, 'is_signed_var': False, 'len': 8, 'name': - // 'SENSOR_ERR', 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|1]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + // config detail: {'name': 'SENSOR_ERR', 'enum': {0: 'SENSOR_ERR_NOERR', 1: + // 'SENSOR_ERR_STEER_SENSOR_ERR'}, 'precision': 1.0, 'len': 8, + // 'is_signed_var': False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': + // 32, 'type': 'enum', 'order': 'intel', 'physical_unit': ''} Steer_status__512::Sensor_errType sensor_err(const std::uint8_t* bytes, const int32_t length) const; }; diff --git a/modules/canbus_vehicle/ch/protocol/steer_status__512_test.cc b/modules/canbus/vehicle/ch/protocol/steer_status__512_test.cc similarity index 82% rename from modules/canbus_vehicle/ch/protocol/steer_status__512_test.cc rename to modules/canbus/vehicle/ch/protocol/steer_status__512_test.cc index 3b80611a2d8..3c8a705640c 100644 --- a/modules/canbus_vehicle/ch/protocol/steer_status__512_test.cc +++ b/modules/canbus/vehicle/ch/protocol/steer_status__512_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/steer_status__512.h" +#include "modules/canbus/vehicle/ch/protocol/steer_status__512.h" #include "gtest/gtest.h" namespace apollo { @@ -28,7 +28,7 @@ class Steerstatus512Test : public ::testing::Test { TEST_F(Steerstatus512Test, General) { uint8_t data[8] = {0x01, 0x02, 0x03, 0x01, 0x00, 0x12, 0x13, 0x14}; int32_t length = 8; - Ch cd; + ChassisDetail cd; Steerstatus512 steerstatus; steerstatus.Parse(data, length, &cd); @@ -41,11 +41,11 @@ TEST_F(Steerstatus512Test, General) { EXPECT_EQ(data[6], 0b00010011); EXPECT_EQ(data[7], 0b00010100); - EXPECT_EQ(cd.steer_status__512().steer_angle_en_sts(), 1); - EXPECT_DOUBLE_EQ(cd.steer_status__512().steer_angle_sts(), + EXPECT_EQ(cd.ch().steer_status__512().steer_angle_en_sts(), 1); + EXPECT_DOUBLE_EQ(cd.ch().steer_status__512().steer_angle_sts(), 0.77000000000000002); - EXPECT_EQ(cd.steer_status__512().steer_err(), 1); - EXPECT_EQ(cd.steer_status__512().sensor_err(), 0); + EXPECT_EQ(cd.ch().steer_status__512().steer_err(), 1); + EXPECT_EQ(cd.ch().steer_status__512().sensor_err(), 0); } } // namespace ch diff --git a/modules/canbus_vehicle/ch/protocol/throttle_command_110.cc b/modules/canbus/vehicle/ch/protocol/throttle_command_110.cc similarity index 75% rename from modules/canbus_vehicle/ch/protocol/throttle_command_110.cc rename to modules/canbus/vehicle/ch/protocol/throttle_command_110.cc index 6d4a03dd006..9e98ad9018d 100644 --- a/modules/canbus_vehicle/ch/protocol/throttle_command_110.cc +++ b/modules/canbus/vehicle/ch/protocol/throttle_command_110.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/throttle_command_110.h" +#include "modules/canbus/vehicle/ch/protocol/throttle_command_110.h" #include "modules/drivers/canbus/common/byte.h" namespace apollo { @@ -29,7 +29,7 @@ const int32_t Throttlecommand110::ID = 0x110; Throttlecommand110::Throttlecommand110() { Reset(); } uint32_t Throttlecommand110::GetPeriod() const { - // TODO(All) : modify every protocol's period manually + // modify every protocol's period manually static const uint32_t PERIOD = 20 * 1000; return PERIOD; } @@ -40,7 +40,7 @@ void Throttlecommand110::UpdateData(uint8_t* data) { } void Throttlecommand110::Reset() { - // TODO(All) : you should check this manually + // you should check this manually throttle_pedal_en_ctrl_ = Throttle_command_110::THROTTLE_PEDAL_EN_CTRL_DISABLE; throttle_pedal_cmd_ = 0; @@ -52,11 +52,11 @@ Throttlecommand110* Throttlecommand110::set_throttle_pedal_en_ctrl( return this; } -// config detail: {'bit': 0, 'description': 'throttle pedal enable -// bit(Command)', 'enum': {0: 'THROTTLE_PEDAL_EN_CTRL_DISABLE', 1: -// 'THROTTLE_PEDAL_EN_CTRL_ENABLE'}, 'is_signed_var': False, 'len': 8, 'name': -// 'THROTTLE_PEDAL_EN_CTRL', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +// config detail: {'description': 'throttle pedal enable bit(Command)', 'enum': +// {0: 'THROTTLE_PEDAL_EN_CTRL_DISABLE', 1: 'THROTTLE_PEDAL_EN_CTRL_ENABLE'}, +// 'precision': 1.0, 'len': 8, 'name': 'THROTTLE_PEDAL_EN_CTRL', +// 'is_signed_var': False, 'offset': 0.0, 'physical_range': '[0|1]', 'bit': 0, +// 'type': 'enum', 'order': 'intel', 'physical_unit': ''} void Throttlecommand110::set_p_throttle_pedal_en_ctrl( uint8_t* data, Throttle_command_110::Throttle_pedal_en_ctrlType throttle_pedal_en_ctrl) { @@ -72,10 +72,10 @@ Throttlecommand110* Throttlecommand110::set_throttle_pedal_cmd( return this; } -// config detail: {'bit': 8, 'description': 'Percentage of throttle -// pedal(Command)', 'is_signed_var': False, 'len': 8, 'name': -// 'THROTTLE_PEDAL_CMD', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|100]', 'physical_unit': '%', 'precision': 1.0, 'type': 'int'} +// config detail: {'description': 'Percentage of throttle pedal(Command)', +// 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': 'THROTTLE_PEDAL_CMD', +// 'is_signed_var': False, 'physical_range': '[0|100]', 'bit': 8, 'type': 'int', +// 'order': 'intel', 'physical_unit': '%'} void Throttlecommand110::set_p_throttle_pedal_cmd(uint8_t* data, int throttle_pedal_cmd) { throttle_pedal_cmd = ProtocolData::BoundedValue(0, 100, throttle_pedal_cmd); diff --git a/modules/canbus_vehicle/ch/protocol/throttle_command_110.h b/modules/canbus/vehicle/ch/protocol/throttle_command_110.h similarity index 54% rename from modules/canbus_vehicle/ch/protocol/throttle_command_110.h rename to modules/canbus/vehicle/ch/protocol/throttle_command_110.h index 14ea87b179b..1a114c97e04 100644 --- a/modules/canbus_vehicle/ch/protocol/throttle_command_110.h +++ b/modules/canbus/vehicle/ch/protocol/throttle_command_110.h @@ -16,8 +16,7 @@ #pragma once - -#include "modules/canbus_vehicle/ch/proto/ch.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,7 +24,7 @@ namespace canbus { namespace ch { class Throttlecommand110 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -37,36 +36,36 @@ class Throttlecommand110 : public ::apollo::drivers::canbus::ProtocolData< void Reset() override; - // config detail: {'bit': 0, 'description': 'throttle pedal enable - // bit(Command)', 'enum': {0: 'THROTTLE_PEDAL_EN_CTRL_DISABLE', 1: - // 'THROTTLE_PEDAL_EN_CTRL_ENABLE'}, 'is_signed_var': False, 'len': 8, 'name': - // 'THROTTLE_PEDAL_EN_CTRL', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} + // config detail: {'description': 'throttle pedal enable bit(Command)', + // 'enum': {0: 'THROTTLE_PEDAL_EN_CTRL_DISABLE', 1: + // 'THROTTLE_PEDAL_EN_CTRL_ENABLE'}, 'precision': 1.0, 'len': 8, 'name': + // 'THROTTLE_PEDAL_EN_CTRL', 'is_signed_var': False, 'offset': 0.0, + // 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', 'order': 'intel', + // 'physical_unit': ''} Throttlecommand110* set_throttle_pedal_en_ctrl( Throttle_command_110::Throttle_pedal_en_ctrlType throttle_pedal_en_ctrl); - // config detail: {'bit': 8, 'description': 'Percentage of throttle - // pedal(Command)', 'is_signed_var': False, 'len': 8, 'name': - // 'THROTTLE_PEDAL_CMD', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|100]', 'physical_unit': '%', 'precision': 1.0, 'type': 'int'} + // config detail: {'description': 'Percentage of throttle pedal(Command)', + // 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': 'THROTTLE_PEDAL_CMD', + // 'is_signed_var': False, 'physical_range': '[0|100]', 'bit': 8, 'type': + // 'int', 'order': 'intel', 'physical_unit': '%'} Throttlecommand110* set_throttle_pedal_cmd(int throttle_pedal_cmd); private: - // config detail: {'bit': 0, 'description': 'throttle pedal enable - // bit(Command)', 'enum': {0: 'THROTTLE_PEDAL_EN_CTRL_DISABLE', 1: - // 'THROTTLE_PEDAL_EN_CTRL_ENABLE'}, 'is_signed_var': False, 'len': 8, 'name': - // 'THROTTLE_PEDAL_EN_CTRL', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} + // config detail: {'description': 'throttle pedal enable bit(Command)', + // 'enum': {0: 'THROTTLE_PEDAL_EN_CTRL_DISABLE', 1: + // 'THROTTLE_PEDAL_EN_CTRL_ENABLE'}, 'precision': 1.0, 'len': 8, 'name': + // 'THROTTLE_PEDAL_EN_CTRL', 'is_signed_var': False, 'offset': 0.0, + // 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', 'order': 'intel', + // 'physical_unit': ''} void set_p_throttle_pedal_en_ctrl( uint8_t* data, Throttle_command_110::Throttle_pedal_en_ctrlType throttle_pedal_en_ctrl); - // config detail: {'bit': 8, 'description': 'Percentage of throttle - // pedal(Command)', 'is_signed_var': False, 'len': 8, 'name': - // 'THROTTLE_PEDAL_CMD', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|100]', 'physical_unit': '%', 'precision': 1.0, 'type': 'int'} + // config detail: {'description': 'Percentage of throttle pedal(Command)', + // 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': 'THROTTLE_PEDAL_CMD', + // 'is_signed_var': False, 'physical_range': '[0|100]', 'bit': 8, 'type': + // 'int', 'order': 'intel', 'physical_unit': '%'} void set_p_throttle_pedal_cmd(uint8_t* data, int throttle_pedal_cmd); private: diff --git a/modules/canbus_vehicle/ch/protocol/throttle_command_110_test.cc b/modules/canbus/vehicle/ch/protocol/throttle_command_110_test.cc similarity index 95% rename from modules/canbus_vehicle/ch/protocol/throttle_command_110_test.cc rename to modules/canbus/vehicle/ch/protocol/throttle_command_110_test.cc index 67449dbb3c7..2e6df48ce64 100644 --- a/modules/canbus_vehicle/ch/protocol/throttle_command_110_test.cc +++ b/modules/canbus/vehicle/ch/protocol/throttle_command_110_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/throttle_command_110.h" +#include "modules/canbus/vehicle/ch/protocol/throttle_command_110.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/ch/protocol/throttle_status__510.cc b/modules/canbus/vehicle/ch/protocol/throttle_status__510.cc similarity index 72% rename from modules/canbus_vehicle/ch/protocol/throttle_status__510.cc rename to modules/canbus/vehicle/ch/protocol/throttle_status__510.cc index 437b50f1dbf..5ed200ad8f9 100644 --- a/modules/canbus_vehicle/ch/protocol/throttle_status__510.cc +++ b/modules/canbus/vehicle/ch/protocol/throttle_status__510.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/throttle_status__510.h" +#include "modules/canbus/vehicle/ch/protocol/throttle_status__510.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,15 +29,15 @@ Throttlestatus510::Throttlestatus510() {} const int32_t Throttlestatus510::ID = 0x510; void Throttlestatus510::Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const { - chassis + ChassisDetail* chassis) const { + chassis->mutable_ch() ->mutable_throttle_status__510() ->set_throttle_pedal_en_sts(throttle_pedal_en_sts(bytes, length)); - chassis->mutable_throttle_status__510()->set_throttle_pedal_sts( + chassis->mutable_ch()->mutable_throttle_status__510()->set_throttle_pedal_sts( throttle_pedal_sts(bytes, length)); - chassis->mutable_throttle_status__510()->set_drive_motor_err( + chassis->mutable_ch()->mutable_throttle_status__510()->set_drive_motor_err( drive_motor_err(bytes, length)); - chassis->mutable_throttle_status__510()->set_battery_bms_err( + chassis->mutable_ch()->mutable_throttle_status__510()->set_battery_bms_err( battery_bms_err(bytes, length)); chassis->mutable_check_response()->set_is_vcu_online( throttle_pedal_en_sts(bytes, length) == 1); @@ -60,10 +60,10 @@ Throttlestatus510::throttle_pedal_en_sts(const std::uint8_t* bytes, return ret; } -// config detail: {'bit': 8, 'description': 'Percentage of throttle -// pedal(Status)', 'is_signed_var': False, 'len': 8, 'name': -// 'throttle_pedal_sts', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|100]', 'physical_unit': '%', 'precision': 1.0, 'type': 'int'} +// config detail: {'description': 'Percentage of throttle pedal(Status)', +// 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': 'throttle_pedal_sts', +// 'is_signed_var': False, 'physical_range': '[0|100]', 'bit': 8, 'type': 'int', +// 'order': 'intel', 'physical_unit': '%'} int Throttlestatus510::throttle_pedal_sts(const std::uint8_t* bytes, int32_t length) const { Byte t0(bytes + 1); @@ -73,10 +73,11 @@ int Throttlestatus510::throttle_pedal_sts(const std::uint8_t* bytes, return ret; } -// config detail: {'bit': 16, 'enum': {0: 'DRIVE_MOTOR_ERR_NOERR', 1: -// 'DRIVE_MOTOR_ERR_DRV_MOTOR_ERR'}, 'is_signed_var': False, 'len': 8, 'name': -// 'drive_motor_err', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +// config detail: {'name': 'drive_motor_err', 'enum': {0: +// 'DRIVE_MOTOR_ERR_NOERR', 1: 'DRIVE_MOTOR_ERR_DRV_MOTOR_ERR'}, +// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'offset': 0.0, +// 'physical_range': '[0|1]', 'bit': 16, 'type': 'enum', 'order': 'intel', +// 'physical_unit': ''} Throttle_status__510::Drive_motor_errType Throttlestatus510::drive_motor_err( const std::uint8_t* bytes, int32_t length) const { Byte t0(bytes + 2); @@ -87,10 +88,10 @@ Throttle_status__510::Drive_motor_errType Throttlestatus510::drive_motor_err( return ret; } -// config detail: {'bit': 24, 'enum': {0: 'BATTERY_BMS_ERR_NOERR', 1: -// 'BATTERY_BMS_ERR_BATTERY_ERR'}, 'is_signed_var': False, 'len': 8, 'name': -// 'battery_bms_err', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +// config detail: {'name': 'battery_bms_err', 'enum': {0: +// 'BATTERY_BMS_ERR_NOERR', 1: 'BATTERY_BMS_ERR_BATTERY_ERR'}, 'precision': 1.0, +// 'len': 8, 'is_signed_var': False, 'offset': 0.0, 'physical_range': '[0|1]', +// 'bit': 24, 'type': 'enum', 'order': 'intel', 'physical_unit': ''} Throttle_status__510::Battery_bms_errType Throttlestatus510::battery_bms_err( const std::uint8_t* bytes, int32_t length) const { Byte t0(bytes + 3); diff --git a/modules/canbus_vehicle/ch/protocol/throttle_status__510.h b/modules/canbus/vehicle/ch/protocol/throttle_status__510.h similarity index 52% rename from modules/canbus_vehicle/ch/protocol/throttle_status__510.h rename to modules/canbus/vehicle/ch/protocol/throttle_status__510.h index da07f9be894..c94444b1330 100644 --- a/modules/canbus_vehicle/ch/protocol/throttle_status__510.h +++ b/modules/canbus/vehicle/ch/protocol/throttle_status__510.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ch/proto/ch.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,40 +24,42 @@ namespace canbus { namespace ch { class Throttlestatus510 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Throttlestatus510(); void Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const override; + ChassisDetail* chassis) const override; private: - // config detail: {'bit': 0, 'description': 'throttle pedal enable - // bit(Status)', 'enum': {0: 'THROTTLE_PEDAL_EN_STS_DISABLE', 1: - // 'THROTTLE_PEDAL_EN_STS_ENABLE', 2: 'THROTTLE_PEDAL_EN_STS_TAKEOVER'}, - // 'is_signed_var': False, 'len': 8, 'name': 'THROTTLE_PEDAL_EN_STS', - // 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|2]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + // config detail: {'description': 'throttle pedal enable bit(Status)', 'enum': + // {0: 'THROTTLE_PEDAL_EN_STS_DISABLE', 1: 'THROTTLE_PEDAL_EN_STS_ENABLE', 2: + // 'THROTTLE_PEDAL_EN_STS_TAKEOVER'}, 'precision': 1.0, 'len': 8, 'name': + // 'THROTTLE_PEDAL_EN_STS', 'is_signed_var': False, 'offset': 0.0, + // 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', 'order': 'intel', + // 'physical_unit': ''} Throttle_status__510::Throttle_pedal_en_stsType throttle_pedal_en_sts( const std::uint8_t* bytes, const int32_t length) const; - // config detail: {'bit': 8, 'description': 'Percentage of throttle - // pedal(Status)', 'is_signed_var': False, 'len': 8, 'name': - // 'THROTTLE_PEDAL_STS', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|100]', 'physical_unit': '%', 'precision': 1.0, 'type': 'int'} + // config detail: {'description': 'Percentage of throttle pedal(Status)', + // 'offset': 0.0, 'precision': 1.0, 'len': 8, 'name': 'THROTTLE_PEDAL_STS', + // 'is_signed_var': False, 'physical_range': '[0|100]', 'bit': 8, 'type': + // 'int', 'order': 'intel', 'physical_unit': '%'} int throttle_pedal_sts(const std::uint8_t* bytes, const int32_t length) const; - // config detail: {'bit': 16, 'enum': {0: 'DRIVE_MOTOR_ERR_NOERR', 1: - // 'DRIVE_MOTOR_ERR_DRV_MOTOR_ERR'}, 'is_signed_var': False, 'len': 8, 'name': - // 'DRIVE_MOTOR_ERR', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + // config detail: {'name': 'DRIVE_MOTOR_ERR', 'enum': {0: + // 'DRIVE_MOTOR_ERR_NOERR', 1: 'DRIVE_MOTOR_ERR_DRV_MOTOR_ERR'}, + // 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'offset': 0.0, + // 'physical_range': '[0|1]', 'bit': 16, 'type': 'enum', 'order': 'intel', + // 'physical_unit': ''} Throttle_status__510::Drive_motor_errType drive_motor_err( const std::uint8_t* bytes, const int32_t length) const; - // config detail: {'bit': 24, 'enum': {0: 'BATTERY_BMS_ERR_NOERR', 1: - // 'BATTERY_BMS_ERR_BATTERY_ERR'}, 'is_signed_var': False, 'len': 8, 'name': - // 'BATTERY_BMS_ERR', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + // config detail: {'name': 'BATTERY_BMS_ERR', 'enum': {0: + // 'BATTERY_BMS_ERR_NOERR', 1: 'BATTERY_BMS_ERR_BATTERY_ERR'}, + // 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'offset': 0.0, + // 'physical_range': '[0|1]', 'bit': 24, 'type': 'enum', 'order': 'intel', + // 'physical_unit': ''} Throttle_status__510::Battery_bms_errType battery_bms_err( const std::uint8_t* bytes, const int32_t length) const; }; diff --git a/modules/canbus_vehicle/ch/protocol/throttle_status__510_test.cc b/modules/canbus/vehicle/ch/protocol/throttle_status__510_test.cc similarity index 80% rename from modules/canbus_vehicle/ch/protocol/throttle_status__510_test.cc rename to modules/canbus/vehicle/ch/protocol/throttle_status__510_test.cc index 1937f093bb5..dac84d6adc0 100644 --- a/modules/canbus_vehicle/ch/protocol/throttle_status__510_test.cc +++ b/modules/canbus/vehicle/ch/protocol/throttle_status__510_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/throttle_status__510.h" +#include "modules/canbus/vehicle/ch/protocol/throttle_status__510.h" #include "gtest/gtest.h" namespace apollo { @@ -28,7 +28,7 @@ class Throttlestatus510Test : public ::testing::Test { TEST_F(Throttlestatus510Test, General) { uint8_t data[8] = {0x01, 0x02, 0x01, 0x00, 0x11, 0x12, 0x13, 0x14}; int32_t length = 8; - Ch cd; + ChassisDetail cd; Throttlestatus510 throttlestatus; throttlestatus.Parse(data, length, &cd); @@ -41,10 +41,10 @@ TEST_F(Throttlestatus510Test, General) { EXPECT_EQ(data[6], 0b00010011); EXPECT_EQ(data[7], 0b00010100); - EXPECT_EQ(cd.throttle_status__510().throttle_pedal_en_sts(), 1); - EXPECT_EQ(cd.throttle_status__510().throttle_pedal_sts(), 2); - EXPECT_EQ(cd.throttle_status__510().drive_motor_err(), 1); - EXPECT_EQ(cd.throttle_status__510().battery_bms_err(), 0); + EXPECT_EQ(cd.ch().throttle_status__510().throttle_pedal_en_sts(), 1); + EXPECT_EQ(cd.ch().throttle_status__510().throttle_pedal_sts(), 2); + EXPECT_EQ(cd.ch().throttle_status__510().drive_motor_err(), 1); + EXPECT_EQ(cd.ch().throttle_status__510().battery_bms_err(), 0); } } // namespace ch diff --git a/modules/canbus_vehicle/ch/protocol/turnsignal_command_113.cc b/modules/canbus/vehicle/ch/protocol/turnsignal_command_113.cc similarity index 57% rename from modules/canbus_vehicle/ch/protocol/turnsignal_command_113.cc rename to modules/canbus/vehicle/ch/protocol/turnsignal_command_113.cc index a63c892bad9..1016a5039fc 100644 --- a/modules/canbus_vehicle/ch/protocol/turnsignal_command_113.cc +++ b/modules/canbus/vehicle/ch/protocol/turnsignal_command_113.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/turnsignal_command_113.h" +#include "modules/canbus/vehicle/ch/protocol/turnsignal_command_113.h" #include "modules/drivers/canbus/common/byte.h" namespace apollo { @@ -29,20 +29,18 @@ const int32_t Turnsignalcommand113::ID = 0x113; Turnsignalcommand113::Turnsignalcommand113() { Reset(); } uint32_t Turnsignalcommand113::GetPeriod() const { - // TODO(All) : modify every protocol's period manually + // modify every protocol's period manually static const uint32_t PERIOD = 20 * 1000; return PERIOD; } void Turnsignalcommand113::UpdateData(uint8_t* data) { set_p_turn_signal_cmd(data, turn_signal_cmd_); - set_p_low_beam_cmd(data, low_beam_cmd_); } void Turnsignalcommand113::Reset() { - // TODO(All) : you should check this manually + // you should check this manually turn_signal_cmd_ = Turnsignal_command_113::TURN_SIGNAL_CMD_NONE; - low_beam_cmd_ = Turnsignal_command_113::LOW_BEAM_CMD_OFF; } Turnsignalcommand113* Turnsignalcommand113::set_turn_signal_cmd( @@ -51,12 +49,11 @@ Turnsignalcommand113* Turnsignalcommand113::set_turn_signal_cmd( return this; } -// config detail: {'bit': 0, 'description': 'Lighting control(Command)', 'enum': -// {0: 'TURN_SIGNAL_CMD_NONE', 1: 'TURN_SIGNAL_CMD_LEFT', 2: -// 'TURN_SIGNAL_CMD_RIGHT', 3: 'TURN_SIGNAL_CMD_HAZARD_WARNING_LAMPSTS'}, -// 'is_signed_var': False, 'len': 8, 'name': 'TURN_SIGNAL_CMD', 'offset': 0.0, -// 'order': 'intel', 'physical_range': '[0|2]', 'physical_unit': '', -// 'precision': 1.0, 'type': 'enum'} +// config detail: {'description': 'Lighting control(Command)', 'enum': {0: +// 'TURN_SIGNAL_CMD_NONE', 1: 'TURN_SIGNAL_CMD_LEFT', 2: +// 'TURN_SIGNAL_CMD_RIGHT'}, 'precision': 1.0, 'len': 8, 'name': +// 'TURN_SIGNAL_CMD', 'is_signed_var': False, 'offset': 0.0, 'physical_range': +// '[0|2]', 'bit': 0, 'type': 'enum', 'order': 'intel', 'physical_unit': ''} void Turnsignalcommand113::set_p_turn_signal_cmd( uint8_t* data, Turnsignal_command_113::Turn_signal_cmdType turn_signal_cmd) { @@ -66,23 +63,6 @@ void Turnsignalcommand113::set_p_turn_signal_cmd( to_set.set_value(static_cast(x), 0, 8); } -Turnsignalcommand113* Turnsignalcommand113::set_low_beam_cmd( - Turnsignal_command_113::Low_beam_cmdType low_beam_cmd) { - low_beam_cmd_ = low_beam_cmd; - return this; -} - -// config detail: {'bit': 8, 'description': 'Lighting control(Command)', 'enum': -// {0: 'LOW_BEAM_CMD_OFF', 1: 'LOW_BEAM_CMD_ON'}, 'is_signed_var': False, 'len': -// 2, 'name': 'LOW_BEAM_CMD', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|2]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -void Turnsignalcommand113::set_p_low_beam_cmd( - uint8_t* data, Turnsignal_command_113::Low_beam_cmdType low_beam_cmd) { - int x = low_beam_cmd; - - Byte to_set(data + 1); - to_set.set_value(static_cast(x), 0, 2); -} } // namespace ch } // namespace canbus } // namespace apollo diff --git a/modules/canbus/vehicle/ch/protocol/turnsignal_command_113.h b/modules/canbus/vehicle/ch/protocol/turnsignal_command_113.h new file mode 100644 index 00000000000..7d2496f8334 --- /dev/null +++ b/modules/canbus/vehicle/ch/protocol/turnsignal_command_113.h @@ -0,0 +1,63 @@ +/****************************************************************************** + * 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 "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" +#include "modules/drivers/canbus/can_comm/protocol_data.h" + +namespace apollo { +namespace canbus { +namespace ch { + +class Turnsignalcommand113 : public ::apollo::drivers::canbus::ProtocolData< + ::apollo::canbus::ChassisDetail> { + public: + static const int32_t ID; + + Turnsignalcommand113(); + + uint32_t GetPeriod() const override; + + void UpdateData(uint8_t* data) override; + + void Reset() override; + + // config detail: {'description': 'Lighting control(Command)', 'enum': {0: + // 'TURN_SIGNAL_CMD_NONE', 1: 'TURN_SIGNAL_CMD_LEFT', 2: + // 'TURN_SIGNAL_CMD_RIGHT'}, 'precision': 1.0, 'len': 8, 'name': + // 'TURN_SIGNAL_CMD', 'is_signed_var': False, 'offset': 0.0, 'physical_range': + // '[0|2]', 'bit': 0, 'type': 'enum', 'order': 'intel', 'physical_unit': ''} + Turnsignalcommand113* set_turn_signal_cmd( + Turnsignal_command_113::Turn_signal_cmdType turn_signal_cmd); + + private: + // config detail: {'description': 'Lighting control(Command)', 'enum': {0: + // 'TURN_SIGNAL_CMD_NONE', 1: 'TURN_SIGNAL_CMD_LEFT', 2: + // 'TURN_SIGNAL_CMD_RIGHT'}, 'precision': 1.0, 'len': 8, 'name': + // 'TURN_SIGNAL_CMD', 'is_signed_var': False, 'offset': 0.0, 'physical_range': + // '[0|2]', 'bit': 0, 'type': 'enum', 'order': 'intel', 'physical_unit': ''} + void set_p_turn_signal_cmd( + uint8_t* data, + Turnsignal_command_113::Turn_signal_cmdType turn_signal_cmd); + + private: + Turnsignal_command_113::Turn_signal_cmdType turn_signal_cmd_; +}; + +} // namespace ch +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/turnsignal_command_113_test.cc b/modules/canbus/vehicle/ch/protocol/turnsignal_command_113_test.cc similarity index 93% rename from modules/canbus_vehicle/ch/protocol/turnsignal_command_113_test.cc rename to modules/canbus/vehicle/ch/protocol/turnsignal_command_113_test.cc index 468e7bbfbf2..0394c5ebbb0 100644 --- a/modules/canbus_vehicle/ch/protocol/turnsignal_command_113_test.cc +++ b/modules/canbus/vehicle/ch/protocol/turnsignal_command_113_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/turnsignal_command_113.h" +#include "modules/canbus/vehicle/ch/protocol/turnsignal_command_113.h" #include "gtest/gtest.h" namespace apollo { @@ -31,7 +31,7 @@ TEST_F(Turnsignalcommand113Test, simple) { uint8_t data[8] = {0x61, 0x62, 0x63, 0x64, 0x65, 0x66, 0x67, 0x68}; turnsignalcommand.UpdateData(data); EXPECT_EQ(data[0], 0b00000000); - EXPECT_EQ(data[1], 0b01100000); + EXPECT_EQ(data[1], 0b01100010); EXPECT_EQ(data[2], 0b01100011); EXPECT_EQ(data[3], 0b01100100); EXPECT_EQ(data[4], 0b01100101); diff --git a/modules/canbus_vehicle/ch/protocol/vin_resp3_51d.cc b/modules/canbus/vehicle/ch/protocol/turnsignal_status__513.cc similarity index 52% rename from modules/canbus_vehicle/ch/protocol/vin_resp3_51d.cc rename to modules/canbus/vehicle/ch/protocol/turnsignal_status__513.cc index 6a62960a137..041d6a689ce 100644 --- a/modules/canbus_vehicle/ch/protocol/vin_resp3_51d.cc +++ b/modules/canbus/vehicle/ch/protocol/turnsignal_status__513.cc @@ -14,11 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/vin_resp3_51d.h" - -#include - -#include "glog/logging.h" +#include "modules/canbus/vehicle/ch/protocol/turnsignal_status__513.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,27 +25,27 @@ namespace ch { using ::apollo::drivers::canbus::Byte; -Vinresp351d::Vinresp351d() {} -const int32_t Vinresp351d::ID = 0x51D; +Turnsignalstatus513::Turnsignalstatus513() {} +const int32_t Turnsignalstatus513::ID = 0x513; -void Vinresp351d::Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const { - chassis->mutable_vin_resp3_51d()->set_vin17( - vin17(bytes, length)); +void Turnsignalstatus513::Parse(const std::uint8_t* bytes, int32_t length, + ChassisDetail* chassis) const { + chassis->mutable_ch()->mutable_turnsignal_status__513()->set_turn_signal_sts( + turn_signal_sts(bytes, length)); } -// config detail: {'bit': 0, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin17', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp351d::vin17(const std::uint8_t* bytes, - int32_t length) const { +// config detail: {'description': 'Lighting control(Status)', 'enum': {0: +// 'TURN_SIGNAL_STS_NONE', 1: 'TURN_SIGNAL_STS_LEFT', 2: +// 'TURN_SIGNAL_STS_RIGHT'}, 'precision': 1.0, 'len': 8, 'name': +// 'turn_signal_sts', 'is_signed_var': False, 'offset': 0.0, 'physical_range': +// '[0|2]', 'bit': 0, 'type': 'enum', 'order': 'intel', 'physical_unit': ''} +Turnsignal_status__513::Turn_signal_stsType +Turnsignalstatus513::turn_signal_sts(const std::uint8_t* bytes, + int32_t length) const { Byte t0(bytes + 0); int32_t x = t0.get_byte(0, 8); - std::string ret = ""; - ret += x; - return ret; + return static_cast(x); } } // namespace ch } // namespace canbus diff --git a/modules/tools/gen_vehicle_protocol/template/report_protocol.h.tpl b/modules/canbus/vehicle/ch/protocol/turnsignal_status__513.h similarity index 59% rename from modules/tools/gen_vehicle_protocol/template/report_protocol.h.tpl rename to modules/canbus/vehicle/ch/protocol/turnsignal_status__513.h index 79219d83e6f..20128981b2c 100644 --- a/modules/tools/gen_vehicle_protocol/template/report_protocol.h.tpl +++ b/modules/canbus/vehicle/ch/protocol/turnsignal_status__513.h @@ -16,27 +16,31 @@ #pragma once -#include "modules/drivers/canbus/can_comm/protocol_data.h" #include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" +#include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { namespace canbus { -namespace %(car_type_lower)s { +namespace ch { -class %(classname)s : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::ChassisDetail> { +class Turnsignalstatus513 : public ::apollo::drivers::canbus::ProtocolData< + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; - %(classname)s(); + Turnsignalstatus513(); void Parse(const std::uint8_t* bytes, int32_t length, - ChassisDetail* chassis) const override; + ChassisDetail* chassis) const override; private: -%(func_declare_list)s + // config detail: {'description': 'Lighting control(Status)', 'enum': {0: + // 'TURN_SIGNAL_STS_NONE', 1: 'TURN_SIGNAL_STS_LEFT', 2: + // 'TURN_SIGNAL_STS_RIGHT'}, 'precision': 1.0, 'len': 8, 'name': + // 'TURN_SIGNAL_STS', 'is_signed_var': False, 'offset': 0.0, 'physical_range': + // '[0|2]', 'bit': 0, 'type': 'enum', 'order': 'intel', 'physical_unit': ''} + Turnsignal_status__513::Turn_signal_stsType turn_signal_sts( + const std::uint8_t* bytes, const int32_t length) const; }; -} // namespace %(car_type_lower)s +} // namespace ch } // namespace canbus } // namespace apollo - - diff --git a/modules/canbus_vehicle/ch/protocol/turnsignal_status__513_test.cc b/modules/canbus/vehicle/ch/protocol/turnsignal_status__513_test.cc similarity index 82% rename from modules/canbus_vehicle/ch/protocol/turnsignal_status__513_test.cc rename to modules/canbus/vehicle/ch/protocol/turnsignal_status__513_test.cc index f794e355830..61af7d0ad54 100644 --- a/modules/canbus_vehicle/ch/protocol/turnsignal_status__513_test.cc +++ b/modules/canbus/vehicle/ch/protocol/turnsignal_status__513_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ch/protocol/turnsignal_status__513.h" +#include "modules/canbus/vehicle/ch/protocol/turnsignal_status__513.h" #include "gtest/gtest.h" namespace apollo { @@ -26,14 +26,14 @@ class Turnsignalstatus513Test : public ::testing::Test { }; TEST_F(Turnsignalstatus513Test, General) { - uint8_t data[8] = {0x01, 0x01, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; + uint8_t data[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; int32_t length = 8; - Ch cd; + ChassisDetail cd; Turnsignalstatus513 turnsignalstatus; turnsignalstatus.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b00000001); - EXPECT_EQ(data[1], 0b00000001); + EXPECT_EQ(data[1], 0b00000010); EXPECT_EQ(data[2], 0b00000011); EXPECT_EQ(data[3], 0b00000100); EXPECT_EQ(data[4], 0b00010001); @@ -41,8 +41,7 @@ TEST_F(Turnsignalstatus513Test, General) { EXPECT_EQ(data[6], 0b00010011); EXPECT_EQ(data[7], 0b00010100); - EXPECT_EQ(cd.turnsignal_status__513().turn_signal_sts(), 1); - EXPECT_EQ(cd.turnsignal_status__513().low_beam_sts(), 1); + EXPECT_EQ(cd.ch().turnsignal_status__513().turn_signal_sts(), 1); } } // namespace ch diff --git a/modules/canbus/vehicle/devkit/BUILD b/modules/canbus/vehicle/devkit/BUILD new file mode 100755 index 00000000000..dfe36395bf3 --- /dev/null +++ b/modules/canbus/vehicle/devkit/BUILD @@ -0,0 +1,81 @@ +load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") +load("//tools:cpplint.bzl", "cpplint") + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "devkit_vehicle_factory", + srcs = [ + "devkit_vehicle_factory.cc", + ], + hdrs = [ + "devkit_vehicle_factory.h", + ], + deps = [ + ":devkit_controller", + ":devkit_message_manager", + "//modules/canbus/vehicle:abstract_vehicle_factory", + ], +) + +cc_test( + name = "devkit_vehicle_factory_test", + size = "small", + srcs = ["devkit_vehicle_factory_test.cc"], + deps = [ + ":devkit_vehicle_factory", + "@com_google_googletest//:gtest_main", + ], +) + +cc_library( + name = "devkit_message_manager", + srcs = ["devkit_message_manager.cc"], + hdrs = ["devkit_message_manager.h"], + deps = [ + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_test( + name = "devkit_message_manager_test", + size = "small", + srcs = ["devkit_message_manager_test.cc"], + deps = [ + "//modules/canbus/vehicle/devkit:devkit_message_manager", + "@com_google_googletest//:gtest_main", + ], +) + +cc_library( + name = "devkit_controller", + srcs = ["devkit_controller.cc"], + hdrs = ["devkit_controller.h"], + deps = [ + ":devkit_message_manager", + "//modules/canbus/common:canbus_common", + "//modules/canbus/proto:canbus_conf_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_cc_proto", + "//modules/canbus/proto:vehicle_parameter_cc_proto", + "//modules/canbus/vehicle:vehicle_controller_base", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/common_msgs/basic_msgs:error_code_cc_proto", + "//modules/common_msgs/control_msgs:control_cmd_cc_proto", + ], +) + +cc_test( + name = "devkit_controller_test", + size = "small", + srcs = ["devkit_controller_test.cc"], + data = ["//modules/canbus:test_data"], + deps = [ + ":devkit_controller", + "@com_google_googletest//:gtest_main", + ], +) + +cpplint() diff --git a/modules/canbus_vehicle/devkit/devkit_controller.cc b/modules/canbus/vehicle/devkit/devkit_controller.cc similarity index 55% rename from modules/canbus_vehicle/devkit/devkit_controller.cc rename to modules/canbus/vehicle/devkit/devkit_controller.cc index fd351e3a0ed..62de09c1e5b 100644 --- a/modules/canbus_vehicle/devkit/devkit_controller.cc +++ b/modules/canbus/vehicle/devkit/devkit_controller.cc @@ -14,17 +14,15 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/devkit_controller.h" - -#include +#include "modules/canbus/vehicle/devkit/devkit_controller.h" #include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "cyber/common/log.h" #include "cyber/time/time.h" #include "modules/canbus/common/canbus_gflags.h" +#include "modules/canbus/vehicle/devkit/devkit_message_manager.h" #include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/canbus_vehicle/devkit/devkit_message_manager.h" #include "modules/drivers/canbus/can_comm/can_sender.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" @@ -41,13 +39,12 @@ namespace { const int32_t kMaxFailAttempt = 10; const int32_t CHECK_RESPONSE_STEER_UNIT_FLAG = 1; const int32_t CHECK_RESPONSE_SPEED_UNIT_FLAG = 2; -bool emergency_brake = false; } // namespace ErrorCode DevkitController::Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Devkit>* const can_sender, - MessageManager<::apollo::canbus::Devkit>* const message_manager) { + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) { if (is_initialized_) { AINFO << "DevkitController has already been initiated."; return ErrorCode::CANBUS_ERROR; @@ -108,21 +105,11 @@ ErrorCode DevkitController::Init( return ErrorCode::CANBUS_ERROR; } - vehicle_mode_command_105_ = dynamic_cast( - message_manager_->GetMutableProtocolDataById(Vehiclemodecommand105::ID)); - if (vehicle_mode_command_105_ == nullptr) { - AERROR - << "Vehiclemodecommand105 does not exist in the DevkitMessageManager!"; - return ErrorCode::CANBUS_ERROR; - } - - can_sender_->AddMessage(Throttlecommand100::ID, throttle_command_100_, false); can_sender_->AddMessage(Brakecommand101::ID, brake_command_101_, false); can_sender_->AddMessage(Gearcommand103::ID, gear_command_103_, false); can_sender_->AddMessage(Parkcommand104::ID, park_command_104_, false); can_sender_->AddMessage(Steeringcommand102::ID, steering_command_102_, false); - can_sender_->AddMessage(Vehiclemodecommand105::ID, vehicle_mode_command_105_, - false); + can_sender_->AddMessage(Throttlecommand100::ID, throttle_command_100_, false); // need sleep to ensure all messages received AINFO << "DevkitController is initialized."; @@ -160,13 +147,13 @@ void DevkitController::Stop() { Chassis DevkitController::chassis() { chassis_.Clear(); - Devkit chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); // 21, 22, previously 1, 2 - // if (driving_mode() == Chassis::EMERGENCY_MODE) { - // set_chassis_error_code(Chassis::NO_ERROR); - // } + if (driving_mode() == Chassis::EMERGENCY_MODE) { + set_chassis_error_code(Chassis::NO_ERROR); + } chassis_.set_driving_mode(driving_mode()); chassis_.set_error_code(chassis_error_code()); @@ -176,29 +163,29 @@ Chassis DevkitController::chassis() { // 4 engine rpm ch has no engine rpm // chassis_.set_engine_rpm(0); // 5 wheel spd - if (chassis_detail.has_wheelspeed_report_506()) { - if (chassis_detail.wheelspeed_report_506().has_rr()) { + if (chassis_detail.devkit().has_wheelspeed_report_506()) { + if (chassis_detail.devkit().wheelspeed_report_506().has_rr()) { chassis_.mutable_wheel_speed()->set_wheel_spd_rr( - chassis_detail.wheelspeed_report_506().rr()); + chassis_detail.devkit().wheelspeed_report_506().rr()); } - if (chassis_detail.wheelspeed_report_506().has_rl()) { + if (chassis_detail.devkit().wheelspeed_report_506().has_rl()) { chassis_.mutable_wheel_speed()->set_wheel_spd_rl( - chassis_detail.wheelspeed_report_506().rl()); + chassis_detail.devkit().wheelspeed_report_506().rl()); } - if (chassis_detail.wheelspeed_report_506().has_fr()) { + if (chassis_detail.devkit().wheelspeed_report_506().has_fr()) { chassis_.mutable_wheel_speed()->set_wheel_spd_fr( - chassis_detail.wheelspeed_report_506().fr()); + chassis_detail.devkit().wheelspeed_report_506().fr()); } - if (chassis_detail.wheelspeed_report_506().has_fl()) { + if (chassis_detail.devkit().wheelspeed_report_506().has_fl()) { chassis_.mutable_wheel_speed()->set_wheel_spd_fl( - chassis_detail.wheelspeed_report_506().fl()); + chassis_detail.devkit().wheelspeed_report_506().fl()); } } // 6 speed_mps - if (chassis_detail.has_vcu_report_505() && - chassis_detail.vcu_report_505().has_speed()) { + if (chassis_detail.devkit().has_vcu_report_505() && + chassis_detail.devkit().vcu_report_505().has_speed()) { chassis_.set_speed_mps( - std::abs(static_cast(chassis_detail.vcu_report_505().speed()))); + static_cast(chassis_detail.devkit().vcu_report_505().speed())); } else { chassis_.set_speed_mps(0); } @@ -207,59 +194,45 @@ Chassis DevkitController::chassis() { // 8 no fuel. do not set; // chassis_.set_fuel_range_m(0); // 9 throttle - if (chassis_detail.has_throttle_report_500() && - chassis_detail.throttle_report_500().has_throttle_pedal_actual()) { + if (chassis_detail.devkit().has_throttle_report_500() && + chassis_detail.devkit() + .throttle_report_500() + .has_throttle_pedal_actual()) { chassis_.set_throttle_percentage(static_cast( - chassis_detail.throttle_report_500().throttle_pedal_actual())); + chassis_detail.devkit().throttle_report_500().throttle_pedal_actual())); } else { chassis_.set_throttle_percentage(0); } - // throttle sender cmd - if (chassis_detail.has_throttle_command_100() && - chassis_detail.throttle_command_100().has_throttle_pedal_target()) { - chassis_.set_throttle_percentage_cmd(static_cast( - chassis_detail.throttle_command_100().throttle_pedal_target())); - } else { - chassis_.set_throttle_percentage_cmd(0); - } // 10 brake - if (chassis_detail.has_brake_report_501() && - chassis_detail.brake_report_501().has_brake_pedal_actual()) { + if (chassis_detail.devkit().has_brake_report_501() && + chassis_detail.devkit().brake_report_501().has_brake_pedal_actual()) { chassis_.set_brake_percentage(static_cast( - chassis_detail.brake_report_501().brake_pedal_actual())); + chassis_detail.devkit().brake_report_501().brake_pedal_actual())); } else { chassis_.set_brake_percentage(0); } - // brake sender cmd - if (chassis_detail.has_brake_command_101() && - chassis_detail.brake_command_101().has_brake_pedal_target()) { - chassis_.set_brake_percentage_cmd(static_cast( - chassis_detail.brake_command_101().brake_pedal_target())); - } else { - chassis_.set_brake_percentage_cmd(0); - } // 23, previously 11 gear - if (chassis_detail.has_gear_report_503() && - chassis_detail.gear_report_503().has_gear_actual()) { + if (chassis_detail.devkit().has_gear_report_503() && + chassis_detail.devkit().gear_report_503().has_gear_actual()) { Chassis::GearPosition gear_pos = Chassis::GEAR_INVALID; - if (chassis_detail.gear_report_503().gear_actual() == + if (chassis_detail.devkit().gear_report_503().gear_actual() == Gear_report_503::GEAR_ACTUAL_INVALID) { gear_pos = Chassis::GEAR_INVALID; } - if (chassis_detail.gear_report_503().gear_actual() == + if (chassis_detail.devkit().gear_report_503().gear_actual() == Gear_report_503::GEAR_ACTUAL_NEUTRAL) { gear_pos = Chassis::GEAR_NEUTRAL; } - if (chassis_detail.gear_report_503().gear_actual() == + if (chassis_detail.devkit().gear_report_503().gear_actual() == Gear_report_503::GEAR_ACTUAL_REVERSE) { gear_pos = Chassis::GEAR_REVERSE; } - if (chassis_detail.gear_report_503().gear_actual() == + if (chassis_detail.devkit().gear_report_503().gear_actual() == Gear_report_503::GEAR_ACTUAL_DRIVE) { gear_pos = Chassis::GEAR_DRIVE; } - if (chassis_detail.gear_report_503().gear_actual() == + if (chassis_detail.devkit().gear_report_503().gear_actual() == Gear_report_503::GEAR_ACTUAL_PARK) { gear_pos = Chassis::GEAR_PARKING; } @@ -268,26 +241,18 @@ Chassis DevkitController::chassis() { chassis_.set_gear_location(Chassis::GEAR_NONE); } // 12 steering - if (chassis_detail.has_steering_report_502() && - chassis_detail.steering_report_502().has_steer_angle_actual()) { + if (chassis_detail.devkit().has_steering_report_502() && + chassis_detail.devkit().steering_report_502().has_steer_angle_actual()) { chassis_.set_steering_percentage(static_cast( - chassis_detail.steering_report_502().steer_angle_actual() * 100.0 / - vehicle_params_.max_steer_angle() * M_PI / 180)); + chassis_detail.devkit().steering_report_502().steer_angle_actual() * + 100.0 / vehicle_params_.max_steer_angle() * M_PI / 180)); } else { chassis_.set_steering_percentage(0); } - // steering sender cmd - if (chassis_detail.has_steering_command_102() && - chassis_detail.steering_command_102().has_steer_angle_target()) { - chassis_.set_steering_percentage_cmd(static_cast( - chassis_detail.steering_command_102().steer_angle_target())); - } else { - chassis_.set_steering_percentage_cmd(0); - } // 13 parking brake - if (chassis_detail.has_park_report_504() && - chassis_detail.park_report_504().has_parking_actual()) { - if (chassis_detail.park_report_504().parking_actual() == + if (chassis_detail.devkit().has_park_report_504() && + chassis_detail.devkit().park_report_504().has_parking_actual()) { + if (chassis_detail.devkit().park_report_504().parking_actual() == Park_report_504::PARKING_ACTUAL_PARKING_TRIGGER) { chassis_.set_parking_brake(true); } else { @@ -297,159 +262,17 @@ Chassis DevkitController::chassis() { chassis_.set_parking_brake(false); } // 14 battery soc - if (chassis_detail.has_bms_report_512() && - chassis_detail.bms_report_512().has_battery_soc_percentage()) { + if (chassis_detail.devkit().has_bms_report_512() && + chassis_detail.devkit().bms_report_512().has_battery_soc()) { chassis_.set_battery_soc_percentage( - chassis_detail.bms_report_512().battery_soc_percentage()); + chassis_detail.devkit().bms_report_512().battery_soc()); } else { chassis_.set_battery_soc_percentage(0); } - // 15 give engage_advice based on battery low soc warn - if (chassis_.battery_soc_percentage() <= 15) { - chassis_.mutable_engage_advice()->set_advice( - apollo::common::EngageAdvice::DISALLOW_ENGAGE); - chassis_.mutable_engage_advice()->set_reason( - "Battery soc percentage is lower than 15%, please charge it quickly!"); - } - // 16 sonor list - // to do(ALL):check your vehicle type, confirm your sonar position because of - // every vhechle has different sonars assembly. - // 08 09 10 11 - if (chassis_detail.has_ultr_sensor_1_507()) { - chassis_.mutable_surround()->set_sonar08( - chassis_detail.ultr_sensor_1_507().uiuss8_tof_direct()); - chassis_.mutable_surround()->set_sonar09( - chassis_detail.ultr_sensor_1_507().uiuss9_tof_direct()); - chassis_.mutable_surround()->set_sonar10( - chassis_detail.ultr_sensor_1_507().uiuss10_tof_direct()); - chassis_.mutable_surround()->set_sonar11( - chassis_detail.ultr_sensor_1_507().uiuss11_tof_direct()); - } else { - chassis_.mutable_surround()->set_sonar08(0); - chassis_.mutable_surround()->set_sonar09(0); - chassis_.mutable_surround()->set_sonar10(0); - chassis_.mutable_surround()->set_sonar11(0); - } - // 2 3 4 5 - if (chassis_detail.has_ultr_sensor_3_509()) { - chassis_.mutable_surround()->set_sonar02( - chassis_detail.ultr_sensor_3_509().uiuss2_tof_direct()); - chassis_.mutable_surround()->set_sonar03( - chassis_detail.ultr_sensor_3_509().uiuss3_tof_direct()); - chassis_.mutable_surround()->set_sonar04( - chassis_detail.ultr_sensor_3_509().uiuss4_tof_direct()); - chassis_.mutable_surround()->set_sonar05( - chassis_detail.ultr_sensor_3_509().uiuss5_tof_direct()); - } else { - chassis_.mutable_surround()->set_sonar02(0); - chassis_.mutable_surround()->set_sonar03(0); - chassis_.mutable_surround()->set_sonar04(0); - chassis_.mutable_surround()->set_sonar05(0); - } - // 0 1 6 7 - if (chassis_detail.has_ultr_sensor_5_511()) { - chassis_.mutable_surround()->set_sonar00( - chassis_detail.ultr_sensor_5_511().uiuss0_tof_direct()); - chassis_.mutable_surround()->set_sonar01( - chassis_detail.ultr_sensor_5_511().uiuss1_tof_direct()); - chassis_.mutable_surround()->set_sonar06( - chassis_detail.ultr_sensor_5_511().uiuss6_tof_direct()); - chassis_.mutable_surround()->set_sonar07( - chassis_detail.ultr_sensor_5_511().uiuss7_tof_direct()); - } else { - chassis_.mutable_surround()->set_sonar00(0); - chassis_.mutable_surround()->set_sonar01(0); - chassis_.mutable_surround()->set_sonar06(0); - chassis_.mutable_surround()->set_sonar07(0); - } - // 17 set vin - // vin set 17 bits, like LSBN1234567890123 is prased as - // vin17(L),vin16(S),vin15(B),......,vin03(1),vin02(2),vin01(3) - std::string vin = ""; - if (chassis_detail.has_vin_resp1_514()) { - Vin_resp1_514 vin_resp1_514 = chassis_detail.vin_resp1_514(); - vin += vin_resp1_514.vin00(); - vin += vin_resp1_514.vin01(); - vin += vin_resp1_514.vin02(); - vin += vin_resp1_514.vin03(); - vin += vin_resp1_514.vin04(); - vin += vin_resp1_514.vin05(); - vin += vin_resp1_514.vin06(); - vin += vin_resp1_514.vin07(); - } - if (chassis_detail.has_vin_resp2_515()) { - Vin_resp2_515 vin_resp2_515 = chassis_detail.vin_resp2_515(); - vin += vin_resp2_515.vin08(); - vin += vin_resp2_515.vin09(); - vin += vin_resp2_515.vin10(); - vin += vin_resp2_515.vin11(); - vin += vin_resp2_515.vin12(); - vin += vin_resp2_515.vin13(); - vin += vin_resp2_515.vin14(); - vin += vin_resp2_515.vin15(); - } - if (chassis_detail.has_vin_resp3_516()) { - Vin_resp3_516 vin_resp3_516 = chassis_detail.vin_resp3_516(); - vin += vin_resp3_516.vin16(); - } - std::reverse(vin.begin(), vin.end()); - chassis_.mutable_vehicle_id()->set_vin(vin); - // 18 front bumper event - if (chassis_detail.has_vcu_report_505() && - chassis_detail.vcu_report_505().has_frontcrash_state()) { - if (chassis_detail.vcu_report_505().frontcrash_state() == - Vcu_report_505::FRONTCRASH_STATE_CRASH_EVENT) { - chassis_.set_front_bumper_event(Chassis::BUMPER_PRESSED); - } else { - chassis_.set_front_bumper_event(Chassis::BUMPER_NORMAL); - } - } else { - chassis_.set_front_bumper_event(Chassis::BUMPER_INVALID); - } - // 19 back bumper event - if (chassis_detail.has_vcu_report_505() && - chassis_detail.vcu_report_505().has_backcrash_state()) { - if (chassis_detail.vcu_report_505().backcrash_state() == - Vcu_report_505::BACKCRASH_STATE_CRASH_EVENT) { - chassis_.set_back_bumper_event(Chassis::BUMPER_PRESSED); - } else { - chassis_.set_back_bumper_event(Chassis::BUMPER_NORMAL); - } - } else { - chassis_.set_back_bumper_event(Chassis::BUMPER_INVALID); - } - - // 20 add checkresponse signal - if (chassis_detail.has_brake_report_501() && - chassis_detail.brake_report_501().has_brake_en_state()) { - chassis_.mutable_check_response()->set_is_esp_online( - chassis_detail.brake_report_501().brake_en_state() == 1); - } - if (chassis_detail.has_steering_report_502() && - chassis_detail.steering_report_502().has_steer_en_state()) { - chassis_.mutable_check_response()->set_is_eps_online( - chassis_detail.steering_report_502().steer_en_state() == 1); - } - if (chassis_detail.has_throttle_report_500() && - chassis_detail.throttle_report_500().has_throttle_en_state()) { - chassis_.mutable_check_response()->set_is_vcu_online( - chassis_detail.throttle_report_500().throttle_en_state() == 1); - } return chassis_; } -bool DevkitController::VerifyID() { - if (!CheckVin()) { - AERROR << "Failed to get the vin."; - GetVin(); - return false; - } else { - ResetVin(); - return true; - } -} - void DevkitController::Emergency() { set_driving_mode(Chassis::EMERGENCY_MODE); ResetProtocol(); @@ -469,19 +292,18 @@ ErrorCode DevkitController::EnableAutoMode() { Steering_command_102::STEER_EN_CTRL_ENABLE); gear_command_103_->set_gear_en_ctrl(Gear_command_103::GEAR_EN_CTRL_ENABLE); park_command_104_->set_park_en_ctrl(Park_command_104::PARK_EN_CTRL_ENABLE); + // set AEB enable if (FLAGS_enable_aeb) { brake_command_101_->set_aeb_en_ctrl( Brake_command_101::AEB_EN_CTRL_ENABLE_AEB); - AINFO << "Set AEB enable"; } can_sender_->Update(); const int32_t flag = CHECK_RESPONSE_STEER_UNIT_FLAG | CHECK_RESPONSE_SPEED_UNIT_FLAG; if (!CheckResponse(flag, true)) { - AERROR << "Failed to switch to COMPLETE_AUTO_DRIVE mode. Please check the " - "emergency button or chassis."; + AERROR << "Failed to switch to COMPLETE_AUTO_DRIVE mode."; Emergency(); set_chassis_error_code(Chassis::CHASSIS_ERROR); return ErrorCode::CANBUS_ERROR; @@ -567,31 +389,24 @@ void DevkitController::Brake(double pedal) { AINFO << "The current drive mode does not need to set brake pedal."; return; } - if (!emergency_brake) { - brake_command_101_->set_brake_pedal_target(pedal); - } - // brake_command_101_->set_brake_pedal_target(pedal); + brake_command_101_->set_brake_pedal_target(pedal); } // drive with pedal -// pedal:0.0~99.9 unit:%s +// pedal:0.0~99.9 unit:% void DevkitController::Throttle(double pedal) { if (driving_mode() != Chassis::COMPLETE_AUTO_DRIVE && driving_mode() != Chassis::AUTO_SPEED_ONLY) { AINFO << "The current drive mode does not need to set throttle pedal."; return; } - if (!emergency_brake) { - throttle_command_100_->set_throttle_pedal_target(pedal); - } - // throttle_command_100_->set_throttle_pedal_target(pedal); + throttle_command_100_->set_throttle_pedal_target(pedal); } -// confirm the car is driven by acceleration command instead of -// throttle/brake pedal drive with acceleration/deceleration acc:-7.0 ~ 5.0, -// unit:m/s^2 +// confirm the car is driven by acceleration command instead of throttle/brake +// pedal drive with acceleration/deceleration acc:-7.0 ~ 5.0, unit:m/s^2 void DevkitController::Acceleration(double acc) { - if (driving_mode() != Chassis::COMPLETE_AUTO_DRIVE && + if (driving_mode() != Chassis::COMPLETE_AUTO_DRIVE || driving_mode() != Chassis::AUTO_SPEED_ONLY) { AINFO << "The current drive mode does not need to set acceleration."; return; @@ -599,10 +414,10 @@ void DevkitController::Acceleration(double acc) { // None } -// devkit default, left:+, right:- +// devkit default, -30 ~ 00, left:+, right:- // need to be compatible with control module, so reverse // steering with default angle speed, 25-250 (default:250) -// angle:-99.99~0.00~99.99, unit:, left:+, right:- +// angle:-99.99~0.00~99.99, unit:, left:-, right:+ void DevkitController::Steer(double angle) { if (driving_mode() != Chassis::COMPLETE_AUTO_DRIVE && driving_mode() != Chassis::AUTO_STEER_ONLY) { @@ -611,16 +426,13 @@ void DevkitController::Steer(double angle) { } const double real_angle = vehicle_params_.max_steer_angle() / M_PI * 180 * angle / 100.0; - - if (!emergency_brake) { - steering_command_102_->set_steer_angle_target(real_angle) - ->set_steer_angle_spd_target(250); - } + steering_command_102_->set_steer_angle_target(real_angle) + ->set_steer_angle_spd(250); } // steering with new angle speed -// angle:-99.99~0.00~99.99, unit:, left:+, right:- -// angle_spd:25~250(default:250), unit:deg/s +// angle:-99.99~0.00~99.99, unit:, left:-, right:+ +// angle_spd:25~250, unit:deg/s void DevkitController::Steer(double angle, double angle_spd) { if (driving_mode() != Chassis::COMPLETE_AUTO_DRIVE && driving_mode() != Chassis::AUTO_STEER_ONLY) { @@ -629,19 +441,15 @@ void DevkitController::Steer(double angle, double angle_spd) { } const double real_angle = vehicle_params_.max_steer_angle() / M_PI * 180 * angle / 100.0; - - if (!emergency_brake) { - steering_command_102_->set_steer_angle_target(real_angle) - ->set_steer_angle_spd_target(250); - } + steering_command_102_->set_steer_angle_target(real_angle) + ->set_steer_angle_spd(250); } void DevkitController::SetEpbBreak(const ControlCommand& command) { if (command.parking_brake()) { - park_command_104_->set_park_target( - Park_command_104::PARK_TARGET_PARKING_TRIGGER); + // None } else { - park_command_104_->set_park_target(Park_command_104::PARK_TARGET_RELEASE); + // None } } @@ -664,47 +472,7 @@ void DevkitController::SetHorn(const ControlCommand& command) { } void DevkitController::SetTurningSignal(const ControlCommand& command) { - // Set Turn Signal - auto signal = command.signal().turn_signal(); - if (signal == common::VehicleSignal::TURN_LEFT) { - vehicle_mode_command_105_->set_turn_light_ctrl( - Vehicle_mode_command_105::TURN_LIGHT_CTRL_LEFT_TURNLAMP_ON); - } else if (signal == common::VehicleSignal::TURN_RIGHT) { - vehicle_mode_command_105_->set_turn_light_ctrl( - Vehicle_mode_command_105::TURN_LIGHT_CTRL_RIGHT_TURNLAMP_ON); - } else if (signal == common::VehicleSignal::TURN_HAZARD_WARNING) { - vehicle_mode_command_105_->set_turn_light_ctrl( - Vehicle_mode_command_105::TURN_LIGHT_CTRL_HAZARD_WARNING_LAMPSTS_ON); - } else { - vehicle_mode_command_105_->set_turn_light_ctrl( - Vehicle_mode_command_105::TURN_LIGHT_CTRL_TURNLAMP_OFF); - } -} - -bool DevkitController::CheckVin() { - if (chassis_.vehicle_id().vin().size() == 17) { - AINFO << "Vin check success! Vehicel vin is " - << chassis_.vehicle_id().vin(); - return true; - } else { - AINFO << "Vin check failed! Current vin size is " - << chassis_.vehicle_id().vin().size(); - return false; - } -} - -void DevkitController::GetVin() { - vehicle_mode_command_105_->set_vin_req( - Vehicle_mode_command_105::VIN_REQ_VIN_REQ_ENABLE); - AINFO << "Get vin"; - can_sender_->Update(); -} - -void DevkitController::ResetVin() { - vehicle_mode_command_105_->set_vin_req( - Vehicle_mode_command_105::VIN_REQ_VIN_REQ_DISABLE); - AINFO << "Reset vin"; - can_sender_->Update(); + // Set Turn Signal do not support on devkit } void DevkitController::ResetProtocol() { @@ -712,58 +480,34 @@ void DevkitController::ResetProtocol() { } bool DevkitController::CheckChassisError() { - Devkit chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); - if (!chassis_detail.has_check_response()) { + if (!chassis_detail.has_devkit()) { AERROR_EVERY(100) << "ChassisDetail has no devkit vehicle info." << chassis_detail.DebugString(); return false; } + Devkit devkit = chassis_detail.devkit(); + // steer fault - if (chassis_detail.has_steering_report_502()) { + if (devkit.has_steering_report_502()) { if (Steering_report_502::STEER_FLT1_STEER_SYSTEM_HARDWARE_FAULT == - chassis_detail.steering_report_502().steer_flt1()) { - AERROR_EVERY(100) << "Chassis has steer system fault."; + devkit.steering_report_502().steer_flt1()) { return true; } } // drive fault - if (chassis_detail.has_throttle_report_500()) { + if (devkit.has_throttle_report_500()) { if (Throttle_report_500::THROTTLE_FLT1_DRIVE_SYSTEM_HARDWARE_FAULT == - chassis_detail.throttle_report_500().throttle_flt1()) { - AERROR_EVERY(100) << "Chassis has drive system fault."; + devkit.throttle_report_500().throttle_flt1()) { return true; } } // brake fault - if (chassis_detail.has_brake_report_501()) { + if (devkit.has_brake_report_501()) { if (Brake_report_501::BRAKE_FLT1_BRAKE_SYSTEM_HARDWARE_FAULT == - chassis_detail.brake_report_501().brake_flt1()) { - AERROR_EVERY(100) << "Chassis has brake system fault."; - return true; - } - } - // battery soc low - if (chassis_detail.has_bms_report_512()) { - if (chassis_detail.bms_report_512().is_battery_soc_low()) { - AERROR_EVERY(100) << "Chassis battery has low soc, please charge."; - return true; - } - } - // battery over emperature fault - if (chassis_detail.has_bms_report_512()) { - if (Bms_report_512::BATTERY_FLT_OVER_TEMP_FAULT == - chassis_detail.bms_report_512().battery_flt_over_temp()) { - AERROR_EVERY(100) << "Chassis battery has over temperature fault."; - return true; - } - } - // battery low temperature fault - if (chassis_detail.has_bms_report_512()) { - if (Bms_report_512::BATTERY_FLT_LOW_TEMP_FAULT == - chassis_detail.bms_report_512().battery_flt_low_temp()) { - AERROR_EVERY(100) << "Chassis battery has below low temperature fault."; + devkit.brake_report_501().brake_flt1()) { return true; } } @@ -791,7 +535,6 @@ void DevkitController::SecurityDogThreadFunc() { start = ::apollo::cyber::Time::Now().ToMicrosecond(); const Chassis::DrivingMode mode = driving_mode(); bool emergency_mode = false; - emergency_brake = false; // 1. horizontal control check if ((mode == Chassis::COMPLETE_AUTO_DRIVE || @@ -800,7 +543,6 @@ void DevkitController::SecurityDogThreadFunc() { ++horizontal_ctrl_fail; if (horizontal_ctrl_fail >= kMaxFailAttempt) { emergency_mode = true; - AINFO << "Driving_mode is into emergency by steer manual intervention"; set_chassis_error_code(Chassis::MANUAL_INTERVENTION); } } else { @@ -814,7 +556,6 @@ void DevkitController::SecurityDogThreadFunc() { ++vertical_ctrl_fail; if (vertical_ctrl_fail >= kMaxFailAttempt) { emergency_mode = true; - AINFO << "Driving_mode is into emergency by speed manual intervention"; set_chassis_error_code(Chassis::MANUAL_INTERVENTION); } } else { @@ -823,31 +564,18 @@ void DevkitController::SecurityDogThreadFunc() { if (CheckChassisError()) { set_chassis_error_code(Chassis::CHASSIS_ERROR); emergency_mode = true; - if (chassis_.speed_mps() > 0.3) { - emergency_brake = true; - } } if (emergency_mode && mode != Chassis::EMERGENCY_MODE) { set_driving_mode(Chassis::EMERGENCY_MODE); - if (emergency_brake) { - throttle_command_100_->set_throttle_pedal_target(0); - brake_command_101_->set_brake_pedal_target(40); - steering_command_102_->set_steer_angle_target(0); - std::this_thread::sleep_for( - std::chrono::duration(3000)); - } message_manager_->ResetSendMessages(); - can_sender_->Update(); - emergency_brake = false; } end = ::apollo::cyber::Time::Now().ToMicrosecond(); std::chrono::duration elapsed{end - start}; if (elapsed < default_period) { std::this_thread::sleep_for(default_period - elapsed); } else { - AERROR << "Too much time consumption in DevkitController looping " - "process:" + AERROR << "Too much time consumption in DevkitController looping process:" << elapsed.count(); } } @@ -855,7 +583,7 @@ void DevkitController::SecurityDogThreadFunc() { bool DevkitController::CheckResponse(const int32_t flags, bool need_wait) { int32_t retry_num = 20; - Devkit chassis_detail; + ChassisDetail chassis_detail; bool is_eps_online = false; bool is_vcu_online = false; bool is_esp_online = false; diff --git a/modules/canbus_vehicle/devkit/devkit_controller.h b/modules/canbus/vehicle/devkit/devkit_controller.h similarity index 84% rename from modules/canbus_vehicle/devkit/devkit_controller.h rename to modules/canbus/vehicle/devkit/devkit_controller.h index ac308330753..f2cf2eee06e 100755 --- a/modules/canbus_vehicle/devkit/devkit_controller.h +++ b/modules/canbus/vehicle/devkit/devkit_controller.h @@ -20,25 +20,22 @@ #include #include "modules/canbus/proto/canbus_conf.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" +#include "modules/canbus/vehicle/devkit/protocol/brake_command_101.h" +#include "modules/canbus/vehicle/devkit/protocol/gear_command_103.h" +#include "modules/canbus/vehicle/devkit/protocol/park_command_104.h" +#include "modules/canbus/vehicle/devkit/protocol/steering_command_102.h" +#include "modules/canbus/vehicle/devkit/protocol/throttle_command_100.h" +#include "modules/canbus/vehicle/vehicle_controller.h" #include "modules/common_msgs/basic_msgs/error_code.pb.h" -#include "modules/common_msgs/chassis_msgs/chassis.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" -#include "modules/canbus_vehicle/devkit/protocol/brake_command_101.h" -#include "modules/canbus_vehicle/devkit/protocol/gear_command_103.h" -#include "modules/canbus_vehicle/devkit/protocol/park_command_104.h" -#include "modules/canbus_vehicle/devkit/protocol/steering_command_102.h" -#include "modules/canbus_vehicle/devkit/protocol/throttle_command_100.h" -#include "modules/canbus_vehicle/devkit/protocol/vehicle_mode_command_105.h" -#include "modules/canbus/vehicle/vehicle_controller.h" - namespace apollo { namespace canbus { namespace devkit { -class DevkitController final - : public VehicleController<::apollo::canbus::Devkit> { +class DevkitController final : public VehicleController { public: DevkitController() {} @@ -46,8 +43,9 @@ class DevkitController final ::apollo::common::ErrorCode Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Devkit>* const can_sender, - MessageManager<::apollo::canbus::Devkit>* const message_manager) override; + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) + override; bool Start() override; @@ -109,13 +107,8 @@ class DevkitController final void SetTurningSignal( const ::apollo::control::ControlCommand& command) override; - // response vid - bool VerifyID() override; void ResetProtocol(); bool CheckChassisError(); - bool CheckVin(); - void GetVin(); - void ResetVin(); private: void SecurityDogThreadFunc(); @@ -132,7 +125,6 @@ class DevkitController final Parkcommand104* park_command_104_ = nullptr; Steeringcommand102* steering_command_102_ = nullptr; Throttlecommand100* throttle_command_100_ = nullptr; - Vehiclemodecommand105* vehicle_mode_command_105_ = nullptr; Chassis chassis_; std::unique_ptr thread_; diff --git a/modules/canbus_vehicle/devkit/devkit_controller_test.cc b/modules/canbus/vehicle/devkit/devkit_controller_test.cc similarity index 93% rename from modules/canbus_vehicle/devkit/devkit_controller_test.cc rename to modules/canbus/vehicle/devkit/devkit_controller_test.cc index f5dc0ecb79e..6e7ede7b096 100755 --- a/modules/canbus_vehicle/devkit/devkit_controller_test.cc +++ b/modules/canbus/vehicle/devkit/devkit_controller_test.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/devkit_controller.h" +#include "modules/canbus/vehicle/devkit/devkit_controller.h" #include "cyber/common/file.h" #include "gtest/gtest.h" #include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" -#include "modules/canbus_vehicle/devkit/devkit_message_manager.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" +#include "modules/canbus/vehicle/devkit/devkit_message_manager.h" #include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" #include "modules/drivers/canbus/can_comm/can_sender.h" @@ -50,7 +50,7 @@ class DevkitControllerTest : public ::testing::Test { DevkitController controller_; ControlCommand control_cmd_; VehicleSignal vehicle_signal_; - CanSender<::apollo::canbus::Devkit> sender_; + CanSender<::apollo::canbus::ChassisDetail> sender_; DevkitMessageManager msg_manager_; CanbusConf canbus_conf_; VehicleParameter params_; diff --git a/modules/canbus_vehicle/devkit/devkit_message_manager.cc b/modules/canbus/vehicle/devkit/devkit_message_manager.cc similarity index 54% rename from modules/canbus_vehicle/devkit/devkit_message_manager.cc rename to modules/canbus/vehicle/devkit/devkit_message_manager.cc index 32039a89ce1..9821e9975bf 100755 --- a/modules/canbus_vehicle/devkit/devkit_message_manager.cc +++ b/modules/canbus/vehicle/devkit/devkit_message_manager.cc @@ -14,31 +14,27 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/devkit_message_manager.h" +#include "modules/canbus/vehicle/devkit/devkit_message_manager.h" -#include "modules/canbus_vehicle/devkit/protocol/brake_command_101.h" -#include "modules/canbus_vehicle/devkit/protocol/gear_command_103.h" -#include "modules/canbus_vehicle/devkit/protocol/park_command_104.h" -#include "modules/canbus_vehicle/devkit/protocol/steering_command_102.h" -#include "modules/canbus_vehicle/devkit/protocol/throttle_command_100.h" -#include "modules/canbus_vehicle/devkit/protocol/vehicle_mode_command_105.h" +#include "modules/canbus/vehicle/devkit/protocol/brake_command_101.h" +#include "modules/canbus/vehicle/devkit/protocol/gear_command_103.h" +#include "modules/canbus/vehicle/devkit/protocol/park_command_104.h" +#include "modules/canbus/vehicle/devkit/protocol/steering_command_102.h" +#include "modules/canbus/vehicle/devkit/protocol/throttle_command_100.h" -#include "modules/canbus_vehicle/devkit/protocol/bms_report_512.h" -#include "modules/canbus_vehicle/devkit/protocol/brake_report_501.h" -#include "modules/canbus_vehicle/devkit/protocol/gear_report_503.h" -#include "modules/canbus_vehicle/devkit/protocol/park_report_504.h" -#include "modules/canbus_vehicle/devkit/protocol/steering_report_502.h" -#include "modules/canbus_vehicle/devkit/protocol/throttle_report_500.h" -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_1_507.h" -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_2_508.h" -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_3_509.h" -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_4_510.h" -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_5_511.h" -#include "modules/canbus_vehicle/devkit/protocol/vcu_report_505.h" -#include "modules/canbus_vehicle/devkit/protocol/vin_resp1_514.h" -#include "modules/canbus_vehicle/devkit/protocol/vin_resp2_515.h" -#include "modules/canbus_vehicle/devkit/protocol/vin_resp3_516.h" -#include "modules/canbus_vehicle/devkit/protocol/wheelspeed_report_506.h" +#include "modules/canbus/vehicle/devkit/protocol/bms_report_512.h" +#include "modules/canbus/vehicle/devkit/protocol/brake_report_501.h" +#include "modules/canbus/vehicle/devkit/protocol/gear_report_503.h" +#include "modules/canbus/vehicle/devkit/protocol/park_report_504.h" +#include "modules/canbus/vehicle/devkit/protocol/steering_report_502.h" +#include "modules/canbus/vehicle/devkit/protocol/throttle_report_500.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_1_507.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_2_508.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_3_509.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_4_510.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_5_511.h" +#include "modules/canbus/vehicle/devkit/protocol/vcu_report_505.h" +#include "modules/canbus/vehicle/devkit/protocol/wheelspeed_report_506.h" namespace apollo { namespace canbus { @@ -51,7 +47,6 @@ DevkitMessageManager::DevkitMessageManager() { AddSendProtocolData(); AddSendProtocolData(); AddSendProtocolData(); - AddSendProtocolData(); // Report Messages AddRecvProtocolData(); @@ -66,9 +61,6 @@ DevkitMessageManager::DevkitMessageManager() { AddRecvProtocolData(); AddRecvProtocolData(); AddRecvProtocolData(); - AddRecvProtocolData(); - AddRecvProtocolData(); - AddRecvProtocolData(); AddRecvProtocolData(); } diff --git a/modules/canbus_vehicle/devkit/devkit_message_manager.h b/modules/canbus/vehicle/devkit/devkit_message_manager.h similarity index 89% rename from modules/canbus_vehicle/devkit/devkit_message_manager.h rename to modules/canbus/vehicle/devkit/devkit_message_manager.h index 16b24935e11..920ba5c8127 100755 --- a/modules/canbus_vehicle/devkit/devkit_message_manager.h +++ b/modules/canbus/vehicle/devkit/devkit_message_manager.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/message_manager.h" namespace apollo { @@ -26,7 +26,7 @@ namespace devkit { using ::apollo::drivers::canbus::MessageManager; class DevkitMessageManager - : public MessageManager<::apollo::canbus::Devkit> { + : public MessageManager<::apollo::canbus::ChassisDetail> { public: DevkitMessageManager(); virtual ~DevkitMessageManager(); diff --git a/modules/canbus_vehicle/devkit/devkit_message_manager_test.cc b/modules/canbus/vehicle/devkit/devkit_message_manager_test.cc similarity index 69% rename from modules/canbus_vehicle/devkit/devkit_message_manager_test.cc rename to modules/canbus/vehicle/devkit/devkit_message_manager_test.cc index 00f8befc461..c5710bfeed1 100755 --- a/modules/canbus_vehicle/devkit/devkit_message_manager_test.cc +++ b/modules/canbus/vehicle/devkit/devkit_message_manager_test.cc @@ -14,28 +14,28 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/devkit_message_manager.h" +#include "modules/canbus/vehicle/devkit/devkit_message_manager.h" #include "gtest/gtest.h" -#include "modules/canbus_vehicle/devkit/protocol/bms_report_512.h" -#include "modules/canbus_vehicle/devkit/protocol/brake_command_101.h" -#include "modules/canbus_vehicle/devkit/protocol/brake_report_501.h" -#include "modules/canbus_vehicle/devkit/protocol/gear_command_103.h" -#include "modules/canbus_vehicle/devkit/protocol/gear_report_503.h" -#include "modules/canbus_vehicle/devkit/protocol/park_command_104.h" -#include "modules/canbus_vehicle/devkit/protocol/park_report_504.h" -#include "modules/canbus_vehicle/devkit/protocol/steering_command_102.h" -#include "modules/canbus_vehicle/devkit/protocol/steering_report_502.h" -#include "modules/canbus_vehicle/devkit/protocol/throttle_command_100.h" -#include "modules/canbus_vehicle/devkit/protocol/throttle_report_500.h" -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_1_507.h" -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_2_508.h" -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_3_509.h" -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_4_510.h" -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_5_511.h" -#include "modules/canbus_vehicle/devkit/protocol/vcu_report_505.h" -#include "modules/canbus_vehicle/devkit/protocol/wheelspeed_report_506.h" +#include "modules/canbus/vehicle/devkit/protocol/bms_report_512.h" +#include "modules/canbus/vehicle/devkit/protocol/brake_command_101.h" +#include "modules/canbus/vehicle/devkit/protocol/brake_report_501.h" +#include "modules/canbus/vehicle/devkit/protocol/gear_command_103.h" +#include "modules/canbus/vehicle/devkit/protocol/gear_report_503.h" +#include "modules/canbus/vehicle/devkit/protocol/park_command_104.h" +#include "modules/canbus/vehicle/devkit/protocol/park_report_504.h" +#include "modules/canbus/vehicle/devkit/protocol/steering_command_102.h" +#include "modules/canbus/vehicle/devkit/protocol/steering_report_502.h" +#include "modules/canbus/vehicle/devkit/protocol/throttle_command_100.h" +#include "modules/canbus/vehicle/devkit/protocol/throttle_report_500.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_1_507.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_2_508.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_3_509.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_4_510.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_5_511.h" +#include "modules/canbus/vehicle/devkit/protocol/vcu_report_505.h" +#include "modules/canbus/vehicle/devkit/protocol/wheelspeed_report_506.h" namespace apollo { namespace canbus { diff --git a/modules/audio/inference/moving_detection_test.cc b/modules/canbus/vehicle/devkit/devkit_vehicle_factory.cc old mode 100644 new mode 100755 similarity index 54% rename from modules/audio/inference/moving_detection_test.cc rename to modules/canbus/vehicle/devkit/devkit_vehicle_factory.cc index d4387636eff..e227b1cc326 --- a/modules/audio/inference/moving_detection_test.cc +++ b/modules/canbus/vehicle/devkit/devkit_vehicle_factory.cc @@ -14,34 +14,26 @@ * limitations under the License. *****************************************************************************/ -#include "modules/audio/inference/moving_detection.h" +#include "modules/canbus/vehicle/devkit/devkit_vehicle_factory.h" -#include "gtest/gtest.h" +#include "cyber/common/log.h" +#include "modules/canbus/vehicle/devkit/devkit_controller.h" +#include "modules/canbus/vehicle/devkit/devkit_message_manager.h" +#include "modules/common/util/util.h" namespace apollo { -namespace audio { +namespace canbus { -class MovingDetectionTest : public ::testing::Test { - public: - virtual void SetUp() {} - - protected: - MovingDetection moving_detection_; -}; - -TEST_F(MovingDetectionTest, fft1d) { - std::vector signal{1.0, 2.0, 3.0, 4.0, -1.0, -2.0}; - std::vector> fft_result = - moving_detection_.fft1d(signal); +std::unique_ptr +DevkitVehicleFactory::CreateVehicleController() { + return std::unique_ptr(new devkit::DevkitController()); } -TEST_F(MovingDetectionTest, moving) { - std::vector> signals{ - {1.0, 2.0, 3.0, 4.0, -1.0, -2.0}, - {-1.0, -2.0, 3.0, 4.0, 1.0, -2.0}}; - MovingResult result = moving_detection_.Detect(signals); - EXPECT_EQ(result, UNKNOWN); +std::unique_ptr> +DevkitVehicleFactory::CreateMessageManager() { + return std::unique_ptr>( + new devkit::DevkitMessageManager()); } -} // namespace audio +} // namespace canbus } // namespace apollo diff --git a/modules/canbus/vehicle/devkit/devkit_vehicle_factory.h b/modules/canbus/vehicle/devkit/devkit_vehicle_factory.h new file mode 100755 index 00000000000..5b1d4e301bb --- /dev/null +++ b/modules/canbus/vehicle/devkit/devkit_vehicle_factory.h @@ -0,0 +1,65 @@ +/****************************************************************************** + * 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 devkit_vehicle_factory.h + */ + +#pragma once + +#include + +#include "modules/canbus/proto/vehicle_parameter.pb.h" +#include "modules/canbus/vehicle/abstract_vehicle_factory.h" +#include "modules/canbus/vehicle/vehicle_controller.h" +#include "modules/drivers/canbus/can_comm/message_manager.h" + +/** + * @namespace apollo::canbus + * @brief apollo::canbus + */ +namespace apollo { +namespace canbus { + +/** + * @class DevkitVehicleFactory + * + * @brief this class is inherited from AbstractVehicleFactory. It can be used to + * create controller and message manager for devkit vehicle. + */ +class DevkitVehicleFactory : public AbstractVehicleFactory { + public: + /** + * @brief destructor + */ + virtual ~DevkitVehicleFactory() = default; + + /** + * @brief create devkit vehicle controller + * @returns a unique_ptr that points to the created controller + */ + std::unique_ptr CreateVehicleController() override; + + /** + * @brief create devkit message manager + * @returns a unique_ptr that points to the created message manager + */ + std::unique_ptr> + CreateMessageManager() override; +}; + +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/devkit_vehicle_factory_test.cc b/modules/canbus/vehicle/devkit/devkit_vehicle_factory_test.cc similarity index 58% rename from modules/canbus_vehicle/devkit/devkit_vehicle_factory_test.cc rename to modules/canbus/vehicle/devkit/devkit_vehicle_factory_test.cc index 94fc2a213db..704d533fe92 100755 --- a/modules/canbus_vehicle/devkit/devkit_vehicle_factory_test.cc +++ b/modules/canbus/vehicle/devkit/devkit_vehicle_factory_test.cc @@ -1,5 +1,5 @@ /****************************************************************************** - * Copyright 2019 The Apollo Authors. All Rights Reserved. + * 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. @@ -14,40 +14,33 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/devkit_vehicle_factory.h" +#include "modules/canbus/vehicle/devkit/devkit_vehicle_factory.h" #include "gtest/gtest.h" - -#include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "cyber/common/file.h" - namespace apollo { namespace canbus { class DevkitVehicleFactoryTest : public ::testing::Test { public: virtual void SetUp() { - std::string canbus_conf_file = - "/apollo/modules/canbus_vehicle/devkit/testdata/" - "devkit_canbus_conf_test.pb.txt"; - cyber::common::GetProtoFromFile(canbus_conf_file, &canbus_conf_); - params_ = canbus_conf_.vehicle_parameter(); - params_.set_brand(apollo::common::DKIT); - devkit_factory_.SetVehicleParameter(params_); + VehicleParameter parameter; + parameter.set_brand(apollo::common::DKIT); + devkit_factory_.SetVehicleParameter(parameter); } virtual void TearDown() {} protected: DevkitVehicleFactory devkit_factory_; - CanbusConf canbus_conf_; - VehicleParameter params_; }; -TEST_F(DevkitVehicleFactoryTest, Init) { - apollo::cyber::Init("vehicle_factory_test"); - EXPECT_EQ(devkit_factory_.Init(&canbus_conf_), true); +TEST_F(DevkitVehicleFactoryTest, InitVehicleController) { + EXPECT_NE(devkit_factory_.CreateVehicleController(), nullptr); +} + +TEST_F(DevkitVehicleFactoryTest, InitMessageManager) { + EXPECT_NE(devkit_factory_.CreateMessageManager(), nullptr); } } // namespace canbus diff --git a/modules/canbus_vehicle/devkit/protocol/BUILD b/modules/canbus/vehicle/devkit/protocol/BUILD similarity index 71% rename from modules/canbus_vehicle/devkit/protocol/BUILD rename to modules/canbus/vehicle/devkit/protocol/BUILD index 3937485255e..2dd1cabddcc 100755 --- a/modules/canbus_vehicle/devkit/protocol/BUILD +++ b/modules/canbus/vehicle/devkit/protocol/BUILD @@ -25,10 +25,6 @@ cc_library( ":ultr_sensor_4_510", ":ultr_sensor_5_511", ":vcu_report_505", - ":vehicle_mode_command_105", - ":vin_resp1_514", - ":vin_resp2_515", - ":vin_resp3_516", ":wheelspeed_report_506", ], ) @@ -39,7 +35,7 @@ cc_library( hdrs = ["bms_report_512.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -50,7 +46,7 @@ cc_test( size = "small", srcs = ["bms_report_512_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -61,7 +57,7 @@ cc_library( hdrs = ["brake_command_101.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -72,7 +68,7 @@ cc_test( size = "small", srcs = ["brake_command_101_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -83,7 +79,7 @@ cc_library( hdrs = ["brake_report_501.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -94,7 +90,7 @@ cc_test( size = "small", srcs = ["brake_report_501_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -105,7 +101,7 @@ cc_library( hdrs = ["gear_command_103.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -116,7 +112,7 @@ cc_test( size = "small", srcs = ["gear_command_103_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -127,7 +123,7 @@ cc_library( hdrs = ["gear_report_503.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -138,7 +134,7 @@ cc_test( size = "small", srcs = ["gear_report_503_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -149,7 +145,7 @@ cc_library( hdrs = ["park_command_104.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -160,7 +156,7 @@ cc_test( size = "small", srcs = ["park_command_104_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -171,7 +167,7 @@ cc_library( hdrs = ["park_report_504.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -182,7 +178,7 @@ cc_test( size = "small", srcs = ["park_report_504_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -193,7 +189,7 @@ cc_library( hdrs = ["steering_command_102.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -204,7 +200,7 @@ cc_test( size = "small", srcs = ["steering_command_102_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -215,7 +211,7 @@ cc_library( hdrs = ["steering_report_502.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -226,7 +222,7 @@ cc_test( size = "small", srcs = ["steering_report_502_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -237,7 +233,7 @@ cc_library( hdrs = ["throttle_command_100.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -248,7 +244,7 @@ cc_test( size = "small", srcs = ["throttle_command_100_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -259,7 +255,7 @@ cc_library( hdrs = ["throttle_report_500.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -270,7 +266,7 @@ cc_test( size = "small", srcs = ["throttle_report_500_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -281,7 +277,7 @@ cc_library( hdrs = ["ultr_sensor_1_507.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -292,7 +288,7 @@ cc_test( size = "small", srcs = ["ultr_sensor_1_507_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -303,7 +299,7 @@ cc_library( hdrs = ["ultr_sensor_2_508.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -314,7 +310,7 @@ cc_test( size = "small", srcs = ["ultr_sensor_2_508_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -325,7 +321,7 @@ cc_library( hdrs = ["ultr_sensor_3_509.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -336,7 +332,7 @@ cc_test( size = "small", srcs = ["ultr_sensor_3_509_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -347,7 +343,7 @@ cc_library( hdrs = ["ultr_sensor_4_510.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -358,7 +354,7 @@ cc_test( size = "small", srcs = ["ultr_sensor_4_510_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -369,7 +365,7 @@ cc_library( hdrs = ["ultr_sensor_5_511.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -380,7 +376,7 @@ cc_test( size = "small", srcs = ["ultr_sensor_5_511_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -391,7 +387,7 @@ cc_library( hdrs = ["vcu_report_505.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -402,66 +398,18 @@ cc_test( size = "small", srcs = ["vcu_report_505_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) -cc_library( - name = "vehicle_mode_command_105", - srcs = ["vehicle_mode_command_105.cc"], - hdrs = ["vehicle_mode_command_105.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_library( - name = "vin_resp1_514", - srcs = ["vin_resp1_514.cc"], - hdrs = ["vin_resp1_514.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_library( - name = "vin_resp2_515", - srcs = ["vin_resp2_515.cc"], - hdrs = ["vin_resp2_515.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_library( - name = "vin_resp3_516", - srcs = ["vin_resp3_516.cc"], - hdrs = ["vin_resp3_516.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - cc_library( name = "wheelspeed_report_506", srcs = ["wheelspeed_report_506.cc"], hdrs = ["wheelspeed_report_506.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -472,7 +420,7 @@ cc_test( size = "small", srcs = ["wheelspeed_report_506_test.cc"], deps = [ - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", + "//modules/canbus/vehicle/devkit/protocol:canbus_devkit_protocol", "@com_google_googletest//:gtest_main", ], ) diff --git a/modules/canbus/vehicle/devkit/protocol/bms_report_512.cc b/modules/canbus/vehicle/devkit/protocol/bms_report_512.cc new file mode 100644 index 00000000000..47f2d9eec11 --- /dev/null +++ b/modules/canbus/vehicle/devkit/protocol/bms_report_512.cc @@ -0,0 +1,91 @@ +/****************************************************************************** + * 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/canbus/vehicle/devkit/protocol/bms_report_512.h" + +#include "glog/logging.h" +#include "modules/drivers/canbus/common/byte.h" +#include "modules/drivers/canbus/common/canbus_consts.h" + +namespace apollo { +namespace canbus { +namespace devkit { + +using ::apollo::drivers::canbus::Byte; + +Bmsreport512::Bmsreport512() {} +const int32_t Bmsreport512::ID = 0x512; + +void Bmsreport512::Parse(const std::uint8_t* bytes, int32_t length, + ChassisDetail* chassis) const { + chassis->mutable_devkit()->mutable_bms_report_512()->set_battery_current( + battery_current(bytes, length)); + chassis->mutable_devkit()->mutable_bms_report_512()->set_battery_voltage( + battery_voltage(bytes, length)); + chassis->mutable_devkit()->mutable_bms_report_512()->set_battery_soc( + battery_soc(bytes, length)); +} + +// config detail: {'bit': 23, 'description': 'Battery Total Current', +// 'is_signed_var': False, 'len': 16, 'name': 'battery_current', 'offset': +// -3200.0, 'order': 'motorola', 'physical_range': '[-3200|3200]', +// 'physical_unit': 'A', 'precision': 0.1, 'type': 'double'} +double Bmsreport512::battery_current(const std::uint8_t* bytes, + int32_t length) const { + Byte t0(bytes + 2); + int32_t x = t0.get_byte(0, 8); + + Byte t1(bytes + 3); + int32_t t = t1.get_byte(0, 8); + x <<= 8; + x |= t; + + double ret = x * 0.100000 + -3200.000000; + return ret; +} + +// config detail: {'bit': 7, 'description': 'Battery Total Voltage', +// 'is_signed_var': False, 'len': 16, 'name': 'battery_voltage', 'offset': 0.0, +// 'order': 'motorola', 'physical_range': '[0|300]', 'physical_unit': 'V', +// 'precision': 0.01, 'type': 'double'} +double Bmsreport512::battery_voltage(const std::uint8_t* bytes, + int32_t length) const { + Byte t0(bytes + 0); + int32_t x = t0.get_byte(0, 8); + + Byte t1(bytes + 1); + int32_t t = t1.get_byte(0, 8); + x <<= 8; + x |= t; + + double ret = x * 0.010000; + return ret; +} + +// config detail: {'bit': 39, 'description': 'Battery Soc percentage', +// 'is_signed_var': False, 'len': 8, 'name': 'battery_soc', 'offset': 0.0, +// 'order': 'motorola', 'physical_range': '[0|100]', 'physical_unit': '%', +// 'precision': 1.0, 'type': 'int'} +int Bmsreport512::battery_soc(const std::uint8_t* bytes, int32_t length) const { + Byte t0(bytes + 4); + int32_t x = t0.get_byte(0, 8); + + int ret = x; + return ret; +} +} // namespace devkit +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/bms_report_512.h b/modules/canbus/vehicle/devkit/protocol/bms_report_512.h similarity index 56% rename from modules/canbus_vehicle/devkit/protocol/bms_report_512.h rename to modules/canbus/vehicle/devkit/protocol/bms_report_512.h index 55e010cef95..670c330292d 100644 --- a/modules/canbus_vehicle/devkit/protocol/bms_report_512.h +++ b/modules/canbus/vehicle/devkit/protocol/bms_report_512.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace devkit { class Bmsreport512 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Bmsreport512(); void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'bit': 23, 'description': 'Battery Total Current', @@ -48,33 +48,7 @@ class Bmsreport512 : public ::apollo::drivers::canbus::ProtocolData< // 'is_signed_var': False, 'len': 8, 'name': 'Battery_Soc', 'offset': 0.0, // 'order': 'motorola', 'physical_range': '[0|100]', 'physical_unit': '%', // 'precision': 1.0, 'type': 'int'} - int battery_soc_percentage(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 40, 'description': 'Battery Inside temperature', - // 'is_signed_var': False, 'len': 1, 'name': 'Battery_Inside_Temperature', - // 'offset': -40, 'order': 'motorola', 'physical_range': '[-40|215]', - // 'physical_unit': 'C', 'precision': 1.0, 'type': 'int'} - int battery_inside_temperature(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'description': 'Battery Below Low temp fault', 'enum': - // {0: 'BATTERY_FLT_LOW_TEMP_NO_FAULT', 1: - // 'BATTERY_FLT_LOW_TEMP_FAULT'}, 'precision': 1.0, 'len': 1, - // 'name': 'Brake_FLT2', 'is_signed_var': False, 'offset': 0.0, - // 'physical_range': '[0|1]', 'bit': 48, 'type': 'enum', 'order': 'motorola', - // 'physical_unit': ''} - Bms_report_512::Battery_flt_lowtempType battery_flt_low_temp( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'description': 'Battery Over High Temp fault', 'enum': - // {0: 'BATTERY_FLT_OVER_TEMP_NO_FAULT', 1: - // 'BATTERY_FLT_OVER_TEMP_FAULT'}, 'precision': 1.0, 'len': 1, - // 'name': 'Brake_FLT2', 'is_signed_var': False, 'offset': 0.0, - // 'physical_range': '[0|1]', 'bit': 49, 'type': 'enum', 'order': 'motorola', - // 'physical_unit': ''} - Bms_report_512::Battery_flt_overtempType battery_flt_over_temp( - const std::uint8_t* bytes, const int32_t length) const; + int battery_soc(const std::uint8_t* bytes, const int32_t length) const; }; } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/bms_report_512_test.cc b/modules/canbus/vehicle/devkit/protocol/bms_report_512_test.cc similarity index 84% rename from modules/canbus_vehicle/devkit/protocol/bms_report_512_test.cc rename to modules/canbus/vehicle/devkit/protocol/bms_report_512_test.cc index 65d122f7272..50c8523df12 100755 --- a/modules/canbus_vehicle/devkit/protocol/bms_report_512_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/bms_report_512_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/bms_report_512.h" +#include "modules/canbus/vehicle/devkit/protocol/bms_report_512.h" #include "gtest/gtest.h" @@ -29,7 +29,7 @@ class Bmsreport512Test : public ::testing::Test { TEST_F(Bmsreport512Test, General) { uint8_t data[8] = {0x01, 0x00, 0x01, 0x03, 0x52, 0x01, 0x00, 0x01}; int32_t length = 8; - Devkit cd; + ChassisDetail cd; Bmsreport512 bmsreport; bmsreport.Parse(data, length, &cd); @@ -42,9 +42,9 @@ TEST_F(Bmsreport512Test, General) { EXPECT_EQ(data[6], 0b00000000); EXPECT_EQ(data[7], 0b00000001); - EXPECT_EQ(cd.bms_report_512().battery_current(), -3174.1); - EXPECT_EQ(cd.bms_report_512().battery_voltage(), 2.56); - EXPECT_EQ(cd.bms_report_512().battery_soc_percentage(), 82); + EXPECT_EQ(cd.devkit().bms_report_512().battery_current(), -3174.1); + EXPECT_EQ(cd.devkit().bms_report_512().battery_voltage(), 2.56); + EXPECT_EQ(cd.devkit().bms_report_512().battery_soc(), 82); } } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/brake_command_101.cc b/modules/canbus/vehicle/devkit/protocol/brake_command_101.cc similarity index 71% rename from modules/canbus_vehicle/devkit/protocol/brake_command_101.cc rename to modules/canbus/vehicle/devkit/protocol/brake_command_101.cc index a3c4b530848..53a694f7d9d 100755 --- a/modules/canbus_vehicle/devkit/protocol/brake_command_101.cc +++ b/modules/canbus/vehicle/devkit/protocol/brake_command_101.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/brake_command_101.h" +#include "modules/canbus/vehicle/devkit/protocol/brake_command_101.h" #include "modules/drivers/canbus/common/byte.h" @@ -35,20 +35,6 @@ uint32_t Brakecommand101::GetPeriod() const { return PERIOD; } -void Brakecommand101::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_brake_command_101()->set_brake_en_ctrl( - brake_en_ctrl(bytes, length)); - chassis->mutable_brake_command_101()->set_aeb_en_ctrl( - aeb_en_ctrl(bytes, length)); - chassis->mutable_brake_command_101()->set_brake_dec( - brake_dec(bytes, length)); - chassis->mutable_brake_command_101()->set_brake_pedal_target( - brake_pedal_target(bytes, length)); - chassis->mutable_brake_command_101()->set_checksum_101( - checksum_101(bytes, length)); -} - void Brakecommand101::UpdateData(uint8_t* data) { set_p_aeb_en_ctrl(data, aeb_en_ctrl_); set_p_brake_dec(data, brake_dec_); @@ -68,24 +54,6 @@ void Brakecommand101::Reset() { brake_en_ctrl_ = Brake_command_101::BRAKE_EN_CTRL_DISABLE; } -Brakecommand101* Brakecommand101::set_brake_en_ctrl( - Brake_command_101::Brake_en_ctrlType brake_en_ctrl) { - brake_en_ctrl_ = brake_en_ctrl; - return this; -} - -// config detail: {'bit': 0, 'enum': {0: 'BRAKE_EN_CTRL_DISABLE', 1: -// 'BRAKE_EN_CTRL_ENABLE'}, 'is_signed_var': False, 'len': 1, 'name': -// 'Brake_EN_CTRL', 'offset': 0.0, 'order': 'motorola', 'physical_range': -// '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -void Brakecommand101::set_p_brake_en_ctrl( - uint8_t* data, Brake_command_101::Brake_en_ctrlType brake_en_ctrl) { - int x = brake_en_ctrl; - - Byte to_set(data + 0); - to_set.set_value(x, 0, 1); -} - Brakecommand101* Brakecommand101::set_aeb_en_ctrl( Brake_command_101::Aeb_en_ctrlType aeb_en_ctrl) { aeb_en_ctrl_ = aeb_en_ctrl; @@ -127,6 +95,22 @@ void Brakecommand101::set_p_brake_dec(uint8_t* data, double brake_dec) { to_set1.set_value(t, 0, 8); } +Brakecommand101* Brakecommand101::set_checksum_101(int checksum_101) { + checksum_101_ = checksum_101; + return this; +} + +// config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': +// 'CheckSum_101', 'offset': 0.0, 'order': 'motorola', 'physical_range': +// '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': 'int'} +void Brakecommand101::set_p_checksum_101(uint8_t* data, int checksum_101) { + checksum_101 = ProtocolData::BoundedValue(0, 255, checksum_101); + int x = checksum_101; + + Byte to_set(data + 7); + to_set.set_value(x, 0, 8); +} + Brakecommand101* Brakecommand101::set_brake_pedal_target( double brake_pedal_target) { brake_pedal_target_ = brake_pedal_target; @@ -153,77 +137,22 @@ void Brakecommand101::set_p_brake_pedal_target(uint8_t* data, to_set1.set_value(t, 0, 8); } -Brakecommand101* Brakecommand101::set_checksum_101(int checksum_101) { - checksum_101_ = checksum_101; +Brakecommand101* Brakecommand101::set_brake_en_ctrl( + Brake_command_101::Brake_en_ctrlType brake_en_ctrl) { + brake_en_ctrl_ = brake_en_ctrl; return this; } -// config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': -// 'CheckSum_101', 'offset': 0.0, 'order': 'motorola', 'physical_range': -// '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -void Brakecommand101::set_p_checksum_101(uint8_t* data, int checksum_101) { - checksum_101 = ProtocolData::BoundedValue(0, 255, checksum_101); - int x = checksum_101; - - Byte to_set(data + 7); - to_set.set_value(x, 0, 8); -} - -Brake_command_101::Brake_en_ctrlType Brakecommand101::brake_en_ctrl( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 1); - - Brake_command_101::Brake_en_ctrlType ret = - static_cast(x); - return ret; -} - -Brake_command_101::Aeb_en_ctrlType Brakecommand101::aeb_en_ctrl( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(1, 1); - - Brake_command_101::Aeb_en_ctrlType ret = - static_cast(x); - return ret; -} - -double Brakecommand101::brake_dec(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 2); - int32_t t = t1.get_byte(6, 2); - x <<= 8; - x |= t; - - double ret = x * 0.01; - return ret; -} - -double Brakecommand101::brake_pedal_target(const std::uint8_t* bytes, - const int32_t length) const { - Byte t0(bytes + 3); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 4); - int32_t t = t1.get_byte(0, 8); - x <<= 8; - x |= t; - - double ret = x * 0.1; - return ret; -} - -int Brakecommand101::checksum_101(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 8); +// config detail: {'bit': 0, 'enum': {0: 'BRAKE_EN_CTRL_DISABLE', 1: +// 'BRAKE_EN_CTRL_ENABLE'}, 'is_signed_var': False, 'len': 1, 'name': +// 'Brake_EN_CTRL', 'offset': 0.0, 'order': 'motorola', 'physical_range': +// '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +void Brakecommand101::set_p_brake_en_ctrl( + uint8_t* data, Brake_command_101::Brake_en_ctrlType brake_en_ctrl) { + int x = brake_en_ctrl; - int ret = x; - return ret; + Byte to_set(data + 0); + to_set.set_value(x, 0, 1); } } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/brake_command_101.h b/modules/canbus/vehicle/devkit/protocol/brake_command_101.h similarity index 85% rename from modules/canbus_vehicle/devkit/protocol/brake_command_101.h rename to modules/canbus/vehicle/devkit/protocol/brake_command_101.h index c1ab0afc35b..dd821890831 100755 --- a/modules/canbus_vehicle/devkit/protocol/brake_command_101.h +++ b/modules/canbus/vehicle/devkit/protocol/brake_command_101.h @@ -16,8 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" - +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,7 +24,7 @@ namespace canbus { namespace devkit { class Brakecommand101 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -33,20 +32,10 @@ class Brakecommand101 : public ::apollo::drivers::canbus::ProtocolData< uint32_t GetPeriod() const override; - void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; - void UpdateData(uint8_t* data) override; void Reset() override; - // config detail: {'bit': 0, 'enum': {0: 'BRAKE_EN_CTRL_DISABLE', 1: - // 'BRAKE_EN_CTRL_ENABLE'}, 'is_signed_var': False, 'len': 1, 'name': - // 'Brake_EN_CTRL', 'offset': 0.0, 'order': 'motorola', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Brakecommand101* set_brake_en_ctrl( - Brake_command_101::Brake_en_ctrlType brake_en_ctrl); - // config detail: {'bit': 1, 'enum': {0: 'AEB_EN_CTRL_DISABLE_AEB', 1: // 'AEB_EN_CTRL_ENABLE_AEB'}, 'is_signed_var': False, 'len': 1, 'name': // 'AEB_EN_CTRL', 'offset': 0.0, 'order': 'motorola', 'physical_range': @@ -59,24 +48,24 @@ class Brakecommand101 : public ::apollo::drivers::canbus::ProtocolData< // '[0|10]', 'physical_unit': 'm/s^2', 'precision': 0.01, 'type': 'double'} Brakecommand101* set_brake_dec(double brake_dec); - // config detail: {'bit': 31, 'is_signed_var': False, 'len': 16, 'name': - // 'Brake_Pedal_Target', 'offset': 0.0, 'order': 'motorola', 'physical_range': - // '[0|100]', 'physical_unit': '%', 'precision': 0.1, 'type': 'double'} - Brakecommand101* set_brake_pedal_target(double brake_pedal_target); - // config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': // 'CheckSum_101', 'offset': 0.0, 'order': 'motorola', 'physical_range': // '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': 'int'} Brakecommand101* set_checksum_101(int checksum_101); - private: + // config detail: {'bit': 31, 'is_signed_var': False, 'len': 16, 'name': + // 'Brake_Pedal_Target', 'offset': 0.0, 'order': 'motorola', 'physical_range': + // '[0|100]', 'physical_unit': '%', 'precision': 0.1, 'type': 'double'} + Brakecommand101* set_brake_pedal_target(double brake_pedal_target); + // config detail: {'bit': 0, 'enum': {0: 'BRAKE_EN_CTRL_DISABLE', 1: // 'BRAKE_EN_CTRL_ENABLE'}, 'is_signed_var': False, 'len': 1, 'name': // 'Brake_EN_CTRL', 'offset': 0.0, 'order': 'motorola', 'physical_range': // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - void set_p_brake_en_ctrl(uint8_t* data, - Brake_command_101::Brake_en_ctrlType brake_en_ctrl); + Brakecommand101* set_brake_en_ctrl( + Brake_command_101::Brake_en_ctrlType brake_en_ctrl); + private: // config detail: {'bit': 1, 'enum': {0: 'AEB_EN_CTRL_DISABLE_AEB', 1: // 'AEB_EN_CTRL_ENABLE_AEB'}, 'is_signed_var': False, 'len': 1, 'name': // 'AEB_EN_CTRL', 'offset': 0.0, 'order': 'motorola', 'physical_range': @@ -89,29 +78,22 @@ class Brakecommand101 : public ::apollo::drivers::canbus::ProtocolData< // '[0|10]', 'physical_unit': 'm/s^2', 'precision': 0.01, 'type': 'double'} void set_p_brake_dec(uint8_t* data, double brake_dec); - // config detail: {'bit': 31, 'is_signed_var': False, 'len': 16, 'name': - // 'Brake_Pedal_Target', 'offset': 0.0, 'order': 'motorola', 'physical_range': - // '[0|100]', 'physical_unit': '%', 'precision': 0.1, 'type': 'double'} - void set_p_brake_pedal_target(uint8_t* data, double brake_pedal_target); - // config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': // 'CheckSum_101', 'offset': 0.0, 'order': 'motorola', 'physical_range': // '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': 'int'} void set_p_checksum_101(uint8_t* data, int checksum_101); - // report the command - Brake_command_101::Brake_en_ctrlType brake_en_ctrl( - const std::uint8_t* bytes, const int32_t length) const; - - Brake_command_101::Aeb_en_ctrlType aeb_en_ctrl(const std::uint8_t* bytes, - const int32_t length) const; - - double brake_dec(const std::uint8_t* bytes, const int32_t length) const; - - double brake_pedal_target(const std::uint8_t* bytes, - const int32_t length) const; + // config detail: {'bit': 31, 'is_signed_var': False, 'len': 16, 'name': + // 'Brake_Pedal_Target', 'offset': 0.0, 'order': 'motorola', 'physical_range': + // '[0|100]', 'physical_unit': '%', 'precision': 0.1, 'type': 'double'} + void set_p_brake_pedal_target(uint8_t* data, double brake_pedal_target); - int checksum_101(const std::uint8_t* bytes, const int32_t length) const; + // config detail: {'bit': 0, 'enum': {0: 'BRAKE_EN_CTRL_DISABLE', 1: + // 'BRAKE_EN_CTRL_ENABLE'}, 'is_signed_var': False, 'len': 1, 'name': + // 'Brake_EN_CTRL', 'offset': 0.0, 'order': 'motorola', 'physical_range': + // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + void set_p_brake_en_ctrl(uint8_t* data, + Brake_command_101::Brake_en_ctrlType brake_en_ctrl); private: Brake_command_101::Aeb_en_ctrlType aeb_en_ctrl_; diff --git a/modules/canbus_vehicle/devkit/protocol/brake_command_101_test.cc b/modules/canbus/vehicle/devkit/protocol/brake_command_101_test.cc similarity index 95% rename from modules/canbus_vehicle/devkit/protocol/brake_command_101_test.cc rename to modules/canbus/vehicle/devkit/protocol/brake_command_101_test.cc index 17e47a7bfea..d9afc147e18 100755 --- a/modules/canbus_vehicle/devkit/protocol/brake_command_101_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/brake_command_101_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/brake_command_101.h" +#include "modules/canbus/vehicle/devkit/protocol/brake_command_101.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/devkit/protocol/brake_report_501.cc b/modules/canbus/vehicle/devkit/protocol/brake_report_501.cc similarity index 90% rename from modules/canbus_vehicle/devkit/protocol/brake_report_501.cc rename to modules/canbus/vehicle/devkit/protocol/brake_report_501.cc index 859fa086ef8..8588f7f826f 100755 --- a/modules/canbus_vehicle/devkit/protocol/brake_report_501.cc +++ b/modules/canbus/vehicle/devkit/protocol/brake_report_501.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/brake_report_501.h" +#include "modules/canbus/vehicle/devkit/protocol/brake_report_501.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" @@ -30,14 +30,14 @@ Brakereport501::Brakereport501() {} const int32_t Brakereport501::ID = 0x501; void Brakereport501::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_brake_report_501()->set_brake_pedal_actual( + ChassisDetail* chassis) const { + chassis->mutable_devkit()->mutable_brake_report_501()->set_brake_pedal_actual( brake_pedal_actual(bytes, length)); - chassis->mutable_brake_report_501()->set_brake_flt2( + chassis->mutable_devkit()->mutable_brake_report_501()->set_brake_flt2( brake_flt2(bytes, length)); - chassis->mutable_brake_report_501()->set_brake_flt1( + chassis->mutable_devkit()->mutable_brake_report_501()->set_brake_flt1( brake_flt1(bytes, length)); - chassis->mutable_brake_report_501()->set_brake_en_state( + chassis->mutable_devkit()->mutable_brake_report_501()->set_brake_en_state( brake_en_state(bytes, length)); chassis->mutable_check_response()->set_is_esp_online( brake_en_state(bytes, length) == 1); diff --git a/modules/canbus_vehicle/devkit/protocol/brake_report_501.h b/modules/canbus/vehicle/devkit/protocol/brake_report_501.h similarity index 94% rename from modules/canbus_vehicle/devkit/protocol/brake_report_501.h rename to modules/canbus/vehicle/devkit/protocol/brake_report_501.h index 2fab9d65f79..5d293aee121 100755 --- a/modules/canbus_vehicle/devkit/protocol/brake_report_501.h +++ b/modules/canbus/vehicle/devkit/protocol/brake_report_501.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace devkit { class Brakereport501 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Brakereport501(); void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'Brake_Pedal_Actual', 'offset': 0.0, 'precision': diff --git a/modules/canbus_vehicle/devkit/protocol/brake_report_501_test.cc b/modules/canbus/vehicle/devkit/protocol/brake_report_501_test.cc similarity index 81% rename from modules/canbus_vehicle/devkit/protocol/brake_report_501_test.cc rename to modules/canbus/vehicle/devkit/protocol/brake_report_501_test.cc index 5aa3b9ecbf8..28408c192a7 100755 --- a/modules/canbus_vehicle/devkit/protocol/brake_report_501_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/brake_report_501_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/brake_report_501.h" +#include "modules/canbus/vehicle/devkit/protocol/brake_report_501.h" #include "gtest/gtest.h" @@ -29,7 +29,7 @@ class Brakereport501Test : public ::testing::Test { TEST_F(Brakereport501Test, General) { uint8_t data[8] = {0x01, 0x00, 0x01, 0x03, 0x52, 0x01, 0x00, 0x01}; int32_t length = 8; - Devkit cd; + ChassisDetail cd; Brakereport501 brakereport; brakereport.Parse(data, length, &cd); @@ -42,10 +42,10 @@ TEST_F(Brakereport501Test, General) { EXPECT_EQ(data[6], 0b00000000); EXPECT_EQ(data[7], 0b00000001); - EXPECT_EQ(cd.brake_report_501().brake_pedal_actual(), 85); - EXPECT_EQ(cd.brake_report_501().brake_flt2(), 1); - EXPECT_EQ(cd.brake_report_501().brake_flt1(), 0); - EXPECT_EQ(cd.brake_report_501().brake_en_state(), 1); + EXPECT_EQ(cd.devkit().brake_report_501().brake_pedal_actual(), 85); + EXPECT_EQ(cd.devkit().brake_report_501().brake_flt2(), 1); + EXPECT_EQ(cd.devkit().brake_report_501().brake_flt1(), 0); + EXPECT_EQ(cd.devkit().brake_report_501().brake_en_state(), 1); } } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/gear_command_103.cc b/modules/canbus/vehicle/devkit/protocol/gear_command_103.cc similarity index 74% rename from modules/canbus_vehicle/devkit/protocol/gear_command_103.cc rename to modules/canbus/vehicle/devkit/protocol/gear_command_103.cc index 9e439776903..7b70e1c7912 100755 --- a/modules/canbus_vehicle/devkit/protocol/gear_command_103.cc +++ b/modules/canbus/vehicle/devkit/protocol/gear_command_103.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/gear_command_103.h" +#include "modules/canbus/vehicle/devkit/protocol/gear_command_103.h" #include "modules/drivers/canbus/common/byte.h" @@ -29,16 +29,6 @@ const int32_t Gearcommand103::ID = 0x103; // public Gearcommand103::Gearcommand103() { Reset(); } -void Gearcommand103::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_gear_command_103()->set_gear_target( - gear_target(bytes, length)); - chassis->mutable_gear_command_103()->set_gear_en_ctrl( - gear_en_ctrl(bytes, length)); - chassis->mutable_gear_command_103()->set_checksum_103( - checksum_103(bytes, length)); -} - uint32_t Gearcommand103::GetPeriod() const { // TODO(All) : modify every protocol's period manually static const uint32_t PERIOD = 20 * 1000; @@ -113,35 +103,6 @@ void Gearcommand103::set_p_checksum_103(uint8_t* data, int checksum_103) { to_set.set_value(x, 0, 8); } -Gear_command_103::Gear_targetType Gearcommand103::gear_target( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 3); - - Gear_command_103::Gear_targetType ret = - static_cast(x); - return ret; -} - -Gear_command_103::Gear_en_ctrlType Gearcommand103::gear_en_ctrl( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 1); - - Gear_command_103::Gear_en_ctrlType ret = - static_cast(x); - return ret; -} - -int Gearcommand103::checksum_103(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 8); - - int ret = x; - return ret; -} - } // namespace devkit } // namespace canbus } // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/gear_command_103.h b/modules/canbus/vehicle/devkit/protocol/gear_command_103.h similarity index 85% rename from modules/canbus_vehicle/devkit/protocol/gear_command_103.h rename to modules/canbus/vehicle/devkit/protocol/gear_command_103.h index 93c4b1506d9..bec1f5b66f3 100755 --- a/modules/canbus_vehicle/devkit/protocol/gear_command_103.h +++ b/modules/canbus/vehicle/devkit/protocol/gear_command_103.h @@ -16,8 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" - +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,7 +24,7 @@ namespace canbus { namespace devkit { class Gearcommand103 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -33,9 +32,6 @@ class Gearcommand103 : public ::apollo::drivers::canbus::ProtocolData< uint32_t GetPeriod() const override; - void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; - void UpdateData(uint8_t* data) override; void Reset() override; @@ -81,15 +77,6 @@ class Gearcommand103 : public ::apollo::drivers::canbus::ProtocolData< // 'type': 'int', 'order': 'motorola', 'physical_unit': ''} void set_p_checksum_103(uint8_t* data, int checksum_103); - // report the command - Gear_command_103::Gear_targetType gear_target(const std::uint8_t* bytes, - const int32_t length) const; - - Gear_command_103::Gear_en_ctrlType gear_en_ctrl(const std::uint8_t* bytes, - const int32_t length) const; - - int checksum_103(const std::uint8_t* bytes, const int32_t length) const; - private: Gear_command_103::Gear_targetType gear_target_; Gear_command_103::Gear_en_ctrlType gear_en_ctrl_; diff --git a/modules/canbus_vehicle/devkit/protocol/gear_command_103_test.cc b/modules/canbus/vehicle/devkit/protocol/gear_command_103_test.cc similarity index 95% rename from modules/canbus_vehicle/devkit/protocol/gear_command_103_test.cc rename to modules/canbus/vehicle/devkit/protocol/gear_command_103_test.cc index 82a851fc5dc..7ecbccb3cc0 100755 --- a/modules/canbus_vehicle/devkit/protocol/gear_command_103_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/gear_command_103_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/gear_command_103.h" +#include "modules/canbus/vehicle/devkit/protocol/gear_command_103.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/devkit/protocol/gear_report_503.cc b/modules/canbus/vehicle/devkit/protocol/gear_report_503.cc similarity index 90% rename from modules/canbus_vehicle/devkit/protocol/gear_report_503.cc rename to modules/canbus/vehicle/devkit/protocol/gear_report_503.cc index a2cf774efaf..eeae91a08b3 100755 --- a/modules/canbus_vehicle/devkit/protocol/gear_report_503.cc +++ b/modules/canbus/vehicle/devkit/protocol/gear_report_503.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/gear_report_503.h" +#include "modules/canbus/vehicle/devkit/protocol/gear_report_503.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" @@ -30,10 +30,10 @@ Gearreport503::Gearreport503() {} const int32_t Gearreport503::ID = 0x503; void Gearreport503::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_gear_report_503()->set_gear_flt( + ChassisDetail* chassis) const { + chassis->mutable_devkit()->mutable_gear_report_503()->set_gear_flt( gear_flt(bytes, length)); - chassis->mutable_gear_report_503()->set_gear_actual( + chassis->mutable_devkit()->mutable_gear_report_503()->set_gear_actual( gear_actual(bytes, length)); } diff --git a/modules/canbus_vehicle/devkit/protocol/gear_report_503.h b/modules/canbus/vehicle/devkit/protocol/gear_report_503.h similarity index 92% rename from modules/canbus_vehicle/devkit/protocol/gear_report_503.h rename to modules/canbus/vehicle/devkit/protocol/gear_report_503.h index 9c1c0ddb3c3..fc702e97e6a 100755 --- a/modules/canbus_vehicle/devkit/protocol/gear_report_503.h +++ b/modules/canbus/vehicle/devkit/protocol/gear_report_503.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace devkit { class Gearreport503 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Gearreport503(); void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'Gear_FLT', 'enum': {0: 'GEAR_FLT_NO_FAULT', 1: diff --git a/modules/canbus_vehicle/devkit/protocol/gear_report_503_test.cc b/modules/canbus/vehicle/devkit/protocol/gear_report_503_test.cc similarity index 88% rename from modules/canbus_vehicle/devkit/protocol/gear_report_503_test.cc rename to modules/canbus/vehicle/devkit/protocol/gear_report_503_test.cc index 9ed1145f9af..9c58ddb59d2 100755 --- a/modules/canbus_vehicle/devkit/protocol/gear_report_503_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/gear_report_503_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/gear_report_503.h" +#include "modules/canbus/vehicle/devkit/protocol/gear_report_503.h" #include "gtest/gtest.h" @@ -29,7 +29,7 @@ class Gearreport503Test : public ::testing::Test { TEST_F(Gearreport503Test, General) { uint8_t data[8] = {0x04, 0x01, 0x01, 0x10, 0x90, 0x01, 0x00, 0x01}; int32_t length = 8; - Devkit cd; + ChassisDetail cd; Gearreport503 gearreport; gearreport.Parse(data, length, &cd); @@ -42,8 +42,8 @@ TEST_F(Gearreport503Test, General) { EXPECT_EQ(data[6], 0b00000000); EXPECT_EQ(data[7], 0b00000001); - EXPECT_EQ(cd.gear_report_503().gear_flt(), 1); - EXPECT_EQ(cd.gear_report_503().gear_actual(), 4); + EXPECT_EQ(cd.devkit().gear_report_503().gear_flt(), 1); + EXPECT_EQ(cd.devkit().gear_report_503().gear_actual(), 4); } } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/park_command_104.cc b/modules/canbus/vehicle/devkit/protocol/park_command_104.cc similarity index 73% rename from modules/canbus_vehicle/devkit/protocol/park_command_104.cc rename to modules/canbus/vehicle/devkit/protocol/park_command_104.cc index 754cac9b685..dd768d0c9b2 100755 --- a/modules/canbus_vehicle/devkit/protocol/park_command_104.cc +++ b/modules/canbus/vehicle/devkit/protocol/park_command_104.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/park_command_104.h" +#include "modules/canbus/vehicle/devkit/protocol/park_command_104.h" #include "modules/drivers/canbus/common/byte.h" @@ -35,16 +35,6 @@ uint32_t Parkcommand104::GetPeriod() const { return PERIOD; } -void Parkcommand104::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_park_command_104()->set_park_target( - park_target(bytes, length)); - chassis->mutable_park_command_104()->set_park_en_ctrl( - park_en_ctrl(bytes, length)); - chassis->mutable_park_command_104()->set_checksum_104( - checksum_104(bytes, length)); -} - void Parkcommand104::UpdateData(uint8_t* data) { set_p_park_target(data, park_target_); set_p_park_en_ctrl(data, park_en_ctrl_); @@ -112,35 +102,6 @@ void Parkcommand104::set_p_park_en_ctrl( to_set.set_value(x, 0, 1); } -Park_command_104::Park_targetType Parkcommand104::park_target( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 3); - - Park_command_104::Park_targetType ret = - static_cast(x); - return ret; -} - -Park_command_104::Park_en_ctrlType Parkcommand104::park_en_ctrl( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 1); - - Park_command_104::Park_en_ctrlType ret = - static_cast(x); - return ret; -} - -int Parkcommand104::checksum_104(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 8); - - int ret = x; - return ret; -} - } // namespace devkit } // namespace canbus } // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/park_command_104.h b/modules/canbus/vehicle/devkit/protocol/park_command_104.h similarity index 84% rename from modules/canbus_vehicle/devkit/protocol/park_command_104.h rename to modules/canbus/vehicle/devkit/protocol/park_command_104.h index 0e89557d86b..5a7607dcb8e 100755 --- a/modules/canbus_vehicle/devkit/protocol/park_command_104.h +++ b/modules/canbus/vehicle/devkit/protocol/park_command_104.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace devkit { class Parkcommand104 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -32,9 +32,6 @@ class Parkcommand104 : public ::apollo::drivers::canbus::ProtocolData< uint32_t GetPeriod() const override; - void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; - void UpdateData(uint8_t* data) override; void Reset() override; @@ -78,15 +75,6 @@ class Parkcommand104 : public ::apollo::drivers::canbus::ProtocolData< void set_p_park_en_ctrl(uint8_t* data, Park_command_104::Park_en_ctrlType park_en_ctrl); - // report the command - Park_command_104::Park_targetType park_target(const std::uint8_t* bytes, - const int32_t length) const; - - Park_command_104::Park_en_ctrlType park_en_ctrl(const std::uint8_t* bytes, - const int32_t length) const; - - int checksum_104(const std::uint8_t* bytes, const int32_t length) const; - private: int checksum_104_; Park_command_104::Park_targetType park_target_; diff --git a/modules/canbus_vehicle/devkit/protocol/park_command_104_test.cc b/modules/canbus/vehicle/devkit/protocol/park_command_104_test.cc similarity index 95% rename from modules/canbus_vehicle/devkit/protocol/park_command_104_test.cc rename to modules/canbus/vehicle/devkit/protocol/park_command_104_test.cc index 9547a47e097..49aa2ef9236 100755 --- a/modules/canbus_vehicle/devkit/protocol/park_command_104_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/park_command_104_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/park_command_104.h" +#include "modules/canbus/vehicle/devkit/protocol/park_command_104.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/devkit/protocol/park_report_504.cc b/modules/canbus/vehicle/devkit/protocol/park_report_504.cc similarity index 90% rename from modules/canbus_vehicle/devkit/protocol/park_report_504.cc rename to modules/canbus/vehicle/devkit/protocol/park_report_504.cc index 22a21d76f96..dc00ef61518 100755 --- a/modules/canbus_vehicle/devkit/protocol/park_report_504.cc +++ b/modules/canbus/vehicle/devkit/protocol/park_report_504.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/park_report_504.h" +#include "modules/canbus/vehicle/devkit/protocol/park_report_504.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" @@ -30,10 +30,10 @@ Parkreport504::Parkreport504() {} const int32_t Parkreport504::ID = 0x504; void Parkreport504::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_park_report_504()->set_parking_actual( + ChassisDetail* chassis) const { + chassis->mutable_devkit()->mutable_park_report_504()->set_parking_actual( parking_actual(bytes, length)); - chassis->mutable_park_report_504()->set_park_flt( + chassis->mutable_devkit()->mutable_park_report_504()->set_park_flt( park_flt(bytes, length)); } diff --git a/modules/canbus_vehicle/devkit/protocol/park_report_504.h b/modules/canbus/vehicle/devkit/protocol/park_report_504.h similarity index 91% rename from modules/canbus_vehicle/devkit/protocol/park_report_504.h rename to modules/canbus/vehicle/devkit/protocol/park_report_504.h index 4b3fd9b409b..a18ffc1bef9 100755 --- a/modules/canbus_vehicle/devkit/protocol/park_report_504.h +++ b/modules/canbus/vehicle/devkit/protocol/park_report_504.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace devkit { class Parkreport504 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Parkreport504(); void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'Parking_actual', 'enum': {0: diff --git a/modules/canbus_vehicle/devkit/protocol/park_report_504_test.cc b/modules/canbus/vehicle/devkit/protocol/park_report_504_test.cc similarity index 87% rename from modules/canbus_vehicle/devkit/protocol/park_report_504_test.cc rename to modules/canbus/vehicle/devkit/protocol/park_report_504_test.cc index ccbcc5d8a0d..7a89845c2e8 100755 --- a/modules/canbus_vehicle/devkit/protocol/park_report_504_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/park_report_504_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/park_report_504.h" +#include "modules/canbus/vehicle/devkit/protocol/park_report_504.h" #include "gtest/gtest.h" @@ -29,7 +29,7 @@ class Parkreport504Test : public ::testing::Test { TEST_F(Parkreport504Test, General) { uint8_t data[8] = {0x04, 0x01, 0x01, 0x10, 0x90, 0x01, 0x00, 0x01}; int32_t length = 8; - Devkit cd; + ChassisDetail cd; Parkreport504 parkreport; parkreport.Parse(data, length, &cd); @@ -42,8 +42,8 @@ TEST_F(Parkreport504Test, General) { EXPECT_EQ(data[6], 0b00000000); EXPECT_EQ(data[7], 0b00000001); - EXPECT_EQ(cd.park_report_504().parking_actual(), 0); - EXPECT_EQ(cd.park_report_504().park_flt(), 1); + EXPECT_EQ(cd.devkit().park_report_504().parking_actual(), 0); + EXPECT_EQ(cd.devkit().park_report_504().park_flt(), 1); } } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/steering_command_102.cc b/modules/canbus/vehicle/devkit/protocol/steering_command_102.cc similarity index 61% rename from modules/canbus_vehicle/devkit/protocol/steering_command_102.cc rename to modules/canbus/vehicle/devkit/protocol/steering_command_102.cc index d7ec048eb8d..d9ba2bbc2bd 100755 --- a/modules/canbus_vehicle/devkit/protocol/steering_command_102.cc +++ b/modules/canbus/vehicle/devkit/protocol/steering_command_102.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/steering_command_102.h" +#include "modules/canbus/vehicle/devkit/protocol/steering_command_102.h" #include "modules/drivers/canbus/common/byte.h" @@ -35,22 +35,10 @@ uint32_t Steeringcommand102::GetPeriod() const { return PERIOD; } -void Steeringcommand102::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_steering_command_102()->set_steer_en_ctrl( - steer_en_ctrl(bytes, length)); - chassis->mutable_steering_command_102() ->set_steer_angle_target( - steer_angle_target(bytes, length)); - chassis->mutable_steering_command_102()->set_steer_angle_spd_target( - steer_angle_spd_target(bytes, length)); - chassis->mutable_steering_command_102()->set_checksum_102( - checksum_102(bytes, length)); -} - void Steeringcommand102::UpdateData(uint8_t* data) { set_p_steer_en_ctrl(data, steer_en_ctrl_); set_p_steer_angle_target(data, steer_angle_target_); - set_p_steer_angle_spd_target(data, steer_angle_spd_target_); + set_p_steer_angle_spd(data, steer_angle_spd_); checksum_102_ = data[0] ^ data[1] ^ data[2] ^ data[3] ^ data[4] ^ data[5] ^ data[6]; set_p_checksum_102(data, checksum_102_); @@ -60,7 +48,7 @@ void Steeringcommand102::Reset() { // TODO(All) : you should check this manually steer_en_ctrl_ = Steering_command_102::STEER_EN_CTRL_DISABLE; steer_angle_target_ = 0; - steer_angle_spd_target_ = 0; + steer_angle_spd_ = 0; checksum_102_ = 0; } @@ -90,8 +78,8 @@ Steeringcommand102* Steeringcommand102::set_steer_angle_target( // config detail: {'bit': 31, 'is_signed_var': False, 'len': 16, 'name': // 'Steer_ANGLE_Target', 'offset': -500.0, 'order': 'motorola', -// 'physical_range': '[-500|500]''right -, left +', 'physical_unit': 'deg', -// 'precision': 1.0, 'type': 'int'} +// 'physical_range': '[-500|500]', 'physical_unit': 'deg', 'precision': 1.0, +// 'type': 'int'} void Steeringcommand102::set_p_steer_angle_target(uint8_t* data, int steer_angle_target) { steer_angle_target = @@ -109,21 +97,19 @@ void Steeringcommand102::set_p_steer_angle_target(uint8_t* data, to_set1.set_value(t, 0, 8); } -Steeringcommand102* Steeringcommand102::set_steer_angle_spd_target( - int steer_angle_spd_target) { - steer_angle_spd_target_ = steer_angle_spd_target; +Steeringcommand102* Steeringcommand102::set_steer_angle_spd( + int steer_angle_spd) { + steer_angle_spd_ = steer_angle_spd; return this; } // config detail: {'bit': 15, 'is_signed_var': False, 'len': 8, 'name': -// 'Steer_ANGLE_SPD_Target', 'offset': 0.0, 'order': 'motorola', -// 'physical_range': '[0|250]', 'physical_unit': 'deg/s', 'precision': 1.0, -// 'type': 'int'} -void Steeringcommand102::set_p_steer_angle_spd_target( - uint8_t* data, int steer_angle_spd_target) { - steer_angle_spd_target = - ProtocolData::BoundedValue(0, 250, steer_angle_spd_target); - int x = steer_angle_spd_target; +// 'Steer_ANGLE_SPD', 'offset': 0.0, 'order': 'motorola', 'physical_range': +// '[0|250]', 'physical_unit': 'deg/s', 'precision': 1.0, 'type': 'int'} +void Steeringcommand102::set_p_steer_angle_spd(uint8_t* data, + int steer_angle_spd) { + steer_angle_spd = ProtocolData::BoundedValue(0, 250, steer_angle_spd); + int x = steer_angle_spd; Byte to_set(data + 1); to_set.set_value(x, 0, 8); @@ -145,48 +131,6 @@ void Steeringcommand102::set_p_checksum_102(uint8_t* data, int checksum_102) { to_set.set_value(x, 0, 8); } -Steering_command_102::Steer_en_ctrlType Steeringcommand102::steer_en_ctrl( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 1); - - Steering_command_102::Steer_en_ctrlType ret = - static_cast(x); - return ret; -} - -double Steeringcommand102::steer_angle_target(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 3); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 4); - int32_t t = t1.get_byte(0, 8); - x <<= 8; - x |= t; - - double ret = x * 1 + -500.000000; - return ret; -} - -double Steeringcommand102::steer_angle_spd_target(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 1; - return ret; -} - -int Steeringcommand102::checksum_102(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 8); - - int ret = x; - return ret; -} - } // namespace devkit } // namespace canbus } // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/steering_command_102.h b/modules/canbus/vehicle/devkit/protocol/steering_command_102.h similarity index 72% rename from modules/canbus_vehicle/devkit/protocol/steering_command_102.h rename to modules/canbus/vehicle/devkit/protocol/steering_command_102.h index e11fc2b4de6..dc4406594f8 100755 --- a/modules/canbus_vehicle/devkit/protocol/steering_command_102.h +++ b/modules/canbus/vehicle/devkit/protocol/steering_command_102.h @@ -16,8 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" - +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,7 +24,7 @@ namespace canbus { namespace devkit { class Steeringcommand102 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -33,9 +32,6 @@ class Steeringcommand102 : public ::apollo::drivers::canbus::ProtocolData< uint32_t GetPeriod() const override; - void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; - void UpdateData(uint8_t* data) override; void Reset() override; @@ -49,15 +45,14 @@ class Steeringcommand102 : public ::apollo::drivers::canbus::ProtocolData< // config detail: {'bit': 31, 'is_signed_var': False, 'len': 16, 'name': // 'Steer_ANGLE_Target', 'offset': -500.0, 'order': 'motorola', - // 'physical_range': '[-500|500]''right -, left +', 'physical_unit': 'deg', - // 'precision': 1.0, 'type': 'int'} + // 'physical_range': '[-500|500]', 'physical_unit': 'deg', 'precision': 1.0, + // 'type': 'int'} Steeringcommand102* set_steer_angle_target(int steer_angle_target); // config detail: {'bit': 15, 'is_signed_var': False, 'len': 8, 'name': - // 'Steer_ANGLE_SPD_Target', 'offset': 0.0, 'order': 'motorola', - // 'physical_range': '[0|250]', 'physical_unit': 'deg/s', 'precision': 1.0, - // 'type': 'int'} - Steeringcommand102* set_steer_angle_spd_target(int steer_angle_spd_target); + // 'Steer_ANGLE_SPD', 'offset': 0.0, 'order': 'motorola', 'physical_range': + // '[0|250]', 'physical_unit': 'deg/s', 'precision': 1.0, 'type': 'int'} + Steeringcommand102* set_steer_angle_spd(int steer_angle_spd); // config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': // 'CheckSum_102', 'offset': 0.0, 'order': 'motorola', 'physical_range': @@ -79,32 +74,19 @@ class Steeringcommand102 : public ::apollo::drivers::canbus::ProtocolData< void set_p_steer_angle_target(uint8_t* data, int steer_angle_target); // config detail: {'bit': 15, 'is_signed_var': False, 'len': 8, 'name': - // 'Steer_ANGLE_SPD_Target', 'offset': 0.0, 'order': 'motorola', - // 'physical_range': '[0|250]', 'physical_unit': 'deg/s', 'precision': 1.0, - // 'type': 'int'} - void set_p_steer_angle_spd_target(uint8_t* data, int steer_angle_spd_target); + // 'Steer_ANGLE_SPD', 'offset': 0.0, 'order': 'motorola', 'physical_range': + // '[0|250]', 'physical_unit': 'deg/s', 'precision': 1.0, 'type': 'int'} + void set_p_steer_angle_spd(uint8_t* data, int steer_angle_spd); // config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': // 'CheckSum_102', 'offset': 0.0, 'order': 'motorola', 'physical_range': // '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': 'int'} void set_p_checksum_102(uint8_t* data, int checksum_102); - // report the command - Steering_command_102::Steer_en_ctrlType steer_en_ctrl( - const std::uint8_t* bytes, const int32_t length) const; - - double steer_angle_target(const std::uint8_t* bytes, - const int32_t length) const; - - double steer_angle_spd_target(const std::uint8_t* bytes, - const int32_t length) const; - - int checksum_102(const std::uint8_t* bytes, const int32_t length) const; - private: Steering_command_102::Steer_en_ctrlType steer_en_ctrl_; int steer_angle_target_; - int steer_angle_spd_target_; + int steer_angle_spd_; int checksum_102_; }; diff --git a/modules/canbus_vehicle/devkit/protocol/steering_command_102_test.cc b/modules/canbus/vehicle/devkit/protocol/steering_command_102_test.cc similarity index 95% rename from modules/canbus_vehicle/devkit/protocol/steering_command_102_test.cc rename to modules/canbus/vehicle/devkit/protocol/steering_command_102_test.cc index b1acd814559..dc30d46297c 100755 --- a/modules/canbus_vehicle/devkit/protocol/steering_command_102_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/steering_command_102_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/steering_command_102.h" +#include "modules/canbus/vehicle/devkit/protocol/steering_command_102.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/devkit/protocol/steering_report_502.cc b/modules/canbus/vehicle/devkit/protocol/steering_report_502.cc similarity index 77% rename from modules/canbus_vehicle/devkit/protocol/steering_report_502.cc rename to modules/canbus/vehicle/devkit/protocol/steering_report_502.cc index cacb9106cea..92fd3dd16f4 100755 --- a/modules/canbus_vehicle/devkit/protocol/steering_report_502.cc +++ b/modules/canbus/vehicle/devkit/protocol/steering_report_502.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/steering_report_502.h" +#include "modules/canbus/vehicle/devkit/protocol/steering_report_502.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" @@ -30,48 +30,30 @@ Steeringreport502::Steeringreport502() {} const int32_t Steeringreport502::ID = 0x502; void Steeringreport502::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_steering_report_502()->set_steer_angle_rear_actual( - steer_angle_rear_actual(bytes, length)); - chassis->mutable_steering_report_502()->set_steer_angle_spd_actual( - steer_angle_spd_actual(bytes, length)); - chassis->mutable_steering_report_502()->set_steer_flt2( + ChassisDetail* chassis) const { + chassis->mutable_devkit() + ->mutable_steering_report_502() + ->set_steer_angle_spd_actual(steer_angle_spd_actual(bytes, length)); + chassis->mutable_devkit()->mutable_steering_report_502()->set_steer_flt2( steer_flt2(bytes, length)); - chassis->mutable_steering_report_502()->set_steer_flt1( + chassis->mutable_devkit()->mutable_steering_report_502()->set_steer_flt1( steer_flt1(bytes, length)); - chassis->mutable_steering_report_502()->set_steer_en_state( + chassis->mutable_devkit()->mutable_steering_report_502()->set_steer_en_state( steer_en_state(bytes, length)); - chassis->mutable_steering_report_502()->set_steer_angle_actual( - steer_angle_actual(bytes, length)); + chassis->mutable_devkit() + ->mutable_steering_report_502() + ->set_steer_angle_actual(steer_angle_actual(bytes, length)); chassis->mutable_check_response()->set_is_eps_online( steer_en_state(bytes, length) == 1); } -// config detail: {'bit': 47, 'is_signed_var': False, 'len': 16, 'name': -// 'steer_angle_rear_actual', 'offset': -500.0, 'order': 'motorola', -// 'physical_range': '[-500|500]', 'physical_unit': 'deg', 'precision': 1.0, -// 'type': 'int'} -int Steeringreport502::steer_angle_rear_actual(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 5); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 6); - int32_t t = t1.get_byte(0, 8); - x <<= 8; - x |= t; - - int ret = x + -500.000000; - return ret; -} - -// config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': +// config detail: {'bit': 55, 'is_signed_var': False, 'len': 8, 'name': // 'steer_angle_spd_actual', 'offset': 0.0, 'order': 'motorola', // 'physical_range': '[0|0]', 'physical_unit': 'deg/s', 'precision': 1.0, // 'type': 'int'} int Steeringreport502::steer_angle_spd_actual(const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 7); + Byte t0(bytes + 6); int32_t x = t0.get_byte(0, 8); int ret = x; diff --git a/modules/canbus_vehicle/devkit/protocol/steering_report_502.h b/modules/canbus/vehicle/devkit/protocol/steering_report_502.h similarity index 84% rename from modules/canbus_vehicle/devkit/protocol/steering_report_502.h rename to modules/canbus/vehicle/devkit/protocol/steering_report_502.h index 19f41cdf697..10e951cbf3a 100755 --- a/modules/canbus_vehicle/devkit/protocol/steering_report_502.h +++ b/modules/canbus/vehicle/devkit/protocol/steering_report_502.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,22 +24,15 @@ namespace canbus { namespace devkit { class Steeringreport502 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Steeringreport502(); void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; + ChassisDetail* chassis) const override; private: - // config detail: {'bit': 47, 'is_signed_var': False, 'len': 16, 'name': - // 'Steer_ANGLE_Rear_Actual', 'offset': -500.0, 'order': 'motorola', - // 'physical_range': '[-500|500]', 'physical_unit': 'deg', 'precision': 1.0, - // 'type': 'int'} - int steer_angle_rear_actual(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': + // config detail: {'bit': 55, 'is_signed_var': False, 'len': 8, 'name': // 'Steer_ANGLE_SPD_Actual', 'offset': 0.0, 'order': 'motorola', // 'physical_range': '[0|0]', 'physical_unit': 'deg/s', 'precision': 1.0, // 'type': 'int'} diff --git a/modules/canbus_vehicle/devkit/protocol/steering_report_502_test.cc b/modules/canbus/vehicle/devkit/protocol/steering_report_502_test.cc similarity index 77% rename from modules/canbus_vehicle/devkit/protocol/steering_report_502_test.cc rename to modules/canbus/vehicle/devkit/protocol/steering_report_502_test.cc index 17b5d65b142..11739a07304 100644 --- a/modules/canbus_vehicle/devkit/protocol/steering_report_502_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/steering_report_502_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/steering_report_502.h" +#include "modules/canbus/vehicle/devkit/protocol/steering_report_502.h" #include "gtest/gtest.h" @@ -30,7 +30,7 @@ class Steeringreport502Test : public ::testing::Test { TEST_F(Steeringreport502Test, General) { uint8_t data[8] = {0x04, 0x01, 0x01, 0x14, 0x1E, 0x03, 0x04, 0x05}; int32_t length = 8; - Devkit cd; + ChassisDetail cd; Steeringreport502 steeringreport; steeringreport.Parse(data, length, &cd); @@ -43,12 +43,11 @@ TEST_F(Steeringreport502Test, General) { EXPECT_EQ(data[6], 0b00000100); EXPECT_EQ(data[7], 0b00000101); - EXPECT_EQ(cd.steering_report_502().steer_angle_spd_actual(), 5); - EXPECT_EQ(cd.steering_report_502().steer_flt2(), 1); - EXPECT_EQ(cd.steering_report_502().steer_flt1(), 1); - EXPECT_EQ(cd.steering_report_502().steer_en_state(), 0); - EXPECT_EQ(cd.steering_report_502().steer_angle_actual(), 4650); - EXPECT_EQ(cd.steering_report_502().steer_angle_rear_actual(), 272); + EXPECT_EQ(cd.devkit().steering_report_502().steer_angle_spd_actual(), 4); + EXPECT_EQ(cd.devkit().steering_report_502().steer_flt2(), 1); + EXPECT_EQ(cd.devkit().steering_report_502().steer_flt1(), 1); + EXPECT_EQ(cd.devkit().steering_report_502().steer_en_state(), 0); + EXPECT_EQ(cd.devkit().steering_report_502().steer_angle_actual(), 4650); } } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/throttle_command_100.cc b/modules/canbus/vehicle/devkit/protocol/throttle_command_100.cc similarity index 60% rename from modules/canbus_vehicle/devkit/protocol/throttle_command_100.cc rename to modules/canbus/vehicle/devkit/protocol/throttle_command_100.cc index f3db492e8be..6733b5e63d9 100755 --- a/modules/canbus_vehicle/devkit/protocol/throttle_command_100.cc +++ b/modules/canbus/vehicle/devkit/protocol/throttle_command_100.cc @@ -14,12 +14,9 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/throttle_command_100.h" - -#include "glog/logging.h" +#include "modules/canbus/vehicle/devkit/protocol/throttle_command_100.h" #include "modules/drivers/canbus/common/byte.h" -#include "modules/drivers/canbus/common/canbus_consts.h" namespace apollo { namespace canbus { @@ -38,22 +35,7 @@ uint32_t Throttlecommand100::GetPeriod() const { return PERIOD; } -void Throttlecommand100::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_throttle_command_100()->set_throttle_en_ctrl( - throttle_en_ctrl(bytes, length)); - chassis->mutable_throttle_command_100()->set_throttle_acc( - throttle_acc(bytes, length)); - chassis->mutable_throttle_command_100()->set_throttle_pedal_target( - throttle_pedal_target(bytes, length)); - chassis->mutable_throttle_command_100()->set_speed_target( - speed_target(bytes, length)); - chassis->mutable_throttle_command_100()->set_checksum_100( - checksum_100(bytes, length)); -} - void Throttlecommand100::UpdateData(uint8_t* data) { - set_p_speed_target(data, speed_target_); set_p_throttle_acc(data, throttle_acc_); set_p_throttle_pedal_target(data, throttle_pedal_target_); set_p_throttle_en_ctrl(data, throttle_en_ctrl_); @@ -64,30 +46,10 @@ void Throttlecommand100::UpdateData(uint8_t* data) { void Throttlecommand100::Reset() { // TODO(All) : you should check this manually - throttle_en_ctrl_ = Throttle_command_100::THROTTLE_EN_CTRL_DISABLE; throttle_acc_ = 0.0; - throttle_pedal_target_ = 0.0; - speed_target_ = 0.0; checksum_100_ = 0; -} - -Throttlecommand100* Throttlecommand100::set_throttle_en_ctrl( - Throttle_command_100::Throttle_en_ctrlType throttle_en_ctrl) { - throttle_en_ctrl_ = throttle_en_ctrl; - return this; -} - -// config detail: {'name': 'Throttle_EN_CTRL', 'enum': {0: -// 'THROTTLE_EN_CTRL_DISABLE', 1: 'THROTTLE_EN_CTRL_ENABLE'}, 'precision': 1.0, -// 'len': 1, 'is_signed_var': False, 'offset': 0.0, 'physical_range': '[0|1]', -// 'bit': 0, 'type': 'enum', 'order': 'motorola', 'physical_unit': ''} -void Throttlecommand100::set_p_throttle_en_ctrl( - uint8_t* data, - Throttle_command_100::Throttle_en_ctrlType throttle_en_ctrl) { - int x = throttle_en_ctrl; - - Byte to_set(data + 0); - to_set.set_value(x, 0, 1); + throttle_pedal_target_ = 0.0; + throttle_en_ctrl_ = Throttle_command_100::THROTTLE_EN_CTRL_DISABLE; } Throttlecommand100* Throttlecommand100::set_throttle_acc(double throttle_acc) { @@ -114,6 +76,22 @@ void Throttlecommand100::set_p_throttle_acc(uint8_t* data, to_set1.set_value(t, 0, 8); } +Throttlecommand100* Throttlecommand100::set_checksum_100(int checksum_100) { + checksum_100_ = checksum_100; + return this; +} + +// config detail: {'name': 'CheckSum_100', 'offset': 0.0, 'precision': 1.0, +// 'len': 8, 'is_signed_var': False, 'physical_range': '[0|255]', 'bit': 63, +// 'type': 'int', 'order': 'motorola', 'physical_unit': ''} +void Throttlecommand100::set_p_checksum_100(uint8_t* data, int checksum_100) { + checksum_100 = ProtocolData::BoundedValue(0, 255, checksum_100); + int x = checksum_100; + + Byte to_set(data + 7); + to_set.set_value(x, 0, 8); +} + Throttlecommand100* Throttlecommand100::set_throttle_pedal_target( double throttle_pedal_target) { throttle_pedal_target_ = throttle_pedal_target; @@ -140,105 +118,23 @@ void Throttlecommand100::set_p_throttle_pedal_target( to_set1.set_value(t, 0, 8); } -Throttlecommand100* Throttlecommand100::set_speed_target(double speed_target) { - speed_target_ = speed_target; - return this; -} - -// config detail: {'bit': 47, 'is_signed_var': False, 'len': 10, 'name': -// 'Speed_Target', 'offset': 0.0, 'order': 'motorola', 'physical_range': -// '[0|10.23]', 'physical_unit': 'm/s', 'precision': 0.01, 'type': 'double'} -void Throttlecommand100::set_p_speed_target(uint8_t* data, - double speed_target) { - speed_target = ProtocolData::BoundedValue(0.0, 10.23, speed_target); - int x = speed_target / 0.010000; - uint8_t t = 0; - - t = x & 0x3; - Byte to_set0(data + 6); - to_set0.set_value(t, 6, 2); - x >>= 2; - - t = x & 0xFF; - Byte to_set1(data + 5); - to_set1.set_value(t, 0, 8); -} - -Throttlecommand100* Throttlecommand100::set_checksum_100(int checksum_100) { - checksum_100_ = checksum_100; +Throttlecommand100* Throttlecommand100::set_throttle_en_ctrl( + Throttle_command_100::Throttle_en_ctrlType throttle_en_ctrl) { + throttle_en_ctrl_ = throttle_en_ctrl; return this; } -// config detail: {'name': 'CheckSum_100', 'offset': 0.0, 'precision': 1.0, -// 'len': 8, 'is_signed_var': False, 'physical_range': '[0|255]', 'bit': 63, -// 'type': 'int', 'order': 'motorola', 'physical_unit': ''} -void Throttlecommand100::set_p_checksum_100(uint8_t* data, int checksum_100) { - checksum_100 = ProtocolData::BoundedValue(0, 255, checksum_100); - int x = checksum_100; - - Byte to_set(data + 7); - to_set.set_value(x, 0, 8); -} - -Throttle_command_100::Throttle_en_ctrlType Throttlecommand100::throttle_en_ctrl( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 1); - - Throttle_command_100::Throttle_en_ctrlType ret = - static_cast(x); - return ret; -} - -double Throttlecommand100::throttle_acc(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 2); - int32_t t = t1.get_byte(6, 2); - x <<= 8; - x |= t; - - double ret = x * 0.01; - return ret; -} - -double Throttlecommand100::throttle_pedal_target(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 3); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 4); - int32_t t = t1.get_byte(0, 8); - x <<= 8; - x |= t; - - double ret = x * 0.100000; - return ret; -} - -double Throttlecommand100::speed_target(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 5); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 6); - int32_t t = t1.get_byte(6, 2); - x <<= 8; - x |= t; - - double ret = x * 0.100000; - return ret; -} - -int Throttlecommand100::checksum_100(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 8); +// config detail: {'name': 'Throttle_EN_CTRL', 'enum': {0: +// 'THROTTLE_EN_CTRL_DISABLE', 1: 'THROTTLE_EN_CTRL_ENABLE'}, 'precision': 1.0, +// 'len': 1, 'is_signed_var': False, 'offset': 0.0, 'physical_range': '[0|1]', +// 'bit': 0, 'type': 'enum', 'order': 'motorola', 'physical_unit': ''} +void Throttlecommand100::set_p_throttle_en_ctrl( + uint8_t* data, + Throttle_command_100::Throttle_en_ctrlType throttle_en_ctrl) { + int x = throttle_en_ctrl; - int ret = x; - return ret; + Byte to_set(data + 0); + to_set.set_value(x, 0, 1); } } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/throttle_command_100.h b/modules/canbus/vehicle/devkit/protocol/throttle_command_100.h similarity index 75% rename from modules/canbus_vehicle/devkit/protocol/throttle_command_100.h rename to modules/canbus/vehicle/devkit/protocol/throttle_command_100.h index c21b96e6707..2b348f8986b 100755 --- a/modules/canbus_vehicle/devkit/protocol/throttle_command_100.h +++ b/modules/canbus/vehicle/devkit/protocol/throttle_command_100.h @@ -16,8 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" - +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,7 +24,7 @@ namespace canbus { namespace devkit { class Throttlecommand100 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -37,87 +36,61 @@ class Throttlecommand100 : public ::apollo::drivers::canbus::ProtocolData< void Reset() override; - void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; - - // config detail: {'name': 'Throttle_EN_CTRL', 'enum': {0: - // 'THROTTLE_EN_CTRL_DISABLE', 1: 'THROTTLE_EN_CTRL_ENABLE'}, - // 'precision': 1.0, 'len': 1, 'is_signed_var': False, 'offset': 0.0, - // 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', 'order': 'motorola', - // 'physical_unit': ''} - Throttlecommand100* set_throttle_en_ctrl( - Throttle_command_100::Throttle_en_ctrlType throttle_en_ctrl); - // config detail: {'name': 'Throttle_Acc', 'offset': 0.0, 'precision': 0.01, // 'len': 10, 'is_signed_var': False, 'physical_range': '[0|10]', 'bit': 15, // 'type': 'double', 'order': 'motorola', 'physical_unit': 'm/s^2'} Throttlecommand100* set_throttle_acc(double throttle_acc); + // config detail: {'name': 'CheckSum_100', 'offset': 0.0, 'precision': 1.0, + // 'len': 8, 'is_signed_var': False, 'physical_range': '[0|255]', 'bit': 63, + // 'type': 'int', 'order': 'motorola', 'physical_unit': ''} + Throttlecommand100* set_checksum_100(int checksum_100); + // config detail: {'name': 'Throttle_Pedal_Target', 'offset': 0.0, // 'precision': 0.1, 'len': 16, 'is_signed_var': False, 'physical_range': // '[0|100]', 'bit': 31, 'type': 'double', 'order': 'motorola', // 'physical_unit': '%'} Throttlecommand100* set_throttle_pedal_target(double throttle_pedal_target); - // config detail: {'bit': 47, 'is_signed_var': False, 'len': 10, 'name': - // 'Speed_Target', 'offset': 0.0, 'order': 'motorola', 'physical_range': - // '[0|10.23]', 'physical_unit': 'm/s', 'precision': 0.01, 'type': 'double'} - Throttlecommand100* set_speed_target(double speed_target); - - // config detail: {'name': 'CheckSum_100', 'offset': 0.0, 'precision': 1.0, - // 'len': 8, 'is_signed_var': False, 'physical_range': '[0|255]', 'bit': 63, - // 'type': 'int', 'order': 'motorola', 'physical_unit': ''} - Throttlecommand100* set_checksum_100(int checksum_100); - - private: // config detail: {'name': 'Throttle_EN_CTRL', 'enum': {0: // 'THROTTLE_EN_CTRL_DISABLE', 1: 'THROTTLE_EN_CTRL_ENABLE'}, // 'precision': 1.0, 'len': 1, 'is_signed_var': False, 'offset': 0.0, // 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', 'order': 'motorola', // 'physical_unit': ''} - void set_p_throttle_en_ctrl( - uint8_t* data, + Throttlecommand100* set_throttle_en_ctrl( Throttle_command_100::Throttle_en_ctrlType throttle_en_ctrl); + private: // config detail: {'name': 'Throttle_Acc', 'offset': 0.0, 'precision': 0.01, // 'len': 10, 'is_signed_var': False, 'physical_range': '[0|10]', 'bit': 15, // 'type': 'double', 'order': 'motorola', 'physical_unit': 'm/s^2'} void set_p_throttle_acc(uint8_t* data, double throttle_acc); - // config detail: {'name': 'Throttle_Pedal_Target', 'offset': 0.0, - // 'precision': 0.1, 'len': 16, 'is_signed_var': False, 'physical_range': - // '[0|100]', 'bit': 31, 'type': 'double', 'order': 'motorola', - // 'physical_unit': '%'} - void set_p_throttle_pedal_target(uint8_t* data, double throttle_pedal_target); - - // config detail: {'bit': 47, 'is_signed_var': False, 'len': 10, 'name': - // 'Speed_Target', 'offset': 0.0, 'order': 'motorola', 'physical_range': - // '[0|10.23]', 'physical_unit': 'm/s', 'precision': 0.01, 'type': 'double'} - void set_p_speed_target(uint8_t* data, double speed_target); - // config detail: {'name': 'CheckSum_100', 'offset': 0.0, 'precision': 1.0, // 'len': 8, 'is_signed_var': False, 'physical_range': '[0|255]', 'bit': 63, // 'type': 'int', 'order': 'motorola', 'physical_unit': ''} void set_p_checksum_100(uint8_t* data, int checksum_100); - Throttle_command_100::Throttle_en_ctrlType throttle_en_ctrl( - const std::uint8_t* bytes, const int32_t length) const; - - double throttle_acc(const std::uint8_t* bytes, const int32_t length) const; - - double throttle_pedal_target(const std::uint8_t* bytes, - const int32_t length) const; - - double speed_target(const std::uint8_t* bytes, const int32_t length) const; + // config detail: {'name': 'Throttle_Pedal_Target', 'offset': 0.0, + // 'precision': 0.1, 'len': 16, 'is_signed_var': False, 'physical_range': + // '[0|100]', 'bit': 31, 'type': 'double', 'order': 'motorola', + // 'physical_unit': '%'} + void set_p_throttle_pedal_target(uint8_t* data, double throttle_pedal_target); - int checksum_100(const std::uint8_t* bytes, const int32_t length) const; + // config detail: {'name': 'Throttle_EN_CTRL', 'enum': {0: + // 'THROTTLE_EN_CTRL_DISABLE', 1: 'THROTTLE_EN_CTRL_ENABLE'}, + // 'precision': 1.0, 'len': 1, 'is_signed_var': False, 'offset': 0.0, + // 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', 'order': 'motorola', + // 'physical_unit': ''} + void set_p_throttle_en_ctrl( + uint8_t* data, + Throttle_command_100::Throttle_en_ctrlType throttle_en_ctrl); private: - Throttle_command_100::Throttle_en_ctrlType throttle_en_ctrl_; double throttle_acc_; - double throttle_pedal_target_; - double speed_target_; int checksum_100_; + double throttle_pedal_target_; + Throttle_command_100::Throttle_en_ctrlType throttle_en_ctrl_; }; } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/throttle_command_100_test.cc b/modules/canbus/vehicle/devkit/protocol/throttle_command_100_test.cc similarity index 89% rename from modules/canbus_vehicle/devkit/protocol/throttle_command_100_test.cc rename to modules/canbus/vehicle/devkit/protocol/throttle_command_100_test.cc index a82102b501b..f94307f7d6a 100755 --- a/modules/canbus_vehicle/devkit/protocol/throttle_command_100_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/throttle_command_100_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/throttle_command_100.h" +#include "modules/canbus/vehicle/devkit/protocol/throttle_command_100.h" #include "gtest/gtest.h" @@ -36,9 +36,9 @@ TEST_F(Throttlecommand100Test, simple) { EXPECT_EQ(data[2], 0b00110011); EXPECT_EQ(data[3], 0b00000000); EXPECT_EQ(data[4], 0b00000000); - EXPECT_EQ(data[5], 0b00000000); - EXPECT_EQ(data[6], 0b00110111); - EXPECT_EQ(data[7], 0b01110100); + EXPECT_EQ(data[5], 0b01110110); + EXPECT_EQ(data[6], 0b01110111); + EXPECT_EQ(data[7], 0b01000010); } } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/throttle_report_500.cc b/modules/canbus/vehicle/devkit/protocol/throttle_report_500.cc similarity index 87% rename from modules/canbus_vehicle/devkit/protocol/throttle_report_500.cc rename to modules/canbus/vehicle/devkit/protocol/throttle_report_500.cc index 42fc15ae4ed..6c2050eba57 100755 --- a/modules/canbus_vehicle/devkit/protocol/throttle_report_500.cc +++ b/modules/canbus/vehicle/devkit/protocol/throttle_report_500.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/throttle_report_500.h" +#include "modules/canbus/vehicle/devkit/protocol/throttle_report_500.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" @@ -30,15 +30,17 @@ Throttlereport500::Throttlereport500() {} const int32_t Throttlereport500::ID = 0x500; void Throttlereport500::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_throttle_report_500()->set_throttle_pedal_actual( - throttle_pedal_actual(bytes, length)); - chassis->mutable_throttle_report_500()->set_throttle_flt2( + ChassisDetail* chassis) const { + chassis->mutable_devkit() + ->mutable_throttle_report_500() + ->set_throttle_pedal_actual(throttle_pedal_actual(bytes, length)); + chassis->mutable_devkit()->mutable_throttle_report_500()->set_throttle_flt2( throttle_flt2(bytes, length)); - chassis->mutable_throttle_report_500()->set_throttle_flt1( + chassis->mutable_devkit()->mutable_throttle_report_500()->set_throttle_flt1( throttle_flt1(bytes, length)); - chassis->mutable_throttle_report_500()->set_throttle_en_state( - throttle_en_state(bytes, length)); + chassis->mutable_devkit() + ->mutable_throttle_report_500() + ->set_throttle_en_state(throttle_en_state(bytes, length)); chassis->mutable_check_response()->set_is_vcu_online( throttle_en_state(bytes, length) == 1); } diff --git a/modules/canbus_vehicle/devkit/protocol/throttle_report_500.h b/modules/canbus/vehicle/devkit/protocol/throttle_report_500.h similarity index 94% rename from modules/canbus_vehicle/devkit/protocol/throttle_report_500.h rename to modules/canbus/vehicle/devkit/protocol/throttle_report_500.h index d3d4f885bca..2f5d2e4b610 100755 --- a/modules/canbus_vehicle/devkit/protocol/throttle_report_500.h +++ b/modules/canbus/vehicle/devkit/protocol/throttle_report_500.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace devkit { class Throttlereport500 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Throttlereport500(); void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'Throttle_Pedal_Actual', 'offset': 0.0, diff --git a/modules/canbus_vehicle/devkit/protocol/throttle_report_500_test.cc b/modules/canbus/vehicle/devkit/protocol/throttle_report_500_test.cc similarity index 80% rename from modules/canbus_vehicle/devkit/protocol/throttle_report_500_test.cc rename to modules/canbus/vehicle/devkit/protocol/throttle_report_500_test.cc index dd799884c71..87ac95234e1 100755 --- a/modules/canbus_vehicle/devkit/protocol/throttle_report_500_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/throttle_report_500_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/throttle_report_500.h" +#include "modules/canbus/vehicle/devkit/protocol/throttle_report_500.h" #include "gtest/gtest.h" @@ -29,7 +29,7 @@ class Throttlereport500Test : public ::testing::Test { TEST_F(Throttlereport500Test, General) { uint8_t data[8] = {0x07, 0x01, 0x01, 0x02, 0x8A, 0x03, 0x04, 0x05}; int32_t length = 8; - Devkit cd; + ChassisDetail cd; Throttlereport500 throttlereport; throttlereport.Parse(data, length, &cd); @@ -42,10 +42,10 @@ TEST_F(Throttlereport500Test, General) { EXPECT_EQ(data[6], 0b00000100); EXPECT_EQ(data[7], 0b00000101); - EXPECT_EQ(cd.throttle_report_500().throttle_pedal_actual(), 65); - EXPECT_EQ(cd.throttle_report_500().throttle_flt2(), 1); - EXPECT_EQ(cd.throttle_report_500().throttle_flt1(), 1); - EXPECT_EQ(cd.throttle_report_500().throttle_en_state(), 3); + EXPECT_EQ(cd.devkit().throttle_report_500().throttle_pedal_actual(), 65); + EXPECT_EQ(cd.devkit().throttle_report_500().throttle_flt2(), 1); + EXPECT_EQ(cd.devkit().throttle_report_500().throttle_flt1(), 1); + EXPECT_EQ(cd.devkit().throttle_report_500().throttle_en_state(), 3); } } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_1_507.cc b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_1_507.cc similarity index 86% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_1_507.cc rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_1_507.cc index 4845eb8da2b..c55660059c1 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_1_507.cc +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_1_507.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_1_507.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_1_507.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" @@ -30,15 +30,17 @@ Ultrsensor1507::Ultrsensor1507() {} const int32_t Ultrsensor1507::ID = 0x507; void Ultrsensor1507::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_ultr_sensor_1_507()->set_uiuss9_tof_direct( + ChassisDetail* chassis) const { + chassis->mutable_devkit()->mutable_ultr_sensor_1_507()->set_uiuss9_tof_direct( uiuss9_tof_direct(bytes, length)); - chassis->mutable_ultr_sensor_1_507()->set_uiuss8_tof_direct( + chassis->mutable_devkit()->mutable_ultr_sensor_1_507()->set_uiuss8_tof_direct( uiuss8_tof_direct(bytes, length)); - chassis->mutable_ultr_sensor_1_507()->set_uiuss11_tof_direct( - uiuss11_tof_direct(bytes, length)); - chassis->mutable_ultr_sensor_1_507()->set_uiuss10_tof_direct( - uiuss10_tof_direct(bytes, length)); + chassis->mutable_devkit() + ->mutable_ultr_sensor_1_507() + ->set_uiuss11_tof_direct(uiuss11_tof_direct(bytes, length)); + chassis->mutable_devkit() + ->mutable_ultr_sensor_1_507() + ->set_uiuss10_tof_direct(uiuss10_tof_direct(bytes, length)); } // config detail: {'name': 'uiuss9_tof_direct', 'offset': 0.0, 'precision': diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_1_507.h b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_1_507.h similarity index 93% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_1_507.h rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_1_507.h index 6859830e455..851248d1c45 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_1_507.h +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_1_507.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace devkit { class Ultrsensor1507 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Ultrsensor1507(); void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'uiUSS9_ToF_Direct', 'offset': 0.0, 'precision': diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_1_507_test.cc b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_1_507_test.cc similarity index 80% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_1_507_test.cc rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_1_507_test.cc index d64c55821fd..f94066c936d 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_1_507_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_1_507_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_1_507.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_1_507.h" #include "gtest/gtest.h" @@ -29,7 +29,7 @@ class Ultrsensor1507Test : public ::testing::Test { TEST_F(Ultrsensor1507Test, General) { uint8_t data[8] = {0xE2, 0x95, 0x06, 0x58, 0x08, 0xD6, 0x02, 0x44}; int32_t length = 8; - Devkit cd; + ChassisDetail cd; Ultrsensor1507 ultrsensor1; ultrsensor1.Parse(data, length, &cd); @@ -42,10 +42,10 @@ TEST_F(Ultrsensor1507Test, General) { EXPECT_EQ(data[6], 0b00000010); EXPECT_EQ(data[7], 0b01000100); - EXPECT_EQ(cd.ultr_sensor_1_507().uiuss9_tof_direct(), 28); - EXPECT_EQ(cd.ultr_sensor_1_507().uiuss8_tof_direct(), 1000); - EXPECT_EQ(cd.ultr_sensor_1_507().uiuss11_tof_direct(), 10); - EXPECT_EQ(cd.ultr_sensor_1_507().uiuss10_tof_direct(), 39); + EXPECT_EQ(cd.devkit().ultr_sensor_1_507().uiuss9_tof_direct(), 28); + EXPECT_EQ(cd.devkit().ultr_sensor_1_507().uiuss8_tof_direct(), 1000); + EXPECT_EQ(cd.devkit().ultr_sensor_1_507().uiuss11_tof_direct(), 10); + EXPECT_EQ(cd.devkit().ultr_sensor_1_507().uiuss10_tof_direct(), 39); } } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_2_508.cc b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_2_508.cc similarity index 83% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_2_508.cc rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_2_508.cc index 5136b910334..b33a21d52a1 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_2_508.cc +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_2_508.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_2_508.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_2_508.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" @@ -30,15 +30,19 @@ Ultrsensor2508::Ultrsensor2508() {} const int32_t Ultrsensor2508::ID = 0x508; void Ultrsensor2508::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_ultr_sensor_2_508()->set_uiuss9_tof_indirect( - uiuss9_tof_indirect(bytes, length)); - chassis->mutable_ultr_sensor_2_508()->set_uiuss8_tof_indirect( - uiuss8_tof_indirect(bytes, length)); - chassis->mutable_ultr_sensor_2_508()->set_uiuss11_tof_indirect( - uiuss11_tof_indirect(bytes, length)); - chassis->mutable_ultr_sensor_2_508()->set_uiuss10_tof_indirect( - uiuss10_tof_indirect(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_devkit() + ->mutable_ultr_sensor_2_508() + ->set_uiuss9_tof_indirect(uiuss9_tof_indirect(bytes, length)); + chassis->mutable_devkit() + ->mutable_ultr_sensor_2_508() + ->set_uiuss8_tof_indirect(uiuss8_tof_indirect(bytes, length)); + chassis->mutable_devkit() + ->mutable_ultr_sensor_2_508() + ->set_uiuss11_tof_indirect(uiuss11_tof_indirect(bytes, length)); + chassis->mutable_devkit() + ->mutable_ultr_sensor_2_508() + ->set_uiuss10_tof_indirect(uiuss10_tof_indirect(bytes, length)); } // config detail: {'name': 'uiuss9_tof_indirect', 'offset': 0.0, 'precision': diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_2_508.h b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_2_508.h similarity index 93% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_2_508.h rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_2_508.h index 3add6a5c5c9..a54f9ca2203 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_2_508.h +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_2_508.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace devkit { class Ultrsensor2508 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Ultrsensor2508(); void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'uiUSS9_ToF_Indirect', 'offset': 0.0, 'precision': diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_2_508_test.cc b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_2_508_test.cc similarity index 79% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_2_508_test.cc rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_2_508_test.cc index 4a688e3cb10..8d09cd48e2f 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_2_508_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_2_508_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_2_508.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_2_508.h" #include "gtest/gtest.h" @@ -29,7 +29,7 @@ class Ultrsensor2508Test : public ::testing::Test { TEST_F(Ultrsensor2508Test, General) { uint8_t data[8] = {0xE2, 0x95, 0x06, 0x58, 0x08, 0xD6, 0x02, 0x44}; int32_t length = 8; - Devkit cd; + ChassisDetail cd; Ultrsensor2508 ultrsensor2; ultrsensor2.Parse(data, length, &cd); @@ -42,10 +42,10 @@ TEST_F(Ultrsensor2508Test, General) { EXPECT_EQ(data[6], 0b00000010); EXPECT_EQ(data[7], 0b01000100); - EXPECT_EQ(cd.ultr_sensor_2_508().uiuss9_tof_indirect(), 28); - EXPECT_EQ(cd.ultr_sensor_2_508().uiuss8_tof_indirect(), 1000); - EXPECT_EQ(cd.ultr_sensor_2_508().uiuss11_tof_indirect(), 10); - EXPECT_EQ(cd.ultr_sensor_2_508().uiuss10_tof_indirect(), 39); + EXPECT_EQ(cd.devkit().ultr_sensor_2_508().uiuss9_tof_indirect(), 28); + EXPECT_EQ(cd.devkit().ultr_sensor_2_508().uiuss8_tof_indirect(), 1000); + EXPECT_EQ(cd.devkit().ultr_sensor_2_508().uiuss11_tof_indirect(), 10); + EXPECT_EQ(cd.devkit().ultr_sensor_2_508().uiuss10_tof_indirect(), 39); } } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_3_509.cc b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_3_509.cc similarity index 88% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_3_509.cc rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_3_509.cc index 4e064c298a2..bce9999dc96 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_3_509.cc +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_3_509.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_3_509.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_3_509.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" @@ -30,14 +30,14 @@ Ultrsensor3509::Ultrsensor3509() {} const int32_t Ultrsensor3509::ID = 0x509; void Ultrsensor3509::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_ultr_sensor_3_509()->set_uiuss5_tof_direct( + ChassisDetail* chassis) const { + chassis->mutable_devkit()->mutable_ultr_sensor_3_509()->set_uiuss5_tof_direct( uiuss5_tof_direct(bytes, length)); - chassis->mutable_ultr_sensor_3_509()->set_uiuss4_tof_direct( + chassis->mutable_devkit()->mutable_ultr_sensor_3_509()->set_uiuss4_tof_direct( uiuss4_tof_direct(bytes, length)); - chassis->mutable_ultr_sensor_3_509()->set_uiuss3_tof_direct( + chassis->mutable_devkit()->mutable_ultr_sensor_3_509()->set_uiuss3_tof_direct( uiuss3_tof_direct(bytes, length)); - chassis->mutable_ultr_sensor_3_509()->set_uiuss2_tof_direct( + chassis->mutable_devkit()->mutable_ultr_sensor_3_509()->set_uiuss2_tof_direct( uiuss2_tof_direct(bytes, length)); } diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_3_509.h b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_3_509.h similarity index 93% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_3_509.h rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_3_509.h index 17ae50311f6..392e546acb1 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_3_509.h +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_3_509.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace devkit { class Ultrsensor3509 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Ultrsensor3509(); void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'uiUSS5_ToF_Direct', 'offset': 0.0, 'precision': diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_3_509_test.cc b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_3_509_test.cc similarity index 80% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_3_509_test.cc rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_3_509_test.cc index 7ac352264b1..5d3cb10efe5 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_3_509_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_3_509_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_3_509.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_3_509.h" #include "gtest/gtest.h" @@ -29,7 +29,7 @@ class Ultrsensor3509Test : public ::testing::Test { TEST_F(Ultrsensor3509Test, General) { uint8_t data[8] = {0xE2, 0x95, 0x06, 0x58, 0x08, 0xD6, 0x02, 0x44}; int32_t length = 8; - Devkit cd; + ChassisDetail cd; Ultrsensor3509 ultrsensor3; ultrsensor3.Parse(data, length, &cd); @@ -42,10 +42,10 @@ TEST_F(Ultrsensor3509Test, General) { EXPECT_EQ(data[6], 0b00000010); EXPECT_EQ(data[7], 0b01000100); - EXPECT_EQ(cd.ultr_sensor_3_509().uiuss5_tof_direct(), 10); - EXPECT_EQ(cd.ultr_sensor_3_509().uiuss4_tof_direct(), 39); - EXPECT_EQ(cd.ultr_sensor_3_509().uiuss3_tof_direct(), 28); - EXPECT_EQ(cd.ultr_sensor_3_509().uiuss2_tof_direct(), 1000); + EXPECT_EQ(cd.devkit().ultr_sensor_3_509().uiuss5_tof_direct(), 10); + EXPECT_EQ(cd.devkit().ultr_sensor_3_509().uiuss4_tof_direct(), 39); + EXPECT_EQ(cd.devkit().ultr_sensor_3_509().uiuss3_tof_direct(), 28); + EXPECT_EQ(cd.devkit().ultr_sensor_3_509().uiuss2_tof_direct(), 1000); } } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_4_510.cc b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_4_510.cc similarity index 83% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_4_510.cc rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_4_510.cc index c94483dd3fa..a2076547c1a 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_4_510.cc +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_4_510.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_4_510.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_4_510.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" @@ -30,15 +30,19 @@ Ultrsensor4510::Ultrsensor4510() {} const int32_t Ultrsensor4510::ID = 0x510; void Ultrsensor4510::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_ultr_sensor_4_510()->set_uiuss5_tof_indirect( - uiuss5_tof_indirect(bytes, length)); - chassis->mutable_ultr_sensor_4_510()->set_uiuss4_tof_indirect( - uiuss4_tof_indirect(bytes, length)); - chassis->mutable_ultr_sensor_4_510()->set_uiuss3_tof_indirect( - uiuss3_tof_indirect(bytes, length)); - chassis->mutable_ultr_sensor_4_510()->set_uiuss2_tof_indirect( - uiuss2_tof_indirect(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_devkit() + ->mutable_ultr_sensor_4_510() + ->set_uiuss5_tof_indirect(uiuss5_tof_indirect(bytes, length)); + chassis->mutable_devkit() + ->mutable_ultr_sensor_4_510() + ->set_uiuss4_tof_indirect(uiuss4_tof_indirect(bytes, length)); + chassis->mutable_devkit() + ->mutable_ultr_sensor_4_510() + ->set_uiuss3_tof_indirect(uiuss3_tof_indirect(bytes, length)); + chassis->mutable_devkit() + ->mutable_ultr_sensor_4_510() + ->set_uiuss2_tof_indirect(uiuss2_tof_indirect(bytes, length)); } // config detail: {'name': 'uiuss5_tof_indirect', 'offset': 0.0, 'precision': diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_4_510.h b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_4_510.h similarity index 93% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_4_510.h rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_4_510.h index e92086dcff2..92a3d4767e7 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_4_510.h +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_4_510.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace devkit { class Ultrsensor4510 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Ultrsensor4510(); void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'uiUSS5_ToF_Indirect', 'offset': 0.0, 'precision': diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_4_510_test.cc b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_4_510_test.cc similarity index 80% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_4_510_test.cc rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_4_510_test.cc index d6ffe273fb0..39a69fe7372 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_4_510_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_4_510_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_4_510.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_4_510.h" #include "gtest/gtest.h" @@ -29,7 +29,7 @@ class Ultrsensor4510Test : public ::testing::Test { TEST_F(Ultrsensor4510Test, General) { uint8_t data[8] = {0xE2, 0x95, 0x06, 0x58, 0x08, 0xD6, 0x02, 0x44}; int32_t length = 8; - Devkit cd; + ChassisDetail cd; Ultrsensor4510 ultrsensor4; ultrsensor4.Parse(data, length, &cd); @@ -42,10 +42,10 @@ TEST_F(Ultrsensor4510Test, General) { EXPECT_EQ(data[6], 0b00000010); EXPECT_EQ(data[7], 0b01000100); - EXPECT_EQ(cd.ultr_sensor_4_510().uiuss5_tof_indirect(), 10); - EXPECT_EQ(cd.ultr_sensor_4_510().uiuss4_tof_indirect(), 39); - EXPECT_EQ(cd.ultr_sensor_4_510().uiuss3_tof_indirect(), 28); - EXPECT_EQ(cd.ultr_sensor_4_510().uiuss2_tof_indirect(), 1000); + EXPECT_EQ(cd.devkit().ultr_sensor_4_510().uiuss5_tof_indirect(), 10); + EXPECT_EQ(cd.devkit().ultr_sensor_4_510().uiuss4_tof_indirect(), 39); + EXPECT_EQ(cd.devkit().ultr_sensor_4_510().uiuss3_tof_indirect(), 28); + EXPECT_EQ(cd.devkit().ultr_sensor_4_510().uiuss2_tof_indirect(), 1000); } } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_5_511.cc b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_5_511.cc similarity index 88% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_5_511.cc rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_5_511.cc index 08ca6afd32a..fd7e9cdd5d2 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_5_511.cc +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_5_511.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_5_511.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_5_511.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" @@ -30,14 +30,14 @@ Ultrsensor5511::Ultrsensor5511() {} const int32_t Ultrsensor5511::ID = 0x511; void Ultrsensor5511::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_ultr_sensor_5_511()->set_uiuss7_tof_direct( + ChassisDetail* chassis) const { + chassis->mutable_devkit()->mutable_ultr_sensor_5_511()->set_uiuss7_tof_direct( uiuss7_tof_direct(bytes, length)); - chassis->mutable_ultr_sensor_5_511()->set_uiuss6_tof_direct( + chassis->mutable_devkit()->mutable_ultr_sensor_5_511()->set_uiuss6_tof_direct( uiuss6_tof_direct(bytes, length)); - chassis->mutable_ultr_sensor_5_511()->set_uiuss1_tof_direct( + chassis->mutable_devkit()->mutable_ultr_sensor_5_511()->set_uiuss1_tof_direct( uiuss1_tof_direct(bytes, length)); - chassis->mutable_ultr_sensor_5_511()->set_uiuss0_tof_direct( + chassis->mutable_devkit()->mutable_ultr_sensor_5_511()->set_uiuss0_tof_direct( uiuss0_tof_direct(bytes, length)); } diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_5_511.h b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_5_511.h similarity index 93% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_5_511.h rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_5_511.h index 28875929ade..adbbf284a34 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_5_511.h +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_5_511.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace devkit { class Ultrsensor5511 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Ultrsensor5511(); void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'uiUSS7_ToF_Direct', 'offset': 0.0, 'precision': diff --git a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_5_511_test.cc b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_5_511_test.cc similarity index 80% rename from modules/canbus_vehicle/devkit/protocol/ultr_sensor_5_511_test.cc rename to modules/canbus/vehicle/devkit/protocol/ultr_sensor_5_511_test.cc index fb0e9f8b178..833cd7ddd2f 100755 --- a/modules/canbus_vehicle/devkit/protocol/ultr_sensor_5_511_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/ultr_sensor_5_511_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/ultr_sensor_5_511.h" +#include "modules/canbus/vehicle/devkit/protocol/ultr_sensor_5_511.h" #include "gtest/gtest.h" @@ -29,7 +29,7 @@ class Ultrsensor5511Test : public ::testing::Test { TEST_F(Ultrsensor5511Test, General) { uint8_t data[8] = {0xE2, 0x95, 0x06, 0x58, 0x08, 0xD6, 0x02, 0x44}; int32_t length = 8; - Devkit cd; + ChassisDetail cd; Ultrsensor5511 ultrsensor5; ultrsensor5.Parse(data, length, &cd); @@ -42,10 +42,10 @@ TEST_F(Ultrsensor5511Test, General) { EXPECT_EQ(data[6], 0b00000010); EXPECT_EQ(data[7], 0b01000100); - EXPECT_EQ(cd.ultr_sensor_5_511().uiuss7_tof_direct(), 10); - EXPECT_EQ(cd.ultr_sensor_5_511().uiuss6_tof_direct(), 39); - EXPECT_EQ(cd.ultr_sensor_5_511().uiuss1_tof_direct(), 28); - EXPECT_EQ(cd.ultr_sensor_5_511().uiuss0_tof_direct(), 1000); + EXPECT_EQ(cd.devkit().ultr_sensor_5_511().uiuss7_tof_direct(), 10); + EXPECT_EQ(cd.devkit().ultr_sensor_5_511().uiuss6_tof_direct(), 39); + EXPECT_EQ(cd.devkit().ultr_sensor_5_511().uiuss1_tof_direct(), 28); + EXPECT_EQ(cd.devkit().ultr_sensor_5_511().uiuss0_tof_direct(), 1000); } } // namespace devkit diff --git a/modules/canbus/vehicle/devkit/protocol/vcu_report_505.cc b/modules/canbus/vehicle/devkit/protocol/vcu_report_505.cc new file mode 100755 index 00000000000..43834429f71 --- /dev/null +++ b/modules/canbus/vehicle/devkit/protocol/vcu_report_505.cc @@ -0,0 +1,143 @@ +/****************************************************************************** + * 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/canbus/vehicle/devkit/protocol/vcu_report_505.h" + +#include "glog/logging.h" + +#include "modules/drivers/canbus/common/byte.h" +#include "modules/drivers/canbus/common/canbus_consts.h" + +namespace apollo { +namespace canbus { +namespace devkit { + +using ::apollo::drivers::canbus::Byte; + +Vcureport505::Vcureport505() {} +const int32_t Vcureport505::ID = 0x505; + +void Vcureport505::Parse(const std::uint8_t* bytes, int32_t length, + ChassisDetail* chassis) const { + chassis->mutable_devkit()->mutable_vcu_report_505()->set_vehicle_mode_state( + vehicle_mode_state(bytes, length)); + chassis->mutable_devkit()->mutable_vcu_report_505()->set_frontcrash_state( + frontcrash_state(bytes, length)); + chassis->mutable_devkit()->mutable_vcu_report_505()->set_backcrash_state( + backcrash_state(bytes, length)); + chassis->mutable_devkit()->mutable_vcu_report_505()->set_aeb_state( + aeb_state(bytes, length)); + chassis->mutable_devkit()->mutable_vcu_report_505()->set_acc( + acc(bytes, length)); + chassis->mutable_devkit()->mutable_vcu_report_505()->set_speed( + speed(bytes, length)); +} + +// config detail: {'bit': 36, 'enum': {0: +// 'VEHICLE_MODE_STATE_MANUAL_REMOTE_MODE', 1: 'VEHICLE_MODE_STATE_AUTO_MODE', +// 2: 'VEHICLE_MODE_STATE_EMERGENCY_MODE', 3: +// 'VEHICLE_MODE_STATE_STANDBY_MODE'}, 'is_signed_var': False, 'len': 2, 'name': +// 'vehicle_mode_state', 'offset': 0.0, 'order': 'motorola', 'physical_range': +// '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +Vcu_report_505::Vehicle_mode_stateType Vcureport505::vehicle_mode_state( + const std::uint8_t* bytes, int32_t length) const { + Byte t0(bytes + 4); + int32_t x = t0.get_byte(3, 2); + + Vcu_report_505::Vehicle_mode_stateType ret = + static_cast(x); + return ret; +} + +// config detail: {'bit': 33, 'enum': {0: 'FRONTCRASH_STATE_NO_EVENT', 1: +// 'FRONTCRASH_STATE_CRASH_EVENT'}, 'is_signed_var': False, 'len': 1, 'name': +// 'frontcrash_state', 'offset': 0.0, 'order': 'motorola', 'physical_range': +// '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +Vcu_report_505::Frontcrash_stateType Vcureport505::frontcrash_state( + const std::uint8_t* bytes, int32_t length) const { + Byte t0(bytes + 4); + int32_t x = t0.get_byte(1, 1); + + Vcu_report_505::Frontcrash_stateType ret = + static_cast(x); + return ret; +} + +// config detail: {'bit': 34, 'enum': {0: 'BACKCRASH_STATE_NO_EVENT', 1: +// 'BACKCRASH_STATE_CRASH_EVENT'}, 'is_signed_var': False, 'len': 1, 'name': +// 'backcrash_state', 'offset': 0.0, 'order': 'motorola', 'physical_range': +// '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +Vcu_report_505::Backcrash_stateType Vcureport505::backcrash_state( + const std::uint8_t* bytes, int32_t length) const { + Byte t0(bytes + 4); + int32_t x = t0.get_byte(2, 1); + + Vcu_report_505::Backcrash_stateType ret = + static_cast(x); + return ret; +} + +// config detail: {'bit': 32, 'enum': {0: 'AEB_STATE_INACTIVE', 1: +// 'AEB_STATE_ACTIVE'}, 'is_signed_var': False, 'len': 1, 'name': 'aeb_state', +// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|0]', +// 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} +Vcu_report_505::Aeb_stateType Vcureport505::aeb_state(const std::uint8_t* bytes, + int32_t length) const { + Byte t0(bytes + 4); + int32_t x = t0.get_byte(0, 1); + + Vcu_report_505::Aeb_stateType ret = + static_cast(x); + return ret; +} + +// config detail: {'bit': 7, 'is_signed_var': True, 'len': 12, 'name': 'acc', +// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[-10|10]', +// 'physical_unit': 'm/s^2', 'precision': 0.01, 'type': 'double'} +double Vcureport505::acc(const std::uint8_t* bytes, int32_t length) const { + Byte t0(bytes + 0); + int32_t x = t0.get_byte(0, 8); + + Byte t1(bytes + 1); + int32_t t = t1.get_byte(4, 4); + x <<= 4; + x |= t; + + x <<= 20; + x >>= 20; + + double ret = x * 0.010000; + return ret; +} + +// config detail: {'bit': 23, 'is_signed_var': False, 'len': 16, 'name': +// 'speed', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|65.535]', +// 'physical_unit': 'm/s', 'precision': 0.001, 'type': 'double'} +double Vcureport505::speed(const std::uint8_t* bytes, int32_t length) const { + Byte t0(bytes + 2); + int32_t x = t0.get_byte(0, 8); + + Byte t1(bytes + 3); + int32_t t = t1.get_byte(0, 8); + x <<= 8; + x |= t; + + double ret = x * 0.001000; + return ret; +} +} // namespace devkit +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus/vehicle/devkit/protocol/vcu_report_505.h b/modules/canbus/vehicle/devkit/protocol/vcu_report_505.h new file mode 100755 index 00000000000..4f59d9634f5 --- /dev/null +++ b/modules/canbus/vehicle/devkit/protocol/vcu_report_505.h @@ -0,0 +1,79 @@ +/****************************************************************************** + * 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 "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" +#include "modules/drivers/canbus/can_comm/protocol_data.h" + +namespace apollo { +namespace canbus { +namespace devkit { + +class Vcureport505 : public ::apollo::drivers::canbus::ProtocolData< + ::apollo::canbus::ChassisDetail> { + public: + static const int32_t ID; + Vcureport505(); + void Parse(const std::uint8_t* bytes, int32_t length, + ChassisDetail* chassis) const override; + + private: + // config detail: {'bit': 36, 'enum': {0: + // 'VEHICLE_MODE_STATE_MANUAL_REMOTE_MODE', 1: 'VEHICLE_MODE_STATE_AUTO_MODE', + // 2: 'VEHICLE_MODE_STATE_EMERGENCY_MODE', 3: + // 'VEHICLE_MODE_STATE_STANDBY_MODE'}, 'is_signed_var': False, 'len': 2, + // 'name': 'Vehicle_Mode_State', 'offset': 0.0, 'order': 'motorola', + // 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': + // 'enum'} + Vcu_report_505::Vehicle_mode_stateType vehicle_mode_state( + const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'bit': 33, 'enum': {0: 'FRONTCRASH_STATE_NO_EVENT', 1: + // 'FRONTCRASH_STATE_CRASH_EVENT'}, 'is_signed_var': False, 'len': 1, 'name': + // 'FrontCrash_State', 'offset': 0.0, 'order': 'motorola', 'physical_range': + // '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + Vcu_report_505::Frontcrash_stateType frontcrash_state( + const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'bit': 34, 'enum': {0: 'BACKCRASH_STATE_NO_EVENT', 1: + // 'BACKCRASH_STATE_CRASH_EVENT'}, 'is_signed_var': False, 'len': 1, 'name': + // 'BackCrash_State', 'offset': 0.0, 'order': 'motorola', 'physical_range': + // '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + Vcu_report_505::Backcrash_stateType backcrash_state( + const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'bit': 32, 'enum': {0: 'AEB_STATE_INACTIVE', 1: + // 'AEB_STATE_ACTIVE'}, 'is_signed_var': False, 'len': 1, 'name': 'AEB_State', + // 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|0]', + // 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} + Vcu_report_505::Aeb_stateType aeb_state(const std::uint8_t* bytes, + const int32_t length) const; + + // config detail: {'bit': 7, 'is_signed_var': True, 'len': 12, 'name': 'ACC', + // 'offset': 0.0, 'order': 'motorola', 'physical_range': '[-10|10]', + // 'physical_unit': 'm/s^2', 'precision': 0.01, 'type': 'double'} + double acc(const std::uint8_t* bytes, const int32_t length) const; + + // config detail: {'bit': 23, 'is_signed_var': False, 'len': 16, 'name': + // 'SPEED', 'offset': 0.0, 'order': 'motorola', 'physical_range': + // '[0|65.535]', 'physical_unit': 'm/s', 'precision': 0.001, 'type': 'double'} + double speed(const std::uint8_t* bytes, const int32_t length) const; +}; + +} // namespace devkit +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/vcu_report_505_test.cc b/modules/canbus/vehicle/devkit/protocol/vcu_report_505_test.cc similarity index 62% rename from modules/canbus_vehicle/devkit/protocol/vcu_report_505_test.cc rename to modules/canbus/vehicle/devkit/protocol/vcu_report_505_test.cc index 8c2e5e376e2..af9497cc1a8 100755 --- a/modules/canbus_vehicle/devkit/protocol/vcu_report_505_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/vcu_report_505_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/vcu_report_505.h" +#include "modules/canbus/vehicle/devkit/protocol/vcu_report_505.h" #include "gtest/gtest.h" @@ -27,9 +27,9 @@ class Vcureport505Test : public ::testing::Test { }; TEST_F(Vcureport505Test, General) { - uint8_t data[8] = {0x07, 0x01, 0x01, 0x02, 0x29, 0x03, 0x04, 0x05}; + uint8_t data[8] = {0x07, 0x01, 0x01, 0x02, 0x8A, 0x03, 0x04, 0x05}; int32_t length = 8; - Devkit cd; + ChassisDetail cd; Vcureport505 vcureport; vcureport.Parse(data, length, &cd); @@ -37,23 +37,17 @@ TEST_F(Vcureport505Test, General) { EXPECT_EQ(data[1], 0b00000001); EXPECT_EQ(data[2], 0b00000001); EXPECT_EQ(data[3], 0b00000010); - EXPECT_EQ(data[4], 0b00101001); + EXPECT_EQ(data[4], 0b10001010); EXPECT_EQ(data[5], 0b00000011); EXPECT_EQ(data[6], 0b00000100); EXPECT_EQ(data[7], 0b00000101); - EXPECT_EQ(cd.vcu_report_505().steer_mode_sts(), 1); - EXPECT_EQ(cd.vcu_report_505().brake_light_actual(), 0); - EXPECT_EQ(cd.vcu_report_505().acc(), 1.12); - EXPECT_EQ(cd.vcu_report_505().speed(), 0.258); - EXPECT_EQ(cd.vcu_report_505().aeb_brake_state(), 1); - EXPECT_EQ(cd.vcu_report_505().frontcrash_state(), 0); - EXPECT_EQ(cd.vcu_report_505().backcrash_state(), 0); - EXPECT_EQ(cd.vcu_report_505().vehicle_mode_state(), 1); - EXPECT_EQ(cd.vcu_report_505().drive_mode_sts(), 1); - EXPECT_EQ(cd.vcu_report_505().chassis_errcode(), 3); - EXPECT_EQ(cd.vcu_report_505().turn_light_actual(), 1); - EXPECT_EQ(cd.vcu_report_505().aeb_mode(), 1); + EXPECT_EQ(cd.devkit().vcu_report_505().vehicle_mode_state(), 1); + EXPECT_EQ(cd.devkit().vcu_report_505().frontcrash_state(), 1); + EXPECT_EQ(cd.devkit().vcu_report_505().backcrash_state(), 0); + EXPECT_EQ(cd.devkit().vcu_report_505().aeb_state(), 0); + EXPECT_EQ(cd.devkit().vcu_report_505().acc(), 1.12); + EXPECT_EQ(cd.devkit().vcu_report_505().speed(), 0.258); } } // namespace devkit diff --git a/modules/canbus_vehicle/devkit/protocol/wheelspeed_report_506.cc b/modules/canbus/vehicle/devkit/protocol/wheelspeed_report_506.cc similarity index 89% rename from modules/canbus_vehicle/devkit/protocol/wheelspeed_report_506.cc rename to modules/canbus/vehicle/devkit/protocol/wheelspeed_report_506.cc index ccc94ecdf89..4801432818d 100755 --- a/modules/canbus_vehicle/devkit/protocol/wheelspeed_report_506.cc +++ b/modules/canbus/vehicle/devkit/protocol/wheelspeed_report_506.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/wheelspeed_report_506.h" +#include "modules/canbus/vehicle/devkit/protocol/wheelspeed_report_506.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" @@ -30,14 +30,14 @@ Wheelspeedreport506::Wheelspeedreport506() {} const int32_t Wheelspeedreport506::ID = 0x506; void Wheelspeedreport506::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_wheelspeed_report_506()->set_rr( + ChassisDetail* chassis) const { + chassis->mutable_devkit()->mutable_wheelspeed_report_506()->set_rr( rr(bytes, length)); - chassis->mutable_wheelspeed_report_506()->set_rl( + chassis->mutable_devkit()->mutable_wheelspeed_report_506()->set_rl( rl(bytes, length)); - chassis->mutable_wheelspeed_report_506()->set_fr( + chassis->mutable_devkit()->mutable_wheelspeed_report_506()->set_fr( fr(bytes, length)); - chassis->mutable_wheelspeed_report_506()->set_fl( + chassis->mutable_devkit()->mutable_wheelspeed_report_506()->set_fl( fl(bytes, length)); } diff --git a/modules/canbus_vehicle/devkit/protocol/wheelspeed_report_506.h b/modules/canbus/vehicle/devkit/protocol/wheelspeed_report_506.h similarity index 92% rename from modules/canbus_vehicle/devkit/protocol/wheelspeed_report_506.h rename to modules/canbus/vehicle/devkit/protocol/wheelspeed_report_506.h index 2b454ffd252..53b04621570 100755 --- a/modules/canbus_vehicle/devkit/protocol/wheelspeed_report_506.h +++ b/modules/canbus/vehicle/devkit/protocol/wheelspeed_report_506.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace devkit { class Wheelspeedreport506 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Wheelspeedreport506(); void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'RR', 'offset': 0.0, 'precision': 0.001, 'len': 16, diff --git a/modules/canbus_vehicle/devkit/protocol/wheelspeed_report_506_test.cc b/modules/canbus/vehicle/devkit/protocol/wheelspeed_report_506_test.cc similarity index 82% rename from modules/canbus_vehicle/devkit/protocol/wheelspeed_report_506_test.cc rename to modules/canbus/vehicle/devkit/protocol/wheelspeed_report_506_test.cc index 290940e5111..bb956e72c0a 100755 --- a/modules/canbus_vehicle/devkit/protocol/wheelspeed_report_506_test.cc +++ b/modules/canbus/vehicle/devkit/protocol/wheelspeed_report_506_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/devkit/protocol/wheelspeed_report_506.h" +#include "modules/canbus/vehicle/devkit/protocol/wheelspeed_report_506.h" #include "gtest/gtest.h" @@ -29,7 +29,7 @@ class Wheelspeedreport506Test : public ::testing::Test { TEST_F(Wheelspeedreport506Test, General) { uint8_t data[8] = {0x07, 0x01, 0x01, 0x02, 0x8A, 0x03, 0x04, 0x05}; int32_t length = 8; - Devkit cd; + ChassisDetail cd; Wheelspeedreport506 wheelspeedreport; wheelspeedreport.Parse(data, length, &cd); @@ -42,10 +42,10 @@ TEST_F(Wheelspeedreport506Test, General) { EXPECT_EQ(data[6], 0b00000100); EXPECT_EQ(data[7], 0b00000101); - EXPECT_EQ(cd.wheelspeed_report_506().rr(), 1.029); - EXPECT_EQ(cd.wheelspeed_report_506().rl(), 35.331); - EXPECT_EQ(cd.wheelspeed_report_506().fr(), 0.258); - EXPECT_EQ(cd.wheelspeed_report_506().fl(), 1.793); + EXPECT_EQ(cd.devkit().wheelspeed_report_506().rr(), 1.029); + EXPECT_EQ(cd.devkit().wheelspeed_report_506().rl(), 35.331); + EXPECT_EQ(cd.devkit().wheelspeed_report_506().fr(), 0.258); + EXPECT_EQ(cd.devkit().wheelspeed_report_506().fl(), 1.793); } } // namespace devkit diff --git a/modules/canbus/vehicle/ge3/BUILD b/modules/canbus/vehicle/ge3/BUILD new file mode 100644 index 00000000000..c32128236df --- /dev/null +++ b/modules/canbus/vehicle/ge3/BUILD @@ -0,0 +1,77 @@ +load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") +load("//tools:cpplint.bzl", "cpplint") + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "ge3_vehicle_factory", + srcs = ["ge3_vehicle_factory.cc"], + hdrs = ["ge3_vehicle_factory.h"], + deps = [ + ":ge3_controller", + ":ge3_message_manager", + "//modules/canbus/proto:vehicle_parameter_cc_proto", + "//modules/canbus/vehicle:abstract_vehicle_factory", + ], +) + +cc_test( + name = "ge3_vehicle_factory_test", + size = "small", + srcs = ["ge3_vehicle_factory_test.cc"], + deps = [ + ":ge3_vehicle_factory", + "@com_google_googletest//:gtest_main", + ], +) + +cc_library( + name = "ge3_message_manager", + srcs = ["ge3_message_manager.cc"], + hdrs = ["ge3_message_manager.h"], + deps = [ + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_test( + name = "ge3_message_manager_test", + size = "small", + srcs = ["ge3_message_manager_test.cc"], + deps = [ + ":ge3_message_manager", + "@com_google_googletest//:gtest_main", + ], +) + +cc_library( + name = "ge3_controller", + srcs = ["ge3_controller.cc"], + hdrs = ["ge3_controller.h"], + deps = [ + ":ge3_message_manager", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle:vehicle_controller_base", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/drivers/canbus/can_comm:can_sender", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_test( + name = "ge3_controller_test", + size = "small", + srcs = ["ge3_controller_test.cc"], + data = ["//modules/canbus:test_data"], + deps = [ + ":ge3_controller", + "//modules/common/util", + "@com_google_googletest//:gtest_main", + ], +) + +cpplint() diff --git a/modules/canbus_vehicle/ge3/ge3_controller.cc b/modules/canbus/vehicle/ge3/ge3_controller.cc similarity index 87% rename from modules/canbus_vehicle/ge3/ge3_controller.cc rename to modules/canbus/vehicle/ge3/ge3_controller.cc index 1b18820b462..f2977e6d1d4 100644 --- a/modules/canbus_vehicle/ge3/ge3_controller.cc +++ b/modules/canbus/vehicle/ge3/ge3_controller.cc @@ -13,13 +13,11 @@ See the License for the specific language governing permissions and limitations under the License. ==============================================================================*/ -#include "modules/canbus_vehicle/ge3/ge3_controller.h" - -#include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" - +#include "modules/canbus/vehicle/ge3/ge3_controller.h" #include "cyber/time/time.h" -#include "modules/canbus_vehicle/ge3/ge3_message_manager.h" +#include "modules/canbus/vehicle/ge3/ge3_message_manager.h" #include "modules/canbus/vehicle/vehicle_controller.h" +#include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "modules/drivers/canbus/can_comm/can_sender.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" @@ -40,8 +38,8 @@ const int32_t CHECK_RESPONSE_SPEED_UNIT_FLAG = 2; } // namespace ErrorCode Ge3Controller::Init( - const VehicleParameter& params, CanSender* const can_sender, - MessageManager<::apollo::canbus::Ge3>* const message_manager) { + const VehicleParameter& params, CanSender* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) { if (is_initialized_) { AINFO << "Ge3Controller has already been initiated."; return ErrorCode::CANBUS_ERROR; @@ -145,7 +143,7 @@ void Ge3Controller::Stop() { Chassis Ge3Controller::chassis() { chassis_.Clear(); - Ge3 chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); // 21, 22, previously 1, 2 @@ -159,9 +157,15 @@ Chassis Ge3Controller::chassis() { // 3 chassis_.set_engine_started(true); + // check if there is not ge3, no chassis detail can be retrieved and return + if (!chassis_detail.has_ge3()) { + AERROR << "NO GE3 chassis information!"; + return chassis_; + } + Ge3 ge3 = chassis_detail.ge3(); // 5 - if (chassis_detail.has_scu_bcs_3_308()) { - Scu_bcs_3_308 scu_bcs_3_308 = chassis_detail.scu_bcs_3_308(); + if (ge3.has_scu_bcs_3_308()) { + Scu_bcs_3_308 scu_bcs_3_308 = ge3.scu_bcs_3_308(); if (scu_bcs_3_308.has_bcs_rrwheelspd()) { if (chassis_.has_wheel_speed()) { chassis_.mutable_wheel_speed()->set_is_wheel_spd_rr_valid( @@ -207,10 +211,9 @@ Chassis Ge3Controller::chassis() { } } - if (chassis_detail.has_scu_bcs_2_307() && - chassis_detail.scu_bcs_2_307().has_bcs_vehspd()) { + if (ge3.has_scu_bcs_2_307() && ge3.scu_bcs_2_307().has_bcs_vehspd()) { chassis_.set_speed_mps( - static_cast(chassis_detail.scu_bcs_2_307().bcs_vehspd())); + static_cast(ge3.scu_bcs_2_307().bcs_vehspd())); } else { chassis_.set_speed_mps(0); } @@ -220,25 +223,22 @@ Chassis Ge3Controller::chassis() { // to avoid confusing, just don't set chassis_.set_fuel_range_m(0); - if (chassis_detail.has_scu_vcu_1_312() && - chassis_detail.scu_vcu_1_312().has_vcu_accpedact()) { + if (ge3.has_scu_vcu_1_312() && ge3.scu_vcu_1_312().has_vcu_accpedact()) { chassis_.set_throttle_percentage( - static_cast(chassis_detail.scu_vcu_1_312().vcu_accpedact())); + static_cast(ge3.scu_vcu_1_312().vcu_accpedact())); } else { chassis_.set_throttle_percentage(0); } // 9 - if (chassis_detail.has_scu_bcs_1_306() && - chassis_detail.scu_bcs_1_306().has_bcs_brkpedact()) { + if (ge3.has_scu_bcs_1_306() && ge3.scu_bcs_1_306().has_bcs_brkpedact()) { chassis_.set_brake_percentage( - static_cast(chassis_detail.scu_bcs_1_306().bcs_brkpedact())); + static_cast(ge3.scu_bcs_1_306().bcs_brkpedact())); } else { chassis_.set_brake_percentage(0); } // 23, previously 10 - if (chassis_detail.has_scu_vcu_1_312() && - chassis_detail.scu_vcu_1_312().has_vcu_gearact()) { - switch (chassis_detail.scu_vcu_1_312().vcu_gearact()) { + if (ge3.has_scu_vcu_1_312() && ge3.scu_vcu_1_312().has_vcu_gearact()) { + switch (ge3.scu_vcu_1_312().vcu_gearact()) { case Scu_vcu_1_312::VCU_GEARACT_INVALID: { chassis_.set_gear_location(Chassis::GEAR_INVALID); } break; @@ -263,29 +263,26 @@ Chassis Ge3Controller::chassis() { } // 11 - if (chassis_detail.has_scu_eps_311() && - chassis_detail.scu_eps_311().has_eps_steerangle()) { + if (ge3.has_scu_eps_311() && ge3.scu_eps_311().has_eps_steerangle()) { chassis_.set_steering_percentage( - static_cast(chassis_detail.scu_eps_311().eps_steerangle() / + static_cast(ge3.scu_eps_311().eps_steerangle() / vehicle_params_.max_steer_angle() * M_PI / 1.80)); } else { chassis_.set_steering_percentage(0); } // 13 - if (chassis_detail.has_scu_epb_310() && - chassis_detail.scu_epb_310().has_epb_sysst()) { - chassis_.set_parking_brake(chassis_detail.scu_epb_310().epb_sysst() == + if (ge3.has_scu_epb_310() && ge3.scu_epb_310().has_epb_sysst()) { + chassis_.set_parking_brake(ge3.scu_epb_310().epb_sysst() == Scu_epb_310::EPB_SYSST_APPLIED); } else { chassis_.set_parking_brake(false); } // 14, 15: ge3 light control - if (chassis_detail.has_scu_bcm_304() && - chassis_detail.scu_bcm_304().has_bcm_highbeamst() && + if (ge3.has_scu_bcm_304() && ge3.scu_bcm_304().has_bcm_highbeamst() && Scu_bcm_304::BCM_HIGHBEAMST_ACTIVE == - chassis_detail.scu_bcm_304().bcm_highbeamst()) { + ge3.scu_bcm_304().bcm_highbeamst()) { if (chassis_.has_signal()) { chassis_.mutable_signal()->set_high_beam(true); } @@ -296,8 +293,8 @@ Chassis Ge3Controller::chassis() { } // 16, 17 - if (chassis_detail.has_scu_bcm_304()) { - Scu_bcm_304 scu_bcm_304 = chassis_detail.scu_bcm_304(); + if (ge3.has_scu_bcm_304()) { + Scu_bcm_304 scu_bcm_304 = ge3.scu_bcm_304(); if (scu_bcm_304.has_bcm_leftturnlampst() && Scu_bcm_304::BCM_LEFTTURNLAMPST_ACTIVE == scu_bcm_304.bcm_leftturnlampst()) { @@ -317,10 +314,8 @@ Chassis Ge3Controller::chassis() { common::VehicleSignal::TURN_NONE); } // 18 - if (chassis_detail.has_scu_bcm_304() && - chassis_detail.scu_bcm_304().has_bcm_hornst() && - Scu_bcm_304::BCM_HORNST_ACTIVE == - chassis_detail.scu_bcm_304().bcm_hornst()) { + if (ge3.has_scu_bcm_304() && ge3.scu_bcm_304().has_bcm_hornst() && + Scu_bcm_304::BCM_HORNST_ACTIVE == ge3.scu_bcm_304().bcm_hornst()) { chassis_.mutable_signal()->set_horn(true); } else { chassis_.mutable_signal()->set_horn(false); @@ -328,11 +323,10 @@ Chassis Ge3Controller::chassis() { // vin number will be written into KVDB once. chassis_.mutable_vehicle_id()->set_vin(""); - if (chassis_detail.has_scu_1_301() && chassis_detail.has_scu_2_302() && - chassis_detail.has_scu_3_303()) { - Scu_1_301 scu_1_301 = chassis_detail.scu_1_301(); - Scu_2_302 scu_2_302 = chassis_detail.scu_2_302(); - Scu_3_303 scu_3_303 = chassis_detail.scu_3_303(); + if (ge3.has_scu_1_301() && ge3.has_scu_2_302() && ge3.has_scu_3_303()) { + Scu_1_301 scu_1_301 = ge3.scu_1_301(); + Scu_2_302 scu_2_302 = ge3.scu_2_302(); + Scu_3_303 scu_3_303 = ge3.scu_3_303(); if (scu_2_302.has_vin00() && scu_2_302.has_vin01() && scu_2_302.has_vin02() && scu_2_302.has_vin03() && scu_2_302.has_vin04() && scu_2_302.has_vin05() && @@ -393,28 +387,9 @@ Chassis Ge3Controller::chassis() { } } - // 19 add checkresponse signal - if (chassis_detail.has_scu_bcs_1_306() && - chassis_detail.scu_bcs_1_306().has_bcs_drvmode()) { - chassis_.mutable_check_response()->set_is_esp_online( - chassis_detail.scu_bcs_1_306().bcs_drvmode() == 1); - } - if (chassis_detail.has_scu_eps_311() && - chassis_detail.scu_eps_311().has_eps_drvmode()) { - chassis_.mutable_check_response()->set_is_eps_online( - chassis_detail.scu_eps_311().eps_drvmode() == 1); - } - if (chassis_detail.has_scu_vcu_1_312() && - chassis_detail.scu_vcu_1_312().has_vcu_drvmode()) { - chassis_.mutable_check_response()->set_is_vcu_online( - chassis_detail.scu_vcu_1_312().vcu_drvmode() == 1); - } - return chassis_; } -bool Ge3Controller::VerifyID() { return true; } - void Ge3Controller::Emergency() { set_driving_mode(Chassis::EMERGENCY_MODE); ResetProtocol(); @@ -621,7 +596,7 @@ void Ge3Controller::Steer(double angle, double angle_spd) { const double real_angle = vehicle_params_.max_steer_angle() / M_PI * 180 * angle / 100.0; const double real_angle_spd = - ProtocolData<::apollo::canbus::Ge3>::BoundedValue( + ProtocolData<::apollo::canbus::ChassisDetail>::BoundedValue( vehicle_params_.min_steer_angle_rate() / M_PI * 180, vehicle_params_.max_steer_angle_rate() / M_PI * 180, vehicle_params_.max_steer_angle_rate() / M_PI * 180 * angle_spd / @@ -677,57 +652,52 @@ void Ge3Controller::SetTurningSignal(const ControlCommand& command) { void Ge3Controller::ResetProtocol() { message_manager_->ResetSendMessages(); } bool Ge3Controller::CheckChassisError() { - Ge3 chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); - if (!chassis_detail.has_check_response()) { + if (!chassis_detail.has_ge3()) { AERROR_EVERY(100) << "ChassisDetail has NO ge3 vehicle info." << chassis_detail.DebugString(); return false; } - + Ge3 ge3 = chassis_detail.ge3(); // check steer error - if (chassis_detail.has_scu_eps_311()) { - if (Scu_eps_311::EPS_FAULTST_FAULT == - chassis_detail.scu_eps_311().eps_faultst()) { + if (ge3.has_scu_eps_311()) { + if (Scu_eps_311::EPS_FAULTST_FAULT == ge3.scu_eps_311().eps_faultst()) { return true; } } // check vcu error - if (chassis_detail.has_scu_vcu_1_312() && - Scu_vcu_1_312::VCU_FAULTST_NORMAL != - chassis_detail.scu_vcu_1_312().vcu_faultst()) { + if (ge3.has_scu_vcu_1_312() && + Scu_vcu_1_312::VCU_FAULTST_NORMAL != ge3.scu_vcu_1_312().vcu_faultst()) { return true; } // check braking error - if (chassis_detail.has_scu_bcs_1_306()) { - if (Scu_bcs_1_306::BCS_FAULTST_FAULT == - chassis_detail.scu_bcs_1_306().bcs_faultst()) { + if (ge3.has_scu_bcs_1_306()) { + if (Scu_bcs_1_306::BCS_FAULTST_FAULT == ge3.scu_bcs_1_306().bcs_faultst()) { return true; } } // check gear error - if (chassis_detail.has_scu_vcu_1_312()) { + if (ge3.has_scu_vcu_1_312()) { if (Scu_vcu_1_312::VCU_GEARFAULTST_FAULT == - chassis_detail.scu_vcu_1_312().vcu_gearfaultst()) { + ge3.scu_vcu_1_312().vcu_gearfaultst()) { return true; } } // check parking error - if (chassis_detail.has_scu_epb_310()) { - if (Scu_epb_310::EPB_FAULTST_FAULT == - chassis_detail.scu_epb_310().epb_faultst()) { + if (ge3.has_scu_epb_310()) { + if (Scu_epb_310::EPB_FAULTST_FAULT == ge3.scu_epb_310().epb_faultst()) { return true; } } // check the whole vehicle error - if (chassis_detail.has_scu_1_301()) { - if (Scu_1_301::SCU_FAULTST_NORMAL != - chassis_detail.scu_1_301().scu_faultst()) { + if (ge3.has_scu_1_301()) { + if (Scu_1_301::SCU_FAULTST_NORMAL != ge3.scu_1_301().scu_faultst()) { return true; } } @@ -802,7 +772,7 @@ void Ge3Controller::SecurityDogThreadFunc() { bool Ge3Controller::CheckResponse(const int32_t flags, bool need_wait) { int32_t retry_num = 20; - Ge3 chassis_detail; + ChassisDetail chassis_detail; bool is_eps_online = false; bool is_vcu_online = false; bool is_esp_online = false; @@ -868,7 +838,7 @@ void Ge3Controller::set_chassis_error_code( } bool Ge3Controller::CheckSafetyError( - const ::apollo::canbus::Ge3& chassis_detail) { + const ::apollo::canbus::ChassisDetail& chassis_detail) { return false; } diff --git a/modules/canbus_vehicle/ge3/ge3_controller.h b/modules/canbus/vehicle/ge3/ge3_controller.h similarity index 87% rename from modules/canbus_vehicle/ge3/ge3_controller.h rename to modules/canbus/vehicle/ge3/ge3_controller.h index 0a8ac1b0426..951f86e6873 100644 --- a/modules/canbus_vehicle/ge3/ge3_controller.h +++ b/modules/canbus/vehicle/ge3/ge3_controller.h @@ -21,11 +21,11 @@ #include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/common_msgs/chassis_msgs/chassis.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_bcm_201.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_bcs_202.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_epb_203.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_eps_204.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_vcu_205.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_bcm_201.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_bcs_202.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_epb_203.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_eps_204.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_vcu_205.h" #include "modules/canbus/vehicle/vehicle_controller.h" #include "modules/common_msgs/basic_msgs/error_code.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" @@ -34,7 +34,7 @@ namespace apollo { namespace canbus { namespace ge3 { -class Ge3Controller final : public VehicleController<::apollo::canbus::Ge3> { +class Ge3Controller final : public VehicleController { public: Ge3Controller() {} @@ -42,8 +42,8 @@ class Ge3Controller final : public VehicleController<::apollo::canbus::Ge3> { ::apollo::common::ErrorCode Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Ge3>* const can_sender, - MessageManager<::apollo::canbus::Ge3>* const message_manager) + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) override; bool Start() override; @@ -102,10 +102,9 @@ class Ge3Controller final : public VehicleController<::apollo::canbus::Ge3> { void SetTurningSignal( const ::apollo::control::ControlCommand& command) override; - bool VerifyID() override; void ResetProtocol(); bool CheckChassisError(); - bool CheckSafetyError(const canbus::Ge3& chassis); + bool CheckSafetyError(const canbus::ChassisDetail& chassis); private: void SecurityDogThreadFunc(); diff --git a/modules/canbus_vehicle/ge3/ge3_controller_test.cc b/modules/canbus/vehicle/ge3/ge3_controller_test.cc similarity index 93% rename from modules/canbus_vehicle/ge3/ge3_controller_test.cc rename to modules/canbus/vehicle/ge3/ge3_controller_test.cc index 64e30ca2b85..d5780bbccdf 100644 --- a/modules/canbus_vehicle/ge3/ge3_controller_test.cc +++ b/modules/canbus/vehicle/ge3/ge3_controller_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/ge3_controller.h" +#include "modules/canbus/vehicle/ge3/ge3_controller.h" #include @@ -22,8 +22,7 @@ #include "gtest/gtest.h" #include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" -#include "modules/canbus_vehicle/ge3/ge3_message_manager.h" +#include "modules/canbus/vehicle/ge3/ge3_message_manager.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" #include "modules/drivers/canbus/can_comm/can_sender.h" @@ -45,7 +44,7 @@ class Ge3ControllerTest : public ::testing::Test { protected: Ge3Controller controller_; - CanSender<::apollo::canbus::Ge3> sender_; + CanSender<::apollo::canbus::ChassisDetail> sender_; CanbusConf canbus_conf_; VehicleParameter params_; Ge3MessageManager msg_manager_; diff --git a/modules/canbus_vehicle/ge3/ge3_message_manager.cc b/modules/canbus/vehicle/ge3/ge3_message_manager.cc similarity index 60% rename from modules/canbus_vehicle/ge3/ge3_message_manager.cc rename to modules/canbus/vehicle/ge3/ge3_message_manager.cc index e691dff4566..f697114b9ed 100644 --- a/modules/canbus_vehicle/ge3/ge3_message_manager.cc +++ b/modules/canbus/vehicle/ge3/ge3_message_manager.cc @@ -13,23 +13,23 @@ See the License for the specific language governing permissions and limitations under the License. ==============================================================================*/ -#include "modules/canbus_vehicle/ge3/ge3_message_manager.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_bcm_201.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_bcs_202.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_epb_203.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_eps_204.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_vcu_205.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_1_301.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_2_302.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_3_303.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_bcm_304.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_bcs_1_306.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_bcs_2_307.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_bcs_3_308.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_epb_310.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_eps_311.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_vcu_1_312.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_vcu_2_313.h" +#include "modules/canbus/vehicle/ge3/ge3_message_manager.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_bcm_201.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_bcs_202.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_epb_203.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_eps_204.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_vcu_205.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_1_301.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_2_302.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_3_303.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcm_304.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcs_1_306.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcs_2_307.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcs_3_308.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_epb_310.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_eps_311.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_vcu_1_312.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_vcu_2_313.h" namespace apollo { namespace canbus { diff --git a/modules/canbus_vehicle/ge3/ge3_message_manager.h b/modules/canbus/vehicle/ge3/ge3_message_manager.h similarity index 88% rename from modules/canbus_vehicle/ge3/ge3_message_manager.h rename to modules/canbus/vehicle/ge3/ge3_message_manager.h index 2a438b84827..0480226f9a1 100644 --- a/modules/canbus_vehicle/ge3/ge3_message_manager.h +++ b/modules/canbus/vehicle/ge3/ge3_message_manager.h @@ -15,7 +15,7 @@ limitations under the License. #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/message_manager.h" namespace apollo { @@ -25,7 +25,7 @@ namespace ge3 { using ::apollo::drivers::canbus::MessageManager; class Ge3MessageManager - : public MessageManager<::apollo::canbus::Ge3> { + : public MessageManager<::apollo::canbus::ChassisDetail> { public: Ge3MessageManager(); virtual ~Ge3MessageManager(); diff --git a/modules/canbus_vehicle/ge3/ge3_message_manager_test.cc b/modules/canbus/vehicle/ge3/ge3_message_manager_test.cc similarity index 69% rename from modules/canbus_vehicle/ge3/ge3_message_manager_test.cc rename to modules/canbus/vehicle/ge3/ge3_message_manager_test.cc index 92b4b76c223..c7950019395 100644 --- a/modules/canbus_vehicle/ge3/ge3_message_manager_test.cc +++ b/modules/canbus/vehicle/ge3/ge3_message_manager_test.cc @@ -14,24 +14,24 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/ge3_message_manager.h" +#include "modules/canbus/vehicle/ge3/ge3_message_manager.h" #include "gtest/gtest.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_bcm_201.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_bcs_202.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_epb_203.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_eps_204.h" -#include "modules/canbus_vehicle/ge3/protocol/pc_vcu_205.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_1_301.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_2_302.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_3_303.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_bcm_304.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_bcs_1_306.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_bcs_2_307.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_bcs_3_308.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_epb_310.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_eps_311.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_vcu_1_312.h" -#include "modules/canbus_vehicle/ge3/protocol/scu_vcu_2_313.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_bcm_201.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_bcs_202.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_epb_203.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_eps_204.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_vcu_205.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_1_301.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_2_302.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_3_303.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcm_304.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcs_1_306.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcs_2_307.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcs_3_308.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_epb_310.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_eps_311.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_vcu_1_312.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_vcu_2_313.h" namespace apollo { namespace canbus { diff --git a/modules/tools/gen_vehicle_protocol/template/report_protocol.cc.tpl b/modules/canbus/vehicle/ge3/ge3_vehicle_factory.cc similarity index 59% rename from modules/tools/gen_vehicle_protocol/template/report_protocol.cc.tpl rename to modules/canbus/vehicle/ge3/ge3_vehicle_factory.cc index b916725105e..e8c8480b6d5 100644 --- a/modules/tools/gen_vehicle_protocol/template/report_protocol.cc.tpl +++ b/modules/canbus/vehicle/ge3/ge3_vehicle_factory.cc @@ -14,27 +14,24 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus/vehicle/%(car_type_lower)s/protocol/%(protocol_name_lower)s.h" - -#include "glog/logging.h" - -#include "modules/drivers/canbus/common/byte.h" -#include "modules/drivers/canbus/common/canbus_consts.h" +#include "modules/canbus/vehicle/ge3/ge3_vehicle_factory.h" +#include "modules/canbus/vehicle/ge3/ge3_controller.h" +#include "modules/canbus/vehicle/ge3/ge3_message_manager.h" +#include "modules/common/util/util.h" namespace apollo { namespace canbus { -namespace %(car_type_lower)s { - -using ::apollo::drivers::canbus::Byte; -%(classname)s::%(classname)s() {} -const int32_t %(classname)s::ID = 0x%(id_upper)s; +std::unique_ptr +Ge3VehicleFactory::CreateVehicleController() { + return std::unique_ptr(new ge3::Ge3Controller()); +} -void %(classname)s::Parse(const std::uint8_t* bytes, int32_t length, - ChassisDetail* chassis) const { -%(set_var_to_protocol_list)s +std::unique_ptr> +Ge3VehicleFactory::CreateMessageManager() { + return std::unique_ptr>( + new ge3::Ge3MessageManager()); } -%(func_impl_list)s -} // namespace %(car_type_lower)s + } // namespace canbus } // namespace apollo diff --git a/modules/canbus/vehicle/ge3/ge3_vehicle_factory.h b/modules/canbus/vehicle/ge3/ge3_vehicle_factory.h new file mode 100644 index 00000000000..8beb13734dc --- /dev/null +++ b/modules/canbus/vehicle/ge3/ge3_vehicle_factory.h @@ -0,0 +1,64 @@ +/****************************************************************************** + * 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. + *****************************************************************************/ + +/** + * @file ge3_vehicle_factory.h + */ + +#pragma once + +#include +#include "modules/canbus/proto/vehicle_parameter.pb.h" +#include "modules/canbus/vehicle/abstract_vehicle_factory.h" +#include "modules/canbus/vehicle/vehicle_controller.h" +#include "modules/drivers/canbus/can_comm/message_manager.h" + +/** + * @namespace apollo::canbus + * @brief apollo::canbus + */ +namespace apollo { +namespace canbus { + +/** + * @class Ge3VehicleFactory + * + * @brief this class is inherited from AbstractVehicleFactory. It can be used to + * create controller and message manager for ge3 vehicle. + */ +class Ge3VehicleFactory : public AbstractVehicleFactory { + public: + /** + * @brief destructor + */ + virtual ~Ge3VehicleFactory() = default; + + /** + * @brief create ge3 vehicle controller + * @returns a unique_ptr that points to the created controller + */ + std::unique_ptr CreateVehicleController() override; + + /** + * @brief create ge3 message manager + * @returns a unique_ptr that points to the created message manager + */ + std::unique_ptr> + CreateMessageManager() override; +}; + +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/ge3/ge3_vehicle_factory_test.cc b/modules/canbus/vehicle/ge3/ge3_vehicle_factory_test.cc similarity index 63% rename from modules/canbus_vehicle/ge3/ge3_vehicle_factory_test.cc rename to modules/canbus/vehicle/ge3/ge3_vehicle_factory_test.cc index 3424cbb2b51..441c7173f3d 100644 --- a/modules/canbus_vehicle/ge3/ge3_vehicle_factory_test.cc +++ b/modules/canbus/vehicle/ge3/ge3_vehicle_factory_test.cc @@ -14,39 +14,32 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/ge3_vehicle_factory.h" - +#include "modules/canbus/vehicle/ge3/ge3_vehicle_factory.h" #include "gtest/gtest.h" - -#include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "cyber/common/file.h" - namespace apollo { namespace canbus { class Ge3VehicleFactoryTest : public ::testing::Test { public: virtual void SetUp() { - std::string canbus_conf_file = - "modules/canbus/testdata/conf/ge3_canbus_conf_test.pb.txt"; - cyber::common::GetProtoFromFile(canbus_conf_file, &canbus_conf_); - params_ = canbus_conf_.vehicle_parameter(); - params_.set_brand(apollo::common::GE3); - ge3_factory_.SetVehicleParameter(params_); + VehicleParameter parameter; + parameter.set_brand(apollo::common::GE3); + ge3_factory_.SetVehicleParameter(parameter); } virtual void TearDown() {} protected: Ge3VehicleFactory ge3_factory_; - CanbusConf canbus_conf_; - VehicleParameter params_; }; -TEST_F(Ge3VehicleFactoryTest, Init) { - apollo::cyber::Init("vehicle_factory_test"); - EXPECT_EQ(ge3_factory_.Init(&canbus_conf_), true); +TEST_F(Ge3VehicleFactoryTest, InitVehicleController) { + EXPECT_NE(ge3_factory_.CreateVehicleController(), nullptr); +} + +TEST_F(Ge3VehicleFactoryTest, InitMessageManager) { + EXPECT_NE(ge3_factory_.CreateMessageManager(), nullptr); } } // namespace canbus diff --git a/modules/canbus_vehicle/ge3/protocol/BUILD b/modules/canbus/vehicle/ge3/protocol/BUILD similarity index 73% rename from modules/canbus_vehicle/ge3/protocol/BUILD rename to modules/canbus/vehicle/ge3/protocol/BUILD index d35f4956293..73140821f2f 100644 --- a/modules/canbus_vehicle/ge3/protocol/BUILD +++ b/modules/canbus/vehicle/ge3/protocol/BUILD @@ -42,7 +42,7 @@ cc_library( "scu_vcu_2_313.h", ], deps = [ - "//modules/canbus_vehicle/ge3/proto:ge3_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -53,10 +53,9 @@ cc_test( size = "small", srcs = ["pc_bcm_201_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -64,10 +63,9 @@ cc_test( size = "small", srcs = ["pc_bcs_202_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -75,10 +73,9 @@ cc_test( size = "small", srcs = ["pc_epb_203_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -86,10 +83,9 @@ cc_test( size = "small", srcs = ["pc_eps_204_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -97,10 +93,9 @@ cc_test( size = "small", srcs = ["pc_vcu_205_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -108,10 +103,9 @@ cc_test( size = "small", srcs = ["scu_1_301_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -119,10 +113,9 @@ cc_test( size = "small", srcs = ["scu_2_302_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -130,10 +123,9 @@ cc_test( size = "small", srcs = ["scu_3_303_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -141,10 +133,9 @@ cc_test( size = "small", srcs = ["scu_bcm_304_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -152,10 +143,9 @@ cc_test( size = "small", srcs = ["scu_bcs_1_306_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -163,10 +153,9 @@ cc_test( size = "small", srcs = ["scu_bcs_2_307_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -174,10 +163,9 @@ cc_test( size = "small", srcs = ["scu_bcs_3_308_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -185,10 +173,9 @@ cc_test( size = "small", srcs = ["scu_epb_310_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -196,10 +183,9 @@ cc_test( size = "small", srcs = ["scu_eps_311_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -207,10 +193,9 @@ cc_test( size = "small", srcs = ["scu_vcu_1_312_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -218,10 +203,9 @@ cc_test( size = "small", srcs = ["scu_vcu_2_313_test.cc"], deps = [ - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", + "//modules/canbus/vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cpplint() diff --git a/modules/canbus_vehicle/ge3/protocol/pc_bcm_201.cc b/modules/canbus/vehicle/ge3/protocol/pc_bcm_201.cc similarity index 99% rename from modules/canbus_vehicle/ge3/protocol/pc_bcm_201.cc rename to modules/canbus/vehicle/ge3/protocol/pc_bcm_201.cc index e8654c7feb1..e1ccdd17e92 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_bcm_201.cc +++ b/modules/canbus/vehicle/ge3/protocol/pc_bcm_201.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/pc_bcm_201.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_bcm_201.h" #include "modules/drivers/canbus/common/byte.h" namespace apollo { diff --git a/modules/canbus_vehicle/ge3/protocol/pc_bcm_201.h b/modules/canbus/vehicle/ge3/protocol/pc_bcm_201.h similarity index 98% rename from modules/canbus_vehicle/ge3/protocol/pc_bcm_201.h rename to modules/canbus/vehicle/ge3/protocol/pc_bcm_201.h index 58387684ee9..c05f1b39e56 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_bcm_201.h +++ b/modules/canbus/vehicle/ge3/protocol/pc_bcm_201.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace ge3 { class Pcbcm201 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/ge3/protocol/pc_bcm_201_test.cc b/modules/canbus/vehicle/ge3/protocol/pc_bcm_201_test.cc similarity index 96% rename from modules/canbus_vehicle/ge3/protocol/pc_bcm_201_test.cc rename to modules/canbus/vehicle/ge3/protocol/pc_bcm_201_test.cc index a9ae2fe0e9c..aab8afbaf61 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_bcm_201_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/pc_bcm_201_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/pc_bcm_201.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_bcm_201.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/ge3/protocol/pc_bcs_202.cc b/modules/canbus/vehicle/ge3/protocol/pc_bcs_202.cc similarity index 98% rename from modules/canbus_vehicle/ge3/protocol/pc_bcs_202.cc rename to modules/canbus/vehicle/ge3/protocol/pc_bcs_202.cc index a7b4af7ed49..582c7fb77a8 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_bcs_202.cc +++ b/modules/canbus/vehicle/ge3/protocol/pc_bcs_202.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/pc_bcs_202.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_bcs_202.h" #include "modules/drivers/canbus/common/byte.h" namespace apollo { diff --git a/modules/canbus_vehicle/ge3/protocol/pc_bcs_202.h b/modules/canbus/vehicle/ge3/protocol/pc_bcs_202.h similarity index 95% rename from modules/canbus_vehicle/ge3/protocol/pc_bcs_202.h rename to modules/canbus/vehicle/ge3/protocol/pc_bcs_202.h index 3faae8c69c3..3ac0ec059a3 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_bcs_202.h +++ b/modules/canbus/vehicle/ge3/protocol/pc_bcs_202.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace ge3 { class Pcbcs202 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/ge3/protocol/pc_bcs_202_test.cc b/modules/canbus/vehicle/ge3/protocol/pc_bcs_202_test.cc similarity index 96% rename from modules/canbus_vehicle/ge3/protocol/pc_bcs_202_test.cc rename to modules/canbus/vehicle/ge3/protocol/pc_bcs_202_test.cc index dbcd0b9c78a..3e420f77c74 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_bcs_202_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/pc_bcs_202_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/pc_bcs_202.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_bcs_202.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/ge3/protocol/pc_epb_203.cc b/modules/canbus/vehicle/ge3/protocol/pc_epb_203.cc similarity index 97% rename from modules/canbus_vehicle/ge3/protocol/pc_epb_203.cc rename to modules/canbus/vehicle/ge3/protocol/pc_epb_203.cc index 7801d33630c..850693d01ea 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_epb_203.cc +++ b/modules/canbus/vehicle/ge3/protocol/pc_epb_203.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/pc_epb_203.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_epb_203.h" #include "modules/drivers/canbus/common/byte.h" namespace apollo { diff --git a/modules/canbus_vehicle/ge3/protocol/pc_epb_203.h b/modules/canbus/vehicle/ge3/protocol/pc_epb_203.h similarity index 96% rename from modules/canbus_vehicle/ge3/protocol/pc_epb_203.h rename to modules/canbus/vehicle/ge3/protocol/pc_epb_203.h index 226e63928f7..1223a36197b 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_epb_203.h +++ b/modules/canbus/vehicle/ge3/protocol/pc_epb_203.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace ge3 { class Pcepb203 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/ge3/protocol/pc_epb_203_test.cc b/modules/canbus/vehicle/ge3/protocol/pc_epb_203_test.cc similarity index 96% rename from modules/canbus_vehicle/ge3/protocol/pc_epb_203_test.cc rename to modules/canbus/vehicle/ge3/protocol/pc_epb_203_test.cc index 27402e672fb..7746b26ca88 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_epb_203_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/pc_epb_203_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/pc_epb_203.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_epb_203.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/ge3/protocol/pc_eps_204.cc b/modules/canbus/vehicle/ge3/protocol/pc_eps_204.cc similarity index 98% rename from modules/canbus_vehicle/ge3/protocol/pc_eps_204.cc rename to modules/canbus/vehicle/ge3/protocol/pc_eps_204.cc index 08b64ca83cf..95b00bcd5c4 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_eps_204.cc +++ b/modules/canbus/vehicle/ge3/protocol/pc_eps_204.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/pc_eps_204.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_eps_204.h" #include "modules/drivers/canbus/common/byte.h" namespace apollo { diff --git a/modules/canbus_vehicle/ge3/protocol/pc_eps_204.h b/modules/canbus/vehicle/ge3/protocol/pc_eps_204.h similarity index 96% rename from modules/canbus_vehicle/ge3/protocol/pc_eps_204.h rename to modules/canbus/vehicle/ge3/protocol/pc_eps_204.h index 61c3ca7aa1b..60b9e50607c 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_eps_204.h +++ b/modules/canbus/vehicle/ge3/protocol/pc_eps_204.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace ge3 { class Pceps204 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/ge3/protocol/pc_eps_204_test.cc b/modules/canbus/vehicle/ge3/protocol/pc_eps_204_test.cc similarity index 96% rename from modules/canbus_vehicle/ge3/protocol/pc_eps_204_test.cc rename to modules/canbus/vehicle/ge3/protocol/pc_eps_204_test.cc index 3d8dc29a78c..315a5fa61af 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_eps_204_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/pc_eps_204_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/pc_eps_204.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_eps_204.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/ge3/protocol/pc_vcu_205.cc b/modules/canbus/vehicle/ge3/protocol/pc_vcu_205.cc similarity index 99% rename from modules/canbus_vehicle/ge3/protocol/pc_vcu_205.cc rename to modules/canbus/vehicle/ge3/protocol/pc_vcu_205.cc index 7e399ed4e77..3d2e7b87ca8 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_vcu_205.cc +++ b/modules/canbus/vehicle/ge3/protocol/pc_vcu_205.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/pc_vcu_205.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_vcu_205.h" #include "modules/drivers/canbus/common/byte.h" namespace apollo { diff --git a/modules/canbus_vehicle/ge3/protocol/pc_vcu_205.h b/modules/canbus/vehicle/ge3/protocol/pc_vcu_205.h similarity index 98% rename from modules/canbus_vehicle/ge3/protocol/pc_vcu_205.h rename to modules/canbus/vehicle/ge3/protocol/pc_vcu_205.h index 27f5a748fd6..a1575b2d3e4 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_vcu_205.h +++ b/modules/canbus/vehicle/ge3/protocol/pc_vcu_205.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace ge3 { class Pcvcu205 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/ge3/protocol/pc_vcu_205_test.cc b/modules/canbus/vehicle/ge3/protocol/pc_vcu_205_test.cc similarity index 96% rename from modules/canbus_vehicle/ge3/protocol/pc_vcu_205_test.cc rename to modules/canbus/vehicle/ge3/protocol/pc_vcu_205_test.cc index ff9da9e8e93..0ca050bf225 100644 --- a/modules/canbus_vehicle/ge3/protocol/pc_vcu_205_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/pc_vcu_205_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/pc_vcu_205.h" +#include "modules/canbus/vehicle/ge3/protocol/pc_vcu_205.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/ge3/protocol/scu_1_301.cc b/modules/canbus/vehicle/ge3/protocol/scu_1_301.cc similarity index 90% rename from modules/canbus_vehicle/ge3/protocol/scu_1_301.cc rename to modules/canbus/vehicle/ge3/protocol/scu_1_301.cc index 79468a43b47..e9556877f50 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_1_301.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_1_301.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_1_301.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_1_301.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,13 +29,13 @@ Scu1301::Scu1301() {} const int32_t Scu1301::ID = 0x301; void Scu1301::Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const { - chassis->mutable_scu_1_301()->set_vin16(vin16(bytes, length)); - chassis->mutable_scu_1_301()->set_scu_stopbutst( + ChassisDetail* chassis) const { + chassis->mutable_ge3()->mutable_scu_1_301()->set_vin16(vin16(bytes, length)); + chassis->mutable_ge3()->mutable_scu_1_301()->set_scu_stopbutst( scu_stopbutst(bytes, length)); - chassis->mutable_scu_1_301()->set_scu_drvmode( + chassis->mutable_ge3()->mutable_scu_1_301()->set_scu_drvmode( scu_drvmode(bytes, length)); - chassis->mutable_scu_1_301()->set_scu_faultst( + chassis->mutable_ge3()->mutable_scu_1_301()->set_scu_faultst( scu_faultst(bytes, length)); } diff --git a/modules/canbus_vehicle/ge3/protocol/scu_1_301.h b/modules/canbus/vehicle/ge3/protocol/scu_1_301.h similarity index 94% rename from modules/canbus_vehicle/ge3/protocol/scu_1_301.h rename to modules/canbus/vehicle/ge3/protocol/scu_1_301.h index 7f493cacc15..efb7ff653b6 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_1_301.h +++ b/modules/canbus/vehicle/ge3/protocol/scu_1_301.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace ge3 { class Scu1301 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Scu1301(); void Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'VIN string character 16', 'offset': 0.0, diff --git a/modules/canbus_vehicle/ge3/protocol/scu_1_301_test.cc b/modules/canbus/vehicle/ge3/protocol/scu_1_301_test.cc similarity index 76% rename from modules/canbus_vehicle/ge3/protocol/scu_1_301_test.cc rename to modules/canbus/vehicle/ge3/protocol/scu_1_301_test.cc index f62ee40fa98..5657e3b6772 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_1_301_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_1_301_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_1_301.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_1_301.h" #include "gtest/gtest.h" namespace apollo { @@ -29,14 +29,14 @@ class Scu1301Test : public ::testing::Test { TEST_F(Scu1301Test, reset) { Scu1301 scu1301; int32_t length = 8; - Ge3 chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; scu1301.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.scu_1_301().vin16(), 2); - EXPECT_DOUBLE_EQ(chassis_detail.scu_1_301().scu_stopbutst(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.scu_1_301().scu_drvmode(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_1_301().scu_faultst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_1_301().vin16(), 2); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_1_301().scu_stopbutst(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_1_301().scu_drvmode(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_1_301().scu_faultst(), 0); } } // namespace ge3 diff --git a/modules/canbus_vehicle/ge3/protocol/scu_2_302.cc b/modules/canbus/vehicle/ge3/protocol/scu_2_302.cc similarity index 85% rename from modules/canbus_vehicle/ge3/protocol/scu_2_302.cc rename to modules/canbus/vehicle/ge3/protocol/scu_2_302.cc index d884339a49a..39150c94124 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_2_302.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_2_302.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_2_302.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_2_302.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,15 +29,15 @@ Scu2302::Scu2302() {} const int32_t Scu2302::ID = 0x302; void Scu2302::Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const { - chassis->mutable_scu_2_302()->set_vin07(vin07(bytes, length)); - chassis->mutable_scu_2_302()->set_vin06(vin06(bytes, length)); - chassis->mutable_scu_2_302()->set_vin05(vin05(bytes, length)); - chassis->mutable_scu_2_302()->set_vin04(vin04(bytes, length)); - chassis->mutable_scu_2_302()->set_vin03(vin03(bytes, length)); - chassis->mutable_scu_2_302()->set_vin02(vin02(bytes, length)); - chassis->mutable_scu_2_302()->set_vin01(vin01(bytes, length)); - chassis->mutable_scu_2_302()->set_vin00(vin00(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_ge3()->mutable_scu_2_302()->set_vin07(vin07(bytes, length)); + chassis->mutable_ge3()->mutable_scu_2_302()->set_vin06(vin06(bytes, length)); + chassis->mutable_ge3()->mutable_scu_2_302()->set_vin05(vin05(bytes, length)); + chassis->mutable_ge3()->mutable_scu_2_302()->set_vin04(vin04(bytes, length)); + chassis->mutable_ge3()->mutable_scu_2_302()->set_vin03(vin03(bytes, length)); + chassis->mutable_ge3()->mutable_scu_2_302()->set_vin02(vin02(bytes, length)); + chassis->mutable_ge3()->mutable_scu_2_302()->set_vin01(vin01(bytes, length)); + chassis->mutable_ge3()->mutable_scu_2_302()->set_vin00(vin00(bytes, length)); } // config detail: {'description': 'VIN string character 07', 'offset': 0.0, diff --git a/modules/canbus_vehicle/ge3/protocol/scu_2_302.h b/modules/canbus/vehicle/ge3/protocol/scu_2_302.h similarity index 95% rename from modules/canbus_vehicle/ge3/protocol/scu_2_302.h rename to modules/canbus/vehicle/ge3/protocol/scu_2_302.h index f8f434a5dda..36b431a5dbc 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_2_302.h +++ b/modules/canbus/vehicle/ge3/protocol/scu_2_302.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace ge3 { class Scu2302 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Scu2302(); void Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'VIN string character 07', 'offset': 0.0, diff --git a/modules/canbus_vehicle/ge3/protocol/scu_2_302_test.cc b/modules/canbus/vehicle/ge3/protocol/scu_2_302_test.cc similarity index 65% rename from modules/canbus_vehicle/ge3/protocol/scu_2_302_test.cc rename to modules/canbus/vehicle/ge3/protocol/scu_2_302_test.cc index e4bdd0272ca..b1ad84b9b6a 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_2_302_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_2_302_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_2_302.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_2_302.h" #include "gtest/gtest.h" namespace apollo { @@ -29,18 +29,18 @@ class Scu2302Test : public ::testing::Test { TEST_F(Scu2302Test, reset) { Scu2302 scu2302; int32_t length = 8; - Ge3 chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x4D, 0x47, 0xFF, 0xEE, 0xDD, 0xCC, 0xBB, 0xAA}; scu2302.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.scu_2_302().vin00(), 'M'); // 77 - EXPECT_DOUBLE_EQ(chassis_detail.scu_2_302().vin01(), 71); - EXPECT_DOUBLE_EQ(chassis_detail.scu_2_302().vin02(), 255); - EXPECT_DOUBLE_EQ(chassis_detail.scu_2_302().vin03(), 238); - EXPECT_DOUBLE_EQ(chassis_detail.scu_2_302().vin04(), 221); - EXPECT_DOUBLE_EQ(chassis_detail.scu_2_302().vin05(), 204); - EXPECT_DOUBLE_EQ(chassis_detail.scu_2_302().vin06(), 187); - EXPECT_DOUBLE_EQ(chassis_detail.scu_2_302().vin07(), 170); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_2_302().vin00(), 'M'); // 77 + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_2_302().vin01(), 71); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_2_302().vin02(), 255); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_2_302().vin03(), 238); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_2_302().vin04(), 221); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_2_302().vin05(), 204); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_2_302().vin06(), 187); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_2_302().vin07(), 170); } } // namespace ge3 diff --git a/modules/canbus_vehicle/ge3/protocol/scu_3_303.cc b/modules/canbus/vehicle/ge3/protocol/scu_3_303.cc similarity index 85% rename from modules/canbus_vehicle/ge3/protocol/scu_3_303.cc rename to modules/canbus/vehicle/ge3/protocol/scu_3_303.cc index 95a5025e140..048b48216eb 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_3_303.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_3_303.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_3_303.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_3_303.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,15 +29,15 @@ Scu3303::Scu3303() {} const int32_t Scu3303::ID = 0x303; void Scu3303::Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const { - chassis->mutable_scu_3_303()->set_vin15(vin15(bytes, length)); - chassis->mutable_scu_3_303()->set_vin14(vin14(bytes, length)); - chassis->mutable_scu_3_303()->set_vin13(vin13(bytes, length)); - chassis->mutable_scu_3_303()->set_vin12(vin12(bytes, length)); - chassis->mutable_scu_3_303()->set_vin11(vin11(bytes, length)); - chassis->mutable_scu_3_303()->set_vin10(vin10(bytes, length)); - chassis->mutable_scu_3_303()->set_vin09(vin09(bytes, length)); - chassis->mutable_scu_3_303()->set_vin08(vin08(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_ge3()->mutable_scu_3_303()->set_vin15(vin15(bytes, length)); + chassis->mutable_ge3()->mutable_scu_3_303()->set_vin14(vin14(bytes, length)); + chassis->mutable_ge3()->mutable_scu_3_303()->set_vin13(vin13(bytes, length)); + chassis->mutable_ge3()->mutable_scu_3_303()->set_vin12(vin12(bytes, length)); + chassis->mutable_ge3()->mutable_scu_3_303()->set_vin11(vin11(bytes, length)); + chassis->mutable_ge3()->mutable_scu_3_303()->set_vin10(vin10(bytes, length)); + chassis->mutable_ge3()->mutable_scu_3_303()->set_vin09(vin09(bytes, length)); + chassis->mutable_ge3()->mutable_scu_3_303()->set_vin08(vin08(bytes, length)); } // config detail: {'description': 'VIN string character 15', 'offset': 0.0, diff --git a/modules/canbus_vehicle/ge3/protocol/scu_3_303.h b/modules/canbus/vehicle/ge3/protocol/scu_3_303.h similarity index 95% rename from modules/canbus_vehicle/ge3/protocol/scu_3_303.h rename to modules/canbus/vehicle/ge3/protocol/scu_3_303.h index 6980090f6f6..89fba45e8b7 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_3_303.h +++ b/modules/canbus/vehicle/ge3/protocol/scu_3_303.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace ge3 { class Scu3303 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Scu3303(); void Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'VIN string character 15', 'offset': 0.0, diff --git a/modules/canbus_vehicle/ge3/protocol/scu_3_303_test.cc b/modules/canbus/vehicle/ge3/protocol/scu_3_303_test.cc similarity index 63% rename from modules/canbus_vehicle/ge3/protocol/scu_3_303_test.cc rename to modules/canbus/vehicle/ge3/protocol/scu_3_303_test.cc index eeee2aef525..fc9149c8429 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_3_303_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_3_303_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_3_303.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_3_303.h" #include "gtest/gtest.h" namespace apollo { @@ -29,18 +29,18 @@ class Scu3303Test : public ::testing::Test { TEST_F(Scu3303Test, reset) { Scu3303 scu3303; int32_t length = 8; - Ge3 chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x41, 0x42, 0x43, 0x61, 0x62, 0x30, 0x31, 0x32}; scu3303.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.scu_3_303().vin08(), 'A'); // 65 - EXPECT_DOUBLE_EQ(chassis_detail.scu_3_303().vin09(), 'B'); // 66 - EXPECT_DOUBLE_EQ(chassis_detail.scu_3_303().vin10(), 67); // 'C' - EXPECT_DOUBLE_EQ(chassis_detail.scu_3_303().vin11(), 97); // 'a' - EXPECT_DOUBLE_EQ(chassis_detail.scu_3_303().vin12(), 'b'); // 98 - EXPECT_DOUBLE_EQ(chassis_detail.scu_3_303().vin13(), 48); // '0' - EXPECT_DOUBLE_EQ(chassis_detail.scu_3_303().vin14(), '1'); // 49 - EXPECT_DOUBLE_EQ(chassis_detail.scu_3_303().vin15(), '2'); // 50 + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_3_303().vin08(), 'A'); // 65 + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_3_303().vin09(), 'B'); // 66 + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_3_303().vin10(), 67); // 'C' + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_3_303().vin11(), 97); // 'a' + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_3_303().vin12(), 'b'); // 98 + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_3_303().vin13(), 48); // '0' + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_3_303().vin14(), '1'); // 49 + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_3_303().vin15(), '2'); // 50 } } // namespace ge3 diff --git a/modules/canbus_vehicle/ge3/protocol/scu_bcm_304.cc b/modules/canbus/vehicle/ge3/protocol/scu_bcm_304.cc similarity index 90% rename from modules/canbus_vehicle/ge3/protocol/scu_bcm_304.cc rename to modules/canbus/vehicle/ge3/protocol/scu_bcm_304.cc index 4d4511ec0ad..6e753404a7e 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_bcm_304.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_bcm_304.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_bcm_304.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcm_304.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,30 +29,30 @@ Scubcm304::Scubcm304() {} const int32_t Scubcm304::ID = 0x304; void Scubcm304::Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const { - chassis->mutable_scu_bcm_304()->set_bcm_vehreversest( + ChassisDetail* chassis) const { + chassis->mutable_ge3()->mutable_scu_bcm_304()->set_bcm_vehreversest( bcm_vehreversest(bytes, length)); - chassis->mutable_scu_bcm_304()->set_bcm_rightturnlampst( + chassis->mutable_ge3()->mutable_scu_bcm_304()->set_bcm_rightturnlampst( bcm_rightturnlampst(bytes, length)); - chassis->mutable_scu_bcm_304()->set_bcm_rearfoglampst( + chassis->mutable_ge3()->mutable_scu_bcm_304()->set_bcm_rearfoglampst( bcm_rearfoglampst(bytes, length)); - chassis->mutable_scu_bcm_304()->set_bcm_parkinglampst( + chassis->mutable_ge3()->mutable_scu_bcm_304()->set_bcm_parkinglampst( bcm_parkinglampst(bytes, length)); - chassis->mutable_scu_bcm_304()->set_bcm_lowbeamst( + chassis->mutable_ge3()->mutable_scu_bcm_304()->set_bcm_lowbeamst( bcm_lowbeamst(bytes, length)); - chassis->mutable_scu_bcm_304()->set_bcm_leftturnlampst( + chassis->mutable_ge3()->mutable_scu_bcm_304()->set_bcm_leftturnlampst( bcm_leftturnlampst(bytes, length)); - chassis->mutable_scu_bcm_304()->set_bcm_keyst( + chassis->mutable_ge3()->mutable_scu_bcm_304()->set_bcm_keyst( bcm_keyst(bytes, length)); - chassis->mutable_scu_bcm_304()->set_bcm_hornst( + chassis->mutable_ge3()->mutable_scu_bcm_304()->set_bcm_hornst( bcm_hornst(bytes, length)); - chassis->mutable_scu_bcm_304()->set_bcm_highbeamst( + chassis->mutable_ge3()->mutable_scu_bcm_304()->set_bcm_highbeamst( bcm_highbeamst(bytes, length)); - chassis->mutable_scu_bcm_304()->set_bcm_hazardlampst( + chassis->mutable_ge3()->mutable_scu_bcm_304()->set_bcm_hazardlampst( bcm_hazardlampst(bytes, length)); - chassis->mutable_scu_bcm_304()->set_bcm_frontfoglampst( + chassis->mutable_ge3()->mutable_scu_bcm_304()->set_bcm_frontfoglampst( bcm_frontfoglampst(bytes, length)); - chassis->mutable_scu_bcm_304()->set_bcm_brakelightswitchst( + chassis->mutable_ge3()->mutable_scu_bcm_304()->set_bcm_brakelightswitchst( bcm_brakelightswitchst(bytes, length)); } diff --git a/modules/canbus_vehicle/ge3/protocol/scu_bcm_304.h b/modules/canbus/vehicle/ge3/protocol/scu_bcm_304.h similarity index 97% rename from modules/canbus_vehicle/ge3/protocol/scu_bcm_304.h rename to modules/canbus/vehicle/ge3/protocol/scu_bcm_304.h index f7cada82024..2ad1667b3f6 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_bcm_304.h +++ b/modules/canbus/vehicle/ge3/protocol/scu_bcm_304.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace ge3 { class Scubcm304 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Scubcm304(); void Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'Vehicle reverse status', 'enum': {0: diff --git a/modules/canbus_vehicle/ge3/protocol/scu_bcm_304_test.cc b/modules/canbus/vehicle/ge3/protocol/scu_bcm_304_test.cc similarity index 55% rename from modules/canbus_vehicle/ge3/protocol/scu_bcm_304_test.cc rename to modules/canbus/vehicle/ge3/protocol/scu_bcm_304_test.cc index b448564e52b..8a7a03c9367 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_bcm_304_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_bcm_304_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_bcm_304.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcm_304.h" #include "gtest/gtest.h" namespace apollo { @@ -29,22 +29,22 @@ class Scubcm304Test : public ::testing::Test { TEST_F(Scubcm304Test, reset) { Scubcm304 scubcm304; int32_t length = 8; - Ge3 chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; scubcm304.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcm_304().bcm_vehreversest(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcm_304().bcm_rightturnlampst(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcm_304().bcm_rearfoglampst(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcm_304().bcm_parkinglampst(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcm_304().bcm_lowbeamst(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcm_304().bcm_leftturnlampst(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcm_304().bcm_keyst(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcm_304().bcm_hornst(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcm_304().bcm_highbeamst(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcm_304().bcm_hazardlampst(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcm_304().bcm_frontfoglampst(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcm_304().bcm_brakelightswitchst(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcm_304().bcm_vehreversest(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcm_304().bcm_rightturnlampst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcm_304().bcm_rearfoglampst(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcm_304().bcm_parkinglampst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcm_304().bcm_lowbeamst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcm_304().bcm_leftturnlampst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcm_304().bcm_keyst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcm_304().bcm_hornst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcm_304().bcm_highbeamst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcm_304().bcm_hazardlampst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcm_304().bcm_frontfoglampst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcm_304().bcm_brakelightswitchst(), 0); } diff --git a/modules/canbus_vehicle/ge3/protocol/scu_bcs_1_306.cc b/modules/canbus/vehicle/ge3/protocol/scu_bcs_1_306.cc similarity index 90% rename from modules/canbus_vehicle/ge3/protocol/scu_bcs_1_306.cc rename to modules/canbus/vehicle/ge3/protocol/scu_bcs_1_306.cc index 070261a9289..076a34c3ba0 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_bcs_1_306.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_bcs_1_306.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_bcs_1_306.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcs_1_306.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,26 +29,26 @@ Scubcs1306::Scubcs1306() {} const int32_t Scubcs1306::ID = 0x306; void Scubcs1306::Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const { - chassis->mutable_scu_bcs_1_306()->set_bcs_aebavailable( + ChassisDetail* chassis) const { + chassis->mutable_ge3()->mutable_scu_bcs_1_306()->set_bcs_aebavailable( bcs_aebavailable(bytes, length)); - chassis->mutable_scu_bcs_1_306()->set_bcs_cddavailable( + chassis->mutable_ge3()->mutable_scu_bcs_1_306()->set_bcs_cddavailable( bcs_cddavailable(bytes, length)); - chassis->mutable_scu_bcs_1_306()->set_bcs_brkpedact( + chassis->mutable_ge3()->mutable_scu_bcs_1_306()->set_bcs_brkpedact( bcs_brkpedact(bytes, length)); - chassis->mutable_scu_bcs_1_306()->set_bcs_intidx( + chassis->mutable_ge3()->mutable_scu_bcs_1_306()->set_bcs_intidx( bcs_intidx(bytes, length)); - chassis->mutable_scu_bcs_1_306()->set_bcs_vdcfaultst( + chassis->mutable_ge3()->mutable_scu_bcs_1_306()->set_bcs_vdcfaultst( bcs_vdcfaultst(bytes, length)); - chassis->mutable_scu_bcs_1_306()->set_bcs_vdcactivest( + chassis->mutable_ge3()->mutable_scu_bcs_1_306()->set_bcs_vdcactivest( bcs_vdcactivest(bytes, length)); - chassis->mutable_scu_bcs_1_306()->set_bcs_absfaultst( + chassis->mutable_ge3()->mutable_scu_bcs_1_306()->set_bcs_absfaultst( bcs_absfaultst(bytes, length)); - chassis->mutable_scu_bcs_1_306()->set_bcs_absactivest( + chassis->mutable_ge3()->mutable_scu_bcs_1_306()->set_bcs_absactivest( bcs_absactivest(bytes, length)); - chassis->mutable_scu_bcs_1_306()->set_bcs_faultst( + chassis->mutable_ge3()->mutable_scu_bcs_1_306()->set_bcs_faultst( bcs_faultst(bytes, length)); - chassis->mutable_scu_bcs_1_306()->set_bcs_drvmode( + chassis->mutable_ge3()->mutable_scu_bcs_1_306()->set_bcs_drvmode( bcs_drvmode(bytes, length)); // newcode chassis->mutable_check_response()->set_is_esp_online( diff --git a/modules/canbus_vehicle/ge3/protocol/scu_bcs_1_306.h b/modules/canbus/vehicle/ge3/protocol/scu_bcs_1_306.h similarity index 97% rename from modules/canbus_vehicle/ge3/protocol/scu_bcs_1_306.h rename to modules/canbus/vehicle/ge3/protocol/scu_bcs_1_306.h index 9528b24faec..50c5613b071 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_bcs_1_306.h +++ b/modules/canbus/vehicle/ge3/protocol/scu_bcs_1_306.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace ge3 { class Scubcs1306 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Scubcs1306(); void Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'VDC active status', 'enum': {0: diff --git a/modules/canbus_vehicle/ge3/protocol/scu_bcs_1_306_test.cc b/modules/canbus/vehicle/ge3/protocol/scu_bcs_1_306_test.cc similarity index 63% rename from modules/canbus_vehicle/ge3/protocol/scu_bcs_1_306_test.cc rename to modules/canbus/vehicle/ge3/protocol/scu_bcs_1_306_test.cc index e1c6561c54b..e8be5ebf5ba 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_bcs_1_306_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_bcs_1_306_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_bcs_1_306.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcs_1_306.h" #include "gtest/gtest.h" namespace apollo { @@ -29,27 +29,27 @@ class Scubcs1306Test : public ::testing::Test { TEST_F(Scubcs1306Test, reset) { Scubcs1306 scubcs1306; int32_t length = 8; - Ge3 chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; scubcs1306.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_1_306().bcs_aebavailable(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_1_306().bcs_aebavailable(), 1); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_1_306().bcs_cddavailable(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_1_306().bcs_cddavailable(), 1); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_1_306().bcs_brkpedact(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_1_306().bcs_brkpedact(), 0.8); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_1_306().bcs_intidx(), 0); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_1_306().bcs_vdcfaultst(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_1_306().bcs_intidx(), 0); // + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_1_306().bcs_vdcfaultst(), 0); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_1_306().bcs_vdcactivest(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_1_306().bcs_vdcactivest(), 0); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_1_306().bcs_absfaultst(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_1_306().bcs_absfaultst(), 0); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_1_306().bcs_absactivest(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_1_306().bcs_absactivest(), 0); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_1_306().bcs_faultst(), 0); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_1_306().bcs_drvmode(), 0); // + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_1_306().bcs_faultst(), 0); // + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_1_306().bcs_drvmode(), 0); // } } // namespace ge3 diff --git a/modules/canbus_vehicle/ge3/protocol/scu_bcs_2_307.cc b/modules/canbus/vehicle/ge3/protocol/scu_bcs_2_307.cc similarity index 90% rename from modules/canbus_vehicle/ge3/protocol/scu_bcs_2_307.cc rename to modules/canbus/vehicle/ge3/protocol/scu_bcs_2_307.cc index c943d829977..d5e660477a9 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_bcs_2_307.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_bcs_2_307.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_bcs_2_307.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcs_2_307.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,16 +29,16 @@ Scubcs2307::Scubcs2307() {} const int32_t Scubcs2307::ID = 0x307; void Scubcs2307::Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const { - chassis->mutable_scu_bcs_2_307()->set_bcs_vehspdvd( + ChassisDetail* chassis) const { + chassis->mutable_ge3()->mutable_scu_bcs_2_307()->set_bcs_vehspdvd( bcs_vehspdvd(bytes, length)); - chassis->mutable_scu_bcs_2_307()->set_bcs_yawrate( + chassis->mutable_ge3()->mutable_scu_bcs_2_307()->set_bcs_yawrate( bcs_yawrate(bytes, length)); - chassis->mutable_scu_bcs_2_307()->set_bcs_vehspd( + chassis->mutable_ge3()->mutable_scu_bcs_2_307()->set_bcs_vehspd( bcs_vehspd(bytes, length)); - chassis->mutable_scu_bcs_2_307()->set_bcs_vehlongaccel( + chassis->mutable_ge3()->mutable_scu_bcs_2_307()->set_bcs_vehlongaccel( bcs_vehlongaccel(bytes, length)); - chassis->mutable_scu_bcs_2_307()->set_bcs_vehlataccel( + chassis->mutable_ge3()->mutable_scu_bcs_2_307()->set_bcs_vehlataccel( bcs_vehlataccel(bytes, length)); } diff --git a/modules/canbus_vehicle/ge3/protocol/scu_bcs_2_307.h b/modules/canbus/vehicle/ge3/protocol/scu_bcs_2_307.h similarity index 94% rename from modules/canbus_vehicle/ge3/protocol/scu_bcs_2_307.h rename to modules/canbus/vehicle/ge3/protocol/scu_bcs_2_307.h index 285d4f2ae3d..241f7d2327d 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_bcs_2_307.h +++ b/modules/canbus/vehicle/ge3/protocol/scu_bcs_2_307.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace ge3 { class Scubcs2307 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Scubcs2307(); void Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'Vehicle speed valid data', 'enum': {0: diff --git a/modules/canbus_vehicle/ge3/protocol/scu_bcs_2_307_test.cc b/modules/canbus/vehicle/ge3/protocol/scu_bcs_2_307_test.cc similarity index 74% rename from modules/canbus_vehicle/ge3/protocol/scu_bcs_2_307_test.cc rename to modules/canbus/vehicle/ge3/protocol/scu_bcs_2_307_test.cc index a3ebf2e394f..b8de5b34ef0 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_bcs_2_307_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_bcs_2_307_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_bcs_2_307.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcs_2_307.h" #include "gtest/gtest.h" namespace apollo { @@ -29,18 +29,18 @@ class Scubcs2307Test : public ::testing::Test { TEST_F(Scubcs2307Test, reset) { Scubcs2307 scubcs2307; int32_t length = 8; - Ge3 chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; scubcs2307.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_2_307().bcs_vehspdvd(), 0); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_2_307().bcs_yawrate(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_2_307().bcs_vehspdvd(), 0); // + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_2_307().bcs_yawrate(), -1.573735); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_2_307().bcs_vehspd(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_2_307().bcs_vehspd(), 8.53125); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_2_307().bcs_vehlongaccel(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_2_307().bcs_vehlongaccel(), -20.290904); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_2_307().bcs_vehlataccel(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_2_307().bcs_vehlataccel(), -21.158968); // } diff --git a/modules/canbus_vehicle/ge3/protocol/scu_bcs_3_308.cc b/modules/canbus/vehicle/ge3/protocol/scu_bcs_3_308.cc similarity index 90% rename from modules/canbus_vehicle/ge3/protocol/scu_bcs_3_308.cc rename to modules/canbus/vehicle/ge3/protocol/scu_bcs_3_308.cc index 0e4019c73ea..357245c40d9 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_bcs_3_308.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_bcs_3_308.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_bcs_3_308.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcs_3_308.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,38 +29,38 @@ Scubcs3308::Scubcs3308() {} const int32_t Scubcs3308::ID = 0x308; void Scubcs3308::Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const { - chassis->mutable_scu_bcs_3_308()->set_bcs_rrwheelspdvd( + ChassisDetail* chassis) const { + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_rrwheelspdvd( bcs_rrwheelspdvd(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_rrwheeldirectionvd( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_rrwheeldirectionvd( bcs_rrwheeldirectionvd(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_rlwheelspdvd( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_rlwheelspdvd( bcs_rlwheelspdvd(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_rlwheeldirectionvd( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_rlwheeldirectionvd( bcs_rlwheeldirectionvd(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_frwheelspdvd( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_frwheelspdvd( bcs_frwheelspdvd(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_frwheeldirectionvd( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_frwheeldirectionvd( bcs_frwheeldirectionvd(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_flwheelspdvd( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_flwheelspdvd( bcs_flwheelspdvd(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_flwheeldirectionvd( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_flwheeldirectionvd( bcs_flwheeldirectionvd(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_rrwheelspd( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_rrwheelspd( bcs_rrwheelspd(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_rrwheeldirection( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_rrwheeldirection( bcs_rrwheeldirection(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_rlwheelspd( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_rlwheelspd( bcs_rlwheelspd(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_rlwheeldirection( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_rlwheeldirection( bcs_rlwheeldirection(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_frwheelspd( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_frwheelspd( bcs_frwheelspd(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_frwheeldirection( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_frwheeldirection( bcs_frwheeldirection(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_flwheelspd( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_flwheelspd( bcs_flwheelspd(bytes, length)); - chassis->mutable_scu_bcs_3_308()->set_bcs_flwheeldirection( + chassis->mutable_ge3()->mutable_scu_bcs_3_308()->set_bcs_flwheeldirection( bcs_flwheeldirection(bytes, length)); } diff --git a/modules/canbus_vehicle/ge3/protocol/scu_bcs_3_308.h b/modules/canbus/vehicle/ge3/protocol/scu_bcs_3_308.h similarity index 97% rename from modules/canbus_vehicle/ge3/protocol/scu_bcs_3_308.h rename to modules/canbus/vehicle/ge3/protocol/scu_bcs_3_308.h index 7d74df214de..7702a73520b 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_bcs_3_308.h +++ b/modules/canbus/vehicle/ge3/protocol/scu_bcs_3_308.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace ge3 { class Scubcs3308 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Scubcs3308(); void Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'Rear right wheel speed valid data', 'enum': diff --git a/modules/canbus_vehicle/ge3/protocol/scu_bcs_3_308_test.cc b/modules/canbus/vehicle/ge3/protocol/scu_bcs_3_308_test.cc similarity index 55% rename from modules/canbus_vehicle/ge3/protocol/scu_bcs_3_308_test.cc rename to modules/canbus/vehicle/ge3/protocol/scu_bcs_3_308_test.cc index 301d8c9aa99..06eb3952611 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_bcs_3_308_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_bcs_3_308_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_bcs_3_308.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_bcs_3_308.h" #include "gtest/gtest.h" namespace apollo { @@ -29,41 +29,41 @@ class Scubcs3308Test : public ::testing::Test { TEST_F(Scubcs3308Test, reset) { Scubcs3308 scubcs3308; int32_t length = 8; - Ge3 chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; scubcs3308.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_3_308().bcs_rrwheelspdvd(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_3_308().bcs_rrwheelspdvd(), 0); // EXPECT_DOUBLE_EQ( - chassis_detail.scu_bcs_3_308().bcs_rrwheeldirectionvd(), 1); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_3_308().bcs_rlwheelspdvd(), + chassis_detail.ge3().scu_bcs_3_308().bcs_rrwheeldirectionvd(), 1); // + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_3_308().bcs_rlwheelspdvd(), 1); // EXPECT_DOUBLE_EQ( - chassis_detail.scu_bcs_3_308().bcs_rlwheeldirectionvd(), 0); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_3_308().bcs_frwheelspdvd(), + chassis_detail.ge3().scu_bcs_3_308().bcs_rlwheeldirectionvd(), 0); // + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_3_308().bcs_frwheelspdvd(), 0); // EXPECT_DOUBLE_EQ( - chassis_detail.scu_bcs_3_308().bcs_frwheeldirectionvd(), 1); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_3_308().bcs_flwheelspdvd(), + chassis_detail.ge3().scu_bcs_3_308().bcs_frwheeldirectionvd(), 1); // + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_3_308().bcs_flwheelspdvd(), 1); // EXPECT_DOUBLE_EQ( - chassis_detail.scu_bcs_3_308().bcs_flwheeldirectionvd(), 0); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_3_308().bcs_rrwheelspd(), + chassis_detail.ge3().scu_bcs_3_308().bcs_flwheeldirectionvd(), 0); // + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_3_308().bcs_rrwheelspd(), 34.3125); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_3_308().bcs_rrwheeldirection(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_3_308().bcs_rrwheeldirection(), 0); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_3_308().bcs_rlwheelspd(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_3_308().bcs_rlwheelspd(), 30.7125); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_3_308().bcs_rlwheeldirection(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_3_308().bcs_rlwheeldirection(), 0); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_3_308().bcs_frwheelspd(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_3_308().bcs_frwheelspd(), 5.4); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_3_308().bcs_frwheeldirection(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_3_308().bcs_frwheeldirection(), 0); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_3_308().bcs_flwheelspd(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_3_308().bcs_flwheelspd(), 1.8); // - EXPECT_DOUBLE_EQ(chassis_detail.scu_bcs_3_308().bcs_flwheeldirection(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_bcs_3_308().bcs_flwheeldirection(), 0); // } diff --git a/modules/canbus_vehicle/ge3/protocol/scu_epb_310.cc b/modules/canbus/vehicle/ge3/protocol/scu_epb_310.cc similarity index 91% rename from modules/canbus_vehicle/ge3/protocol/scu_epb_310.cc rename to modules/canbus/vehicle/ge3/protocol/scu_epb_310.cc index f43e91724bb..cd0deb7505f 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_epb_310.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_epb_310.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_epb_310.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_epb_310.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,14 +29,14 @@ Scuepb310::Scuepb310() {} const int32_t Scuepb310::ID = 0x310; void Scuepb310::Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const { - chassis->mutable_scu_epb_310()->set_epb_intidx( + ChassisDetail* chassis) const { + chassis->mutable_ge3()->mutable_scu_epb_310()->set_epb_intidx( epb_intidx(bytes, length)); - chassis->mutable_scu_epb_310()->set_epb_drvmode( + chassis->mutable_ge3()->mutable_scu_epb_310()->set_epb_drvmode( epb_drvmode(bytes, length)); - chassis->mutable_scu_epb_310()->set_epb_sysst( + chassis->mutable_ge3()->mutable_scu_epb_310()->set_epb_sysst( epb_sysst(bytes, length)); - chassis->mutable_scu_epb_310()->set_epb_faultst( + chassis->mutable_ge3()->mutable_scu_epb_310()->set_epb_faultst( epb_faultst(bytes, length)); } diff --git a/modules/canbus_vehicle/ge3/protocol/scu_epb_310.h b/modules/canbus/vehicle/ge3/protocol/scu_epb_310.h similarity index 94% rename from modules/canbus_vehicle/ge3/protocol/scu_epb_310.h rename to modules/canbus/vehicle/ge3/protocol/scu_epb_310.h index 084f874ebf0..3bf6e12192e 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_epb_310.h +++ b/modules/canbus/vehicle/ge3/protocol/scu_epb_310.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace ge3 { class Scuepb310 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Scuepb310(); void Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'EPS interrupt index', 'enum': {0: diff --git a/modules/canbus_vehicle/ge3/protocol/scu_epb_310_test.cc b/modules/canbus/vehicle/ge3/protocol/scu_epb_310_test.cc similarity index 75% rename from modules/canbus_vehicle/ge3/protocol/scu_epb_310_test.cc rename to modules/canbus/vehicle/ge3/protocol/scu_epb_310_test.cc index f94c67d1acc..f059d006ae3 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_epb_310_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_epb_310_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_epb_310.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_epb_310.h" #include "gtest/gtest.h" namespace apollo { @@ -29,14 +29,14 @@ class Scuepb310Test : public ::testing::Test { TEST_F(Scuepb310Test, reset) { Scuepb310 scuepb310; int32_t length = 8; - Ge3 chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; scuepb310.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.scu_epb_310().epb_intidx(), 2); - EXPECT_DOUBLE_EQ(chassis_detail.scu_epb_310().epb_drvmode(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_epb_310().epb_sysst(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.scu_epb_310().epb_faultst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_epb_310().epb_intidx(), 2); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_epb_310().epb_drvmode(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_epb_310().epb_sysst(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_epb_310().epb_faultst(), 0); } } // namespace ge3 diff --git a/modules/canbus_vehicle/ge3/protocol/scu_eps_311.cc b/modules/canbus/vehicle/ge3/protocol/scu_eps_311.cc similarity index 90% rename from modules/canbus_vehicle/ge3/protocol/scu_eps_311.cc rename to modules/canbus/vehicle/ge3/protocol/scu_eps_311.cc index 25771295be9..1b1bb376162 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_eps_311.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_eps_311.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_eps_311.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_eps_311.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,16 +29,16 @@ Scueps311::Scueps311() {} const int32_t Scueps311::ID = 0x311; void Scueps311::Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const { - chassis->mutable_scu_eps_311()->set_eps_intidx( + ChassisDetail* chassis) const { + chassis->mutable_ge3()->mutable_scu_eps_311()->set_eps_intidx( eps_intidx(bytes, length)); - chassis->mutable_scu_eps_311()->set_eps_steeranglespd( + chassis->mutable_ge3()->mutable_scu_eps_311()->set_eps_steeranglespd( eps_steeranglespd(bytes, length)); - chassis->mutable_scu_eps_311()->set_eps_steerangle( + chassis->mutable_ge3()->mutable_scu_eps_311()->set_eps_steerangle( eps_steerangle(bytes, length)); - chassis->mutable_scu_eps_311()->set_eps_faultst( + chassis->mutable_ge3()->mutable_scu_eps_311()->set_eps_faultst( eps_faultst(bytes, length)); - chassis->mutable_scu_eps_311()->set_eps_drvmode( + chassis->mutable_ge3()->mutable_scu_eps_311()->set_eps_drvmode( eps_drvmode(bytes, length)); // newcode chassis->mutable_check_response()->set_is_eps_online( diff --git a/modules/canbus_vehicle/ge3/protocol/scu_eps_311.h b/modules/canbus/vehicle/ge3/protocol/scu_eps_311.h similarity index 95% rename from modules/canbus_vehicle/ge3/protocol/scu_eps_311.h rename to modules/canbus/vehicle/ge3/protocol/scu_eps_311.h index 5e516a53ad9..3ea3718132d 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_eps_311.h +++ b/modules/canbus/vehicle/ge3/protocol/scu_eps_311.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace ge3 { class Scueps311 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Scueps311(); void Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'EPS interrupt index', 'enum': {0: diff --git a/modules/canbus_vehicle/ge3/protocol/scu_eps_311_test.cc b/modules/canbus/vehicle/ge3/protocol/scu_eps_311_test.cc similarity index 71% rename from modules/canbus_vehicle/ge3/protocol/scu_eps_311_test.cc rename to modules/canbus/vehicle/ge3/protocol/scu_eps_311_test.cc index c2f6ea7ee61..2f63b7dff80 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_eps_311_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_eps_311_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_eps_311.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_eps_311.h" #include "gtest/gtest.h" namespace apollo { @@ -29,15 +29,15 @@ class Scueps311Test : public ::testing::Test { TEST_F(Scueps311Test, reset) { Scueps311 scueps311; int32_t length = 8; - Ge3 chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; scueps311.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.scu_eps_311().eps_intidx(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_eps_311().eps_steeranglespd(), 8); - EXPECT_DOUBLE_EQ(chassis_detail.scu_eps_311().eps_steerangle(), -702.8); - EXPECT_DOUBLE_EQ(chassis_detail.scu_eps_311().eps_faultst(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_eps_311().eps_drvmode(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_eps_311().eps_intidx(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_eps_311().eps_steeranglespd(), 8); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_eps_311().eps_steerangle(), -702.8); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_eps_311().eps_faultst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_eps_311().eps_drvmode(), 1); } } // namespace ge3 diff --git a/modules/canbus_vehicle/ge3/protocol/scu_vcu_1_312.cc b/modules/canbus/vehicle/ge3/protocol/scu_vcu_1_312.cc similarity index 90% rename from modules/canbus_vehicle/ge3/protocol/scu_vcu_1_312.cc rename to modules/canbus/vehicle/ge3/protocol/scu_vcu_1_312.cc index f2f0d195cae..6d8799b56e7 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_vcu_1_312.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_vcu_1_312.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_vcu_1_312.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_vcu_1_312.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,36 +29,36 @@ Scuvcu1312::Scuvcu1312() {} const int32_t Scuvcu1312::ID = 0x312; void Scuvcu1312::Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const { - chassis->mutable_scu_vcu_1_312()->set_vcu_elcsysfault( + ChassisDetail* chassis) const { + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_elcsysfault( vcu_elcsysfault(bytes, length)); - chassis->mutable_scu_vcu_1_312()->set_vcu_brkpedst( + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_brkpedst( vcu_brkpedst(bytes, length)); - chassis->mutable_scu_vcu_1_312()->set_vcu_intidx( + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_intidx( vcu_intidx(bytes, length)); - chassis->mutable_scu_vcu_1_312()->set_vcu_gearintidx( + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_gearintidx( vcu_gearintidx(bytes, length)); - chassis->mutable_scu_vcu_1_312()->set_vcu_geardrvmode( + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_geardrvmode( vcu_geardrvmode(bytes, length)); - chassis->mutable_scu_vcu_1_312()->set_vcu_accpedact( + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_accpedact( vcu_accpedact(bytes, length)); - chassis->mutable_scu_vcu_1_312()->set_vcu_brkpedpst( + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_brkpedpst( vcu_brkpedpst(bytes, length)); - chassis->mutable_scu_vcu_1_312()->set_vcu_vehrng( + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_vehrng( vcu_vehrng(bytes, length)); - chassis->mutable_scu_vcu_1_312()->set_vcu_accpedpst( + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_accpedpst( vcu_accpedpst(bytes, length)); - chassis->mutable_scu_vcu_1_312()->set_vcu_vehrdyst( + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_vehrdyst( vcu_vehrdyst(bytes, length)); - chassis->mutable_scu_vcu_1_312()->set_vcu_faultst( + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_faultst( vcu_faultst(bytes, length)); - chassis->mutable_scu_vcu_1_312()->set_vcu_drvmode( + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_drvmode( vcu_drvmode(bytes, length)); - chassis->mutable_scu_vcu_1_312()->set_vcu_gearpst( + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_gearpst( vcu_gearpst(bytes, length)); - chassis->mutable_scu_vcu_1_312()->set_vcu_gearfaultst( + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_gearfaultst( vcu_gearfaultst(bytes, length)); - chassis->mutable_scu_vcu_1_312()->set_vcu_gearact( + chassis->mutable_ge3()->mutable_scu_vcu_1_312()->set_vcu_gearact( vcu_gearact(bytes, length)); // newcode chassis->mutable_check_response()->set_is_vcu_online( diff --git a/modules/canbus_vehicle/ge3/protocol/scu_vcu_1_312.h b/modules/canbus/vehicle/ge3/protocol/scu_vcu_1_312.h similarity index 97% rename from modules/canbus_vehicle/ge3/protocol/scu_vcu_1_312.h rename to modules/canbus/vehicle/ge3/protocol/scu_vcu_1_312.h index c4c5c4405cc..dad8bb4b859 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_vcu_1_312.h +++ b/modules/canbus/vehicle/ge3/protocol/scu_vcu_1_312.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace ge3 { class Scuvcu1312 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Scuvcu1312(); void Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'Gear fault status', 'enum': {0: diff --git a/modules/canbus/vehicle/ge3/protocol/scu_vcu_1_312_test.cc b/modules/canbus/vehicle/ge3/protocol/scu_vcu_1_312_test.cc new file mode 100644 index 00000000000..7d732165da8 --- /dev/null +++ b/modules/canbus/vehicle/ge3/protocol/scu_vcu_1_312_test.cc @@ -0,0 +1,55 @@ +/****************************************************************************** + * 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/canbus/vehicle/ge3/protocol/scu_vcu_1_312.h" +#include "gtest/gtest.h" + +namespace apollo { +namespace canbus { +namespace ge3 { + +class Scuvcu1312Test : public ::testing::Test { + public: + virtual void SetUp() {} +}; + +TEST_F(Scuvcu1312Test, reset) { + Scuvcu1312 scuvcu1312; + int32_t length = 8; + ChassisDetail chassis_detail; + uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; + + scuvcu1312.Parse(bytes, length, &chassis_detail); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_elcsysfault(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_brkpedst(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_intidx(), 4); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_gearintidx(), 2); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_geardrvmode(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_accpedact(), 14.45); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_brkpedpst(), 6.664); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_vehrng(), 515); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_accpedpst(), 1.568); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_vehrdyst(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_faultst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_drvmode(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_gearpst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_gearfaultst(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_1_312().vcu_gearact(), 0); +} + +} // namespace ge3 +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/ge3/protocol/scu_vcu_2_313.cc b/modules/canbus/vehicle/ge3/protocol/scu_vcu_2_313.cc similarity index 89% rename from modules/canbus_vehicle/ge3/protocol/scu_vcu_2_313.cc rename to modules/canbus/vehicle/ge3/protocol/scu_vcu_2_313.cc index 1a768d3ea33..3a3f45d4e51 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_vcu_2_313.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_vcu_2_313.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_vcu_2_313.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_vcu_2_313.h" #include "glog/logging.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" @@ -29,14 +29,14 @@ Scuvcu2313::Scuvcu2313() {} const int32_t Scuvcu2313::ID = 0x313; void Scuvcu2313::Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const { - chassis->mutable_scu_vcu_2_313()->set_vcu_torqposmax( + ChassisDetail* chassis) const { + chassis->mutable_ge3()->mutable_scu_vcu_2_313()->set_vcu_torqposmax( vcu_torqposmax(bytes, length)); - chassis->mutable_scu_vcu_2_313()->set_vcu_torqnegmax( + chassis->mutable_ge3()->mutable_scu_vcu_2_313()->set_vcu_torqnegmax( vcu_torqnegmax(bytes, length)); - chassis->mutable_scu_vcu_2_313()->set_vcu_torqact( + chassis->mutable_ge3()->mutable_scu_vcu_2_313()->set_vcu_torqact( vcu_torqact(bytes, length)); - chassis->mutable_scu_vcu_2_313()->set_vcu_engspd( + chassis->mutable_ge3()->mutable_scu_vcu_2_313()->set_vcu_engspd( vcu_engspd(bytes, length)); } diff --git a/modules/canbus_vehicle/ge3/protocol/scu_vcu_2_313.h b/modules/canbus/vehicle/ge3/protocol/scu_vcu_2_313.h similarity index 93% rename from modules/canbus_vehicle/ge3/protocol/scu_vcu_2_313.h rename to modules/canbus/vehicle/ge3/protocol/scu_vcu_2_313.h index 508ac6af286..78439f812cd 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_vcu_2_313.h +++ b/modules/canbus/vehicle/ge3/protocol/scu_vcu_2_313.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace ge3 { class Scuvcu2313 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ge3> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Scuvcu2313(); void Parse(const std::uint8_t* bytes, int32_t length, - Ge3* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'Max positive torque', 'offset': 0.0, diff --git a/modules/canbus_vehicle/ge3/protocol/scu_vcu_2_313_test.cc b/modules/canbus/vehicle/ge3/protocol/scu_vcu_2_313_test.cc similarity index 75% rename from modules/canbus_vehicle/ge3/protocol/scu_vcu_2_313_test.cc rename to modules/canbus/vehicle/ge3/protocol/scu_vcu_2_313_test.cc index 3917ef13d9b..105f14e2249 100644 --- a/modules/canbus_vehicle/ge3/protocol/scu_vcu_2_313_test.cc +++ b/modules/canbus/vehicle/ge3/protocol/scu_vcu_2_313_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/ge3/protocol/scu_vcu_2_313.h" +#include "modules/canbus/vehicle/ge3/protocol/scu_vcu_2_313.h" #include "gtest/gtest.h" namespace apollo { @@ -29,15 +29,15 @@ class Scuvcu2313Test : public ::testing::Test { TEST_F(Scuvcu2313Test, reset) { Scuvcu2313 scuvcu2313; int32_t length = 8; - Ge3 chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; scuvcu2313.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_2_313().vcu_torqposmax(), 228); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_2_313().vcu_torqnegmax(), + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_2_313().vcu_torqposmax(), 228); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_2_313().vcu_torqnegmax(), -2796); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_2_313().vcu_torqact(), -2928); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_2_313().vcu_engspd(), 258); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_2_313().vcu_torqact(), -2928); + EXPECT_DOUBLE_EQ(chassis_detail.ge3().scu_vcu_2_313().vcu_engspd(), 258); } } // namespace ge3 diff --git a/modules/canbus_vehicle/gem/BUILD b/modules/canbus/vehicle/gem/BUILD similarity index 50% rename from modules/canbus_vehicle/gem/BUILD rename to modules/canbus/vehicle/gem/BUILD index d1bb2095175..28485100d84 100644 --- a/modules/canbus_vehicle/gem/BUILD +++ b/modules/canbus/vehicle/gem/BUILD @@ -1,5 +1,4 @@ load("@rules_cc//cc:defs.bzl", "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"]) @@ -11,31 +10,19 @@ cc_library( srcs = ["gem_vehicle_factory.cc"], hdrs = ["gem_vehicle_factory.h"], copts = CANBUS_COPTS, - alwayslink = True, deps = [ ":gem_controller", ":gem_message_manager", - "//modules/common/adapters:adapter_gflags", - "//modules/common/status", + "//modules/canbus/proto:canbus_conf_cc_proto", + "//modules/canbus/proto:vehicle_parameter_cc_proto", "//modules/canbus/vehicle:abstract_vehicle_factory", - "//modules/drivers/canbus:sensor_canbus_lib", ], ) -cc_binary( - name = "libgem_vehicle_factory_lib.so", - linkshared = True, - linkstatic = True, - deps = [":gem_vehicle_factory"], -) - - cc_test( name = "gem_vehicle_factory_test", size = "small", srcs = ["gem_vehicle_factory_test.cc"], - data = ["//modules/canbus:test_data"], - linkstatic = True, deps = [ ":gem_vehicle_factory", "@com_google_googletest//:gtest_main", @@ -48,8 +35,8 @@ cc_library( hdrs = ["gem_message_manager.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/gem/proto:gem_cc_proto", - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -72,10 +59,9 @@ cc_library( copts = CANBUS_COPTS, deps = [ ":gem_message_manager", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/canbus_vehicle/gem/proto:gem_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/canbus/vehicle:vehicle_controller_base", - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "//modules/drivers/canbus/can_comm:can_sender", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", @@ -94,67 +80,4 @@ cc_test( ], ) -install( - name = "install", - library_dest = "canbus-vehicle-gem/lib", - data_dest = "canbus-vehicle-gem", - data = [ - ":runtime_data", - ":cyberfile.xml", - ":canbus-vehicle-gem.BUILD", - ], - targets = [ - ":libgem_vehicle_factory_lib.so", - ], - deps = [ - ":pb_gem", - ":pb_hdrs", - ], -) - -install( - name = "pb_hdrs", - data_dest = "canbus-vehicle-gem/include", - data = [ - "//modules/canbus_vehicle/gem/proto:gem_cc_proto", - ], -) - -install_files( - name = "pb_gem", - dest = "canbus-vehicle-gem", - files = [ - "//modules/canbus_vehicle/gem/proto:gem_py_pb2", - ], -) - -filegroup( - name = "runtime_data", - srcs = glob([ - "testdata/**", - ]), -) - -install_src_files( - name = "install_src", - deps = [ - ":install_gem_src", - ":install_gem_hdrs" - ], -) - -install_src_files( - name = "install_gem_src", - src_dir = ["."], - dest = "canbus-vehicle-gem/src", - filter = "*", -) - -install_src_files( - name = "install_gem_hdrs", - src_dir = ["."], - dest = "canbus-vehicle-gem/include", - filter = "*.h", -) - cpplint() diff --git a/modules/canbus_vehicle/gem/gem_controller.cc b/modules/canbus/vehicle/gem/gem_controller.cc similarity index 90% rename from modules/canbus_vehicle/gem/gem_controller.cc rename to modules/canbus/vehicle/gem/gem_controller.cc index 025b2ef9e72..64ddb6b7374 100644 --- a/modules/canbus_vehicle/gem/gem_controller.cc +++ b/modules/canbus/vehicle/gem/gem_controller.cc @@ -14,16 +14,15 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/gem_controller.h" +#include "modules/canbus/vehicle/gem/gem_controller.h" #include -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" #include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "cyber/common/log.h" #include "cyber/time/time.h" -#include "modules/canbus_vehicle/gem/gem_message_manager.h" +#include "modules/canbus/vehicle/gem/gem_message_manager.h" #include "modules/canbus/vehicle/vehicle_controller.h" #include "modules/drivers/canbus/can_comm/can_sender.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" @@ -32,7 +31,6 @@ namespace apollo { namespace canbus { namespace gem { -// using ::apollo::canbus::gem; using ::apollo::common::ErrorCode; using ::apollo::control::ControlCommand; using ::apollo::drivers::canbus::ProtocolData; @@ -47,8 +45,8 @@ const int32_t CHECK_RESPONSE_SPEED_UNIT_FLAG = 2; ErrorCode GemController::Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Gem>* const can_sender, - MessageManager<::apollo::canbus::Gem>* const message_manager) { + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) { if (is_initialized_) { AINFO << "GemController has already been initialized."; return ErrorCode::CANBUS_ERROR; @@ -157,7 +155,7 @@ void GemController::Stop() { Chassis GemController::chassis() { chassis_.Clear(); - Gem chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); // 21, 22, previously 1, 2 @@ -172,10 +170,10 @@ Chassis GemController::chassis() { chassis_.set_engine_started(true); // 5 - if (chassis_detail.has_vehicle_speed_rpt_6f() && - chassis_detail.vehicle_speed_rpt_6f().has_vehicle_speed()) { + if (chassis_detail.gem().has_vehicle_speed_rpt_6f() && + chassis_detail.gem().vehicle_speed_rpt_6f().has_vehicle_speed()) { chassis_.set_speed_mps(static_cast( - chassis_detail.vehicle_speed_rpt_6f().vehicle_speed())); + chassis_detail.gem().vehicle_speed_rpt_6f().vehicle_speed())); } else { chassis_.set_speed_mps(0); } @@ -183,36 +181,36 @@ Chassis GemController::chassis() { // 7 chassis_.set_fuel_range_m(0); // 8 - if (chassis_detail.has_accel_rpt_68() && - chassis_detail.accel_rpt_68().has_output_value()) { + if (chassis_detail.gem().has_accel_rpt_68() && + chassis_detail.gem().accel_rpt_68().has_output_value()) { chassis_.set_throttle_percentage( - static_cast(chassis_detail.accel_rpt_68().output_value())); + static_cast(chassis_detail.gem().accel_rpt_68().output_value())); } else { chassis_.set_throttle_percentage(0); } // 9 - if (chassis_detail.has_brake_rpt_6c() && - chassis_detail.brake_rpt_6c().has_output_value()) { + if (chassis_detail.gem().has_brake_rpt_6c() && + chassis_detail.gem().brake_rpt_6c().has_output_value()) { chassis_.set_brake_percentage( - static_cast(chassis_detail.brake_rpt_6c().output_value())); + static_cast(chassis_detail.gem().brake_rpt_6c().output_value())); } else { chassis_.set_brake_percentage(0); } // 23, previously 10 - if (chassis_detail.has_shift_rpt_66() && - chassis_detail.shift_rpt_66().has_output_value()) { + if (chassis_detail.gem().has_shift_rpt_66() && + chassis_detail.gem().shift_rpt_66().has_output_value()) { Chassis::GearPosition gear_pos = Chassis::GEAR_INVALID; - if (chassis_detail.shift_rpt_66().output_value() == + if (chassis_detail.gem().shift_rpt_66().output_value() == Shift_rpt_66::OUTPUT_VALUE_NEUTRAL) { gear_pos = Chassis::GEAR_NEUTRAL; } - if (chassis_detail.shift_rpt_66().output_value() == + if (chassis_detail.gem().shift_rpt_66().output_value() == Shift_rpt_66::OUTPUT_VALUE_REVERSE) { gear_pos = Chassis::GEAR_REVERSE; } - if (chassis_detail.shift_rpt_66().output_value() == + if (chassis_detail.gem().shift_rpt_66().output_value() == Shift_rpt_66::OUTPUT_VALUE_FORWARD) { gear_pos = Chassis::GEAR_DRIVE; } @@ -224,18 +222,18 @@ Chassis GemController::chassis() { // 11 // TODO(QiL) : verify the unit here. - if (chassis_detail.has_steering_rpt_1_6e() && - chassis_detail.steering_rpt_1_6e().has_output_value()) { - chassis_.set_steering_percentage( - static_cast(chassis_detail.steering_rpt_1_6e().output_value() * - 100.0 / vehicle_params_.max_steer_angle())); + if (chassis_detail.gem().has_steering_rpt_1_6e() && + chassis_detail.gem().steering_rpt_1_6e().has_output_value()) { + chassis_.set_steering_percentage(static_cast( + chassis_detail.gem().steering_rpt_1_6e().output_value() * 100.0 / + vehicle_params_.max_steer_angle())); } else { chassis_.set_steering_percentage(0); } - if (chassis_detail.has_global_rpt_6a() && - chassis_detail.global_rpt_6a().has_pacmod_status()) { - if (chassis_detail.global_rpt_6a().pacmod_status() == + if (chassis_detail.gem().has_global_rpt_6a() && + chassis_detail.gem().global_rpt_6a().has_pacmod_status()) { + if (chassis_detail.gem().global_rpt_6a().pacmod_status() == Global_rpt_6a::PACMOD_STATUS_CONTROL_ENABLED) { chassis_.set_driving_mode(Chassis::COMPLETE_AUTO_DRIVE); global_cmd_69_->set_clear_override( @@ -291,8 +289,6 @@ Chassis GemController::chassis() { return chassis_; } -bool GemController::VerifyID() { return true; } - void GemController::Emergency() { set_driving_mode(Chassis::EMERGENCY_MODE); ResetProtocol(); @@ -444,7 +440,7 @@ void GemController::Steer(double angle, double angle_spd) { const double real_angle = vehicle_params_.max_steer_angle() * angle / 100.0; const double real_angle_spd = - ProtocolData<::apollo::canbus::Gem>::BoundedValue( + ProtocolData<::apollo::canbus::ChassisDetail>::BoundedValue( vehicle_params_.min_steer_angle_rate(), vehicle_params_.max_steer_angle_rate(), vehicle_params_.max_steer_angle_rate() * angle_spd / 100.0); diff --git a/modules/canbus_vehicle/gem/gem_controller.h b/modules/canbus/vehicle/gem/gem_controller.h similarity index 87% rename from modules/canbus_vehicle/gem/gem_controller.h rename to modules/canbus/vehicle/gem/gem_controller.h index f2bfd195955..1d6c783f611 100644 --- a/modules/canbus_vehicle/gem/gem_controller.h +++ b/modules/canbus/vehicle/gem/gem_controller.h @@ -19,26 +19,27 @@ #include #include +#include "cyber/common/macros.h" + #include "modules/canbus/proto/canbus_conf.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" #include "modules/common_msgs/basic_msgs/error_code.pb.h" -#include "modules/common_msgs/chassis_msgs/chassis.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" -#include "cyber/common/macros.h" -#include "modules/canbus_vehicle/gem/protocol/accel_cmd_67.h" -#include "modules/canbus_vehicle/gem/protocol/brake_cmd_6b.h" -#include "modules/canbus_vehicle/gem/protocol/global_cmd_69.h" -#include "modules/canbus_vehicle/gem/protocol/shift_cmd_65.h" -#include "modules/canbus_vehicle/gem/protocol/steering_cmd_6d.h" -#include "modules/canbus_vehicle/gem/protocol/turn_cmd_63.h" +#include "modules/canbus/vehicle/gem/protocol/accel_cmd_67.h" +#include "modules/canbus/vehicle/gem/protocol/brake_cmd_6b.h" +#include "modules/canbus/vehicle/gem/protocol/global_cmd_69.h" +#include "modules/canbus/vehicle/gem/protocol/shift_cmd_65.h" +#include "modules/canbus/vehicle/gem/protocol/steering_cmd_6d.h" +#include "modules/canbus/vehicle/gem/protocol/turn_cmd_63.h" #include "modules/canbus/vehicle/vehicle_controller.h" namespace apollo { namespace canbus { namespace gem { -class GemController final : public VehicleController<::apollo::canbus::Gem> { +class GemController final : public VehicleController { public: GemController() {} @@ -46,8 +47,9 @@ class GemController final : public VehicleController<::apollo::canbus::Gem> { ::apollo::common::ErrorCode Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Gem>* const can_sender, - MessageManager<::apollo::canbus::Gem>* const message_manager) override; + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) + override; bool Start() override; @@ -106,7 +108,6 @@ class GemController final : public VehicleController<::apollo::canbus::Gem> { void SetTurningSignal( const ::apollo::control::ControlCommand& command) override; - bool VerifyID() override; void ResetProtocol(); bool CheckChassisError(); diff --git a/modules/canbus_vehicle/gem/gem_controller_test.cc b/modules/canbus/vehicle/gem/gem_controller_test.cc similarity index 94% rename from modules/canbus_vehicle/gem/gem_controller_test.cc rename to modules/canbus/vehicle/gem/gem_controller_test.cc index 9d6500e7234..c47711d115f 100644 --- a/modules/canbus_vehicle/gem/gem_controller_test.cc +++ b/modules/canbus/vehicle/gem/gem_controller_test.cc @@ -14,18 +14,17 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/gem_controller.h" +#include "modules/canbus/vehicle/gem/gem_controller.h" #include +#include "cyber/common/file.h" #include "gtest/gtest.h" #include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/common_msgs/chassis_msgs/chassis.pb.h" +#include "modules/canbus/vehicle/gem/gem_message_manager.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -#include "cyber/common/file.h" -#include "modules/canbus_vehicle/gem/gem_message_manager.h" #include "modules/drivers/canbus/can_comm/can_sender.h" namespace apollo { @@ -46,7 +45,7 @@ class GemControllerTest : public ::testing::Test { protected: GemController controller_; - CanSender<::apollo::canbus::Gem> sender_; + CanSender<::apollo::canbus::ChassisDetail> sender_; CanbusConf canbus_conf_; VehicleParameter params_; GemMessageManager msg_manager_; diff --git a/modules/canbus_vehicle/gem/gem_message_manager.cc b/modules/canbus/vehicle/gem/gem_message_manager.cc similarity index 55% rename from modules/canbus_vehicle/gem/gem_message_manager.cc rename to modules/canbus/vehicle/gem/gem_message_manager.cc index d07294054e5..ab670051867 100644 --- a/modules/canbus_vehicle/gem/gem_message_manager.cc +++ b/modules/canbus/vehicle/gem/gem_message_manager.cc @@ -13,39 +13,39 @@ See the License for the specific language governing permissions and limitations under the License. ==============================================================================*/ -#include "modules/canbus_vehicle/gem/gem_message_manager.h" +#include "modules/canbus/vehicle/gem/gem_message_manager.h" -#include "modules/canbus_vehicle/gem/protocol/accel_cmd_67.h" -#include "modules/canbus_vehicle/gem/protocol/brake_cmd_6b.h" -#include "modules/canbus_vehicle/gem/protocol/global_cmd_69.h" -#include "modules/canbus_vehicle/gem/protocol/headlight_cmd_76.h" -#include "modules/canbus_vehicle/gem/protocol/horn_cmd_78.h" -#include "modules/canbus_vehicle/gem/protocol/shift_cmd_65.h" -#include "modules/canbus_vehicle/gem/protocol/steering_cmd_6d.h" -#include "modules/canbus_vehicle/gem/protocol/turn_cmd_63.h" -#include "modules/canbus_vehicle/gem/protocol/wiper_cmd_90.h" +#include "modules/canbus/vehicle/gem/protocol/accel_cmd_67.h" +#include "modules/canbus/vehicle/gem/protocol/brake_cmd_6b.h" +#include "modules/canbus/vehicle/gem/protocol/global_cmd_69.h" +#include "modules/canbus/vehicle/gem/protocol/headlight_cmd_76.h" +#include "modules/canbus/vehicle/gem/protocol/horn_cmd_78.h" +#include "modules/canbus/vehicle/gem/protocol/shift_cmd_65.h" +#include "modules/canbus/vehicle/gem/protocol/steering_cmd_6d.h" +#include "modules/canbus/vehicle/gem/protocol/turn_cmd_63.h" +#include "modules/canbus/vehicle/gem/protocol/wiper_cmd_90.h" -#include "modules/canbus_vehicle/gem/protocol/accel_rpt_68.h" -#include "modules/canbus_vehicle/gem/protocol/brake_motor_rpt_1_70.h" -#include "modules/canbus_vehicle/gem/protocol/brake_motor_rpt_2_71.h" -#include "modules/canbus_vehicle/gem/protocol/brake_motor_rpt_3_72.h" -#include "modules/canbus_vehicle/gem/protocol/brake_rpt_6c.h" -#include "modules/canbus_vehicle/gem/protocol/date_time_rpt_83.h" -#include "modules/canbus_vehicle/gem/protocol/global_rpt_6a.h" -#include "modules/canbus_vehicle/gem/protocol/headlight_rpt_77.h" -#include "modules/canbus_vehicle/gem/protocol/horn_rpt_79.h" -#include "modules/canbus_vehicle/gem/protocol/lat_lon_heading_rpt_82.h" -#include "modules/canbus_vehicle/gem/protocol/parking_brake_status_rpt_80.h" -#include "modules/canbus_vehicle/gem/protocol/shift_rpt_66.h" -#include "modules/canbus_vehicle/gem/protocol/steering_motor_rpt_1_73.h" -#include "modules/canbus_vehicle/gem/protocol/steering_motor_rpt_2_74.h" -#include "modules/canbus_vehicle/gem/protocol/steering_motor_rpt_3_75.h" -#include "modules/canbus_vehicle/gem/protocol/steering_rpt_1_6e.h" -#include "modules/canbus_vehicle/gem/protocol/turn_rpt_64.h" -#include "modules/canbus_vehicle/gem/protocol/vehicle_speed_rpt_6f.h" -#include "modules/canbus_vehicle/gem/protocol/wheel_speed_rpt_7a.h" -#include "modules/canbus_vehicle/gem/protocol/wiper_rpt_91.h" -#include "modules/canbus_vehicle/gem/protocol/yaw_rate_rpt_81.h" +#include "modules/canbus/vehicle/gem/protocol/accel_rpt_68.h" +#include "modules/canbus/vehicle/gem/protocol/brake_motor_rpt_1_70.h" +#include "modules/canbus/vehicle/gem/protocol/brake_motor_rpt_2_71.h" +#include "modules/canbus/vehicle/gem/protocol/brake_motor_rpt_3_72.h" +#include "modules/canbus/vehicle/gem/protocol/brake_rpt_6c.h" +#include "modules/canbus/vehicle/gem/protocol/date_time_rpt_83.h" +#include "modules/canbus/vehicle/gem/protocol/global_rpt_6a.h" +#include "modules/canbus/vehicle/gem/protocol/headlight_rpt_77.h" +#include "modules/canbus/vehicle/gem/protocol/horn_rpt_79.h" +#include "modules/canbus/vehicle/gem/protocol/lat_lon_heading_rpt_82.h" +#include "modules/canbus/vehicle/gem/protocol/parking_brake_status_rpt_80.h" +#include "modules/canbus/vehicle/gem/protocol/shift_rpt_66.h" +#include "modules/canbus/vehicle/gem/protocol/steering_motor_rpt_1_73.h" +#include "modules/canbus/vehicle/gem/protocol/steering_motor_rpt_2_74.h" +#include "modules/canbus/vehicle/gem/protocol/steering_motor_rpt_3_75.h" +#include "modules/canbus/vehicle/gem/protocol/steering_rpt_1_6e.h" +#include "modules/canbus/vehicle/gem/protocol/turn_rpt_64.h" +#include "modules/canbus/vehicle/gem/protocol/vehicle_speed_rpt_6f.h" +#include "modules/canbus/vehicle/gem/protocol/wheel_speed_rpt_7a.h" +#include "modules/canbus/vehicle/gem/protocol/wiper_rpt_91.h" +#include "modules/canbus/vehicle/gem/protocol/yaw_rate_rpt_81.h" namespace apollo { namespace canbus { diff --git a/modules/canbus_vehicle/gem/gem_message_manager.h b/modules/canbus/vehicle/gem/gem_message_manager.h similarity index 86% rename from modules/canbus_vehicle/gem/gem_message_manager.h rename to modules/canbus/vehicle/gem/gem_message_manager.h index 0546686115f..f82f86f69bb 100644 --- a/modules/canbus_vehicle/gem/gem_message_manager.h +++ b/modules/canbus/vehicle/gem/gem_message_manager.h @@ -15,8 +15,7 @@ limitations under the License. #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" - +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/message_manager.h" namespace apollo { @@ -25,7 +24,8 @@ namespace gem { using ::apollo::drivers::canbus::MessageManager; -class GemMessageManager : public MessageManager<::apollo::canbus::Gem> { +class GemMessageManager + : public MessageManager<::apollo::canbus::ChassisDetail> { public: GemMessageManager(); virtual ~GemMessageManager(); diff --git a/modules/canbus_vehicle/gem/gem_message_manager_test.cc b/modules/canbus/vehicle/gem/gem_message_manager_test.cc similarity index 65% rename from modules/canbus_vehicle/gem/gem_message_manager_test.cc rename to modules/canbus/vehicle/gem/gem_message_manager_test.cc index 906de67c098..16e165fea91 100644 --- a/modules/canbus_vehicle/gem/gem_message_manager_test.cc +++ b/modules/canbus/vehicle/gem/gem_message_manager_test.cc @@ -14,40 +14,40 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/gem_message_manager.h" +#include "modules/canbus/vehicle/gem/gem_message_manager.h" #include "gtest/gtest.h" -#include "modules/canbus_vehicle/gem/protocol/accel_cmd_67.h" -#include "modules/canbus_vehicle/gem/protocol/accel_rpt_68.h" -#include "modules/canbus_vehicle/gem/protocol/brake_cmd_6b.h" -#include "modules/canbus_vehicle/gem/protocol/brake_motor_rpt_1_70.h" -#include "modules/canbus_vehicle/gem/protocol/brake_motor_rpt_2_71.h" -#include "modules/canbus_vehicle/gem/protocol/brake_motor_rpt_3_72.h" -#include "modules/canbus_vehicle/gem/protocol/brake_rpt_6c.h" -#include "modules/canbus_vehicle/gem/protocol/date_time_rpt_83.h" -#include "modules/canbus_vehicle/gem/protocol/global_cmd_69.h" -#include "modules/canbus_vehicle/gem/protocol/global_rpt_6a.h" -#include "modules/canbus_vehicle/gem/protocol/headlight_cmd_76.h" -#include "modules/canbus_vehicle/gem/protocol/headlight_rpt_77.h" -#include "modules/canbus_vehicle/gem/protocol/horn_cmd_78.h" -#include "modules/canbus_vehicle/gem/protocol/horn_rpt_79.h" -#include "modules/canbus_vehicle/gem/protocol/lat_lon_heading_rpt_82.h" -#include "modules/canbus_vehicle/gem/protocol/parking_brake_status_rpt_80.h" -#include "modules/canbus_vehicle/gem/protocol/shift_cmd_65.h" -#include "modules/canbus_vehicle/gem/protocol/shift_rpt_66.h" -#include "modules/canbus_vehicle/gem/protocol/steering_cmd_6d.h" -#include "modules/canbus_vehicle/gem/protocol/steering_motor_rpt_1_73.h" -#include "modules/canbus_vehicle/gem/protocol/steering_motor_rpt_2_74.h" -#include "modules/canbus_vehicle/gem/protocol/steering_motor_rpt_3_75.h" -#include "modules/canbus_vehicle/gem/protocol/steering_rpt_1_6e.h" -#include "modules/canbus_vehicle/gem/protocol/turn_cmd_63.h" -#include "modules/canbus_vehicle/gem/protocol/turn_rpt_64.h" -#include "modules/canbus_vehicle/gem/protocol/vehicle_speed_rpt_6f.h" -#include "modules/canbus_vehicle/gem/protocol/wheel_speed_rpt_7a.h" -#include "modules/canbus_vehicle/gem/protocol/wiper_cmd_90.h" -#include "modules/canbus_vehicle/gem/protocol/wiper_rpt_91.h" -#include "modules/canbus_vehicle/gem/protocol/yaw_rate_rpt_81.h" +#include "modules/canbus/vehicle/gem/protocol/accel_cmd_67.h" +#include "modules/canbus/vehicle/gem/protocol/accel_rpt_68.h" +#include "modules/canbus/vehicle/gem/protocol/brake_cmd_6b.h" +#include "modules/canbus/vehicle/gem/protocol/brake_motor_rpt_1_70.h" +#include "modules/canbus/vehicle/gem/protocol/brake_motor_rpt_2_71.h" +#include "modules/canbus/vehicle/gem/protocol/brake_motor_rpt_3_72.h" +#include "modules/canbus/vehicle/gem/protocol/brake_rpt_6c.h" +#include "modules/canbus/vehicle/gem/protocol/date_time_rpt_83.h" +#include "modules/canbus/vehicle/gem/protocol/global_cmd_69.h" +#include "modules/canbus/vehicle/gem/protocol/global_rpt_6a.h" +#include "modules/canbus/vehicle/gem/protocol/headlight_cmd_76.h" +#include "modules/canbus/vehicle/gem/protocol/headlight_rpt_77.h" +#include "modules/canbus/vehicle/gem/protocol/horn_cmd_78.h" +#include "modules/canbus/vehicle/gem/protocol/horn_rpt_79.h" +#include "modules/canbus/vehicle/gem/protocol/lat_lon_heading_rpt_82.h" +#include "modules/canbus/vehicle/gem/protocol/parking_brake_status_rpt_80.h" +#include "modules/canbus/vehicle/gem/protocol/shift_cmd_65.h" +#include "modules/canbus/vehicle/gem/protocol/shift_rpt_66.h" +#include "modules/canbus/vehicle/gem/protocol/steering_cmd_6d.h" +#include "modules/canbus/vehicle/gem/protocol/steering_motor_rpt_1_73.h" +#include "modules/canbus/vehicle/gem/protocol/steering_motor_rpt_2_74.h" +#include "modules/canbus/vehicle/gem/protocol/steering_motor_rpt_3_75.h" +#include "modules/canbus/vehicle/gem/protocol/steering_rpt_1_6e.h" +#include "modules/canbus/vehicle/gem/protocol/turn_cmd_63.h" +#include "modules/canbus/vehicle/gem/protocol/turn_rpt_64.h" +#include "modules/canbus/vehicle/gem/protocol/vehicle_speed_rpt_6f.h" +#include "modules/canbus/vehicle/gem/protocol/wheel_speed_rpt_7a.h" +#include "modules/canbus/vehicle/gem/protocol/wiper_cmd_90.h" +#include "modules/canbus/vehicle/gem/protocol/wiper_rpt_91.h" +#include "modules/canbus/vehicle/gem/protocol/yaw_rate_rpt_81.h" namespace apollo { namespace canbus { diff --git a/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_client_test.cc b/modules/canbus/vehicle/gem/gem_vehicle_factory.cc similarity index 55% rename from modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_client_test.cc rename to modules/canbus/vehicle/gem/gem_vehicle_factory.cc index 8df0332bc0c..8dffa6806f6 100644 --- a/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_client_test.cc +++ b/modules/canbus/vehicle/gem/gem_vehicle_factory.cc @@ -14,27 +14,26 @@ * limitations under the License. *****************************************************************************/ -/** - * @file grpc_client_test.cc - * @brief test v2x proxy module and onboard unit interface grpc implement - */ +#include "modules/canbus/vehicle/gem/gem_vehicle_factory.h" -#include "modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_client.h" - -#include "gtest/gtest.h" - -#include "cyber/cyber.h" +#include "cyber/common/log.h" +#include "modules/canbus/vehicle/gem/gem_controller.h" +#include "modules/canbus/vehicle/gem/gem_message_manager.h" +#include "modules/common/util/util.h" namespace apollo { -namespace v2x { +namespace canbus { -TEST(GrpcClientImplTest, Construct) { - apollo::cyber::Init("grpc_client_test"); - GrpcClientImpl grpc_client( - grpc::CreateChannel(FLAGS_grpc_client_host + ":" + FLAGS_grpc_client_port, - grpc::InsecureChannelCredentials())); - bool init_succ = grpc_client.InitFlag(); - EXPECT_TRUE(init_succ); +std::unique_ptr +GemVehicleFactory::CreateVehicleController() { + return std::unique_ptr(new gem::GemController()); } -} // namespace v2x + +std::unique_ptr> +GemVehicleFactory::CreateMessageManager() { + return std::unique_ptr>( + new gem::GemMessageManager()); +} + +} // namespace canbus } // namespace apollo diff --git a/modules/canbus/vehicle/gem/gem_vehicle_factory.h b/modules/canbus/vehicle/gem/gem_vehicle_factory.h new file mode 100644 index 00000000000..6b3cf666dae --- /dev/null +++ b/modules/canbus/vehicle/gem/gem_vehicle_factory.h @@ -0,0 +1,65 @@ +/****************************************************************************** + * 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. + *****************************************************************************/ + +/** + * @file gem_vehicle_factory.h + */ + +#pragma once + +#include + +#include "modules/canbus/proto/vehicle_parameter.pb.h" +#include "modules/canbus/vehicle/abstract_vehicle_factory.h" +#include "modules/canbus/vehicle/vehicle_controller.h" +#include "modules/drivers/canbus/can_comm/message_manager.h" + +/** + * @namespace apollo::canbus + * @brief apollo::canbus + */ +namespace apollo { +namespace canbus { + +/** + * @class GemVehicleFactory + * + * @brief this class is inherited from AbstractVehicleFactory. It can be used to + * create controller and message manager for gem vehicle. + */ +class GemVehicleFactory : public AbstractVehicleFactory { + public: + /** + * @brief destructor + */ + virtual ~GemVehicleFactory() = default; + + /** + * @brief create gem vehicle controller + * @returns a unique_ptr that points to the created controller + */ + std::unique_ptr CreateVehicleController() override; + + /** + * @brief create gem message manager + * @returns a unique_ptr that points to the created message manager + */ + std::unique_ptr> + CreateMessageManager() override; +}; + +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/gem/gem_vehicle_factory_test.cc b/modules/canbus/vehicle/gem/gem_vehicle_factory_test.cc similarity index 63% rename from modules/canbus_vehicle/gem/gem_vehicle_factory_test.cc rename to modules/canbus/vehicle/gem/gem_vehicle_factory_test.cc index 23511e84c77..f379bd1732d 100644 --- a/modules/canbus_vehicle/gem/gem_vehicle_factory_test.cc +++ b/modules/canbus/vehicle/gem/gem_vehicle_factory_test.cc @@ -14,38 +14,34 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/gem_vehicle_factory.h" +#include "modules/canbus/vehicle/gem/gem_vehicle_factory.h" #include "gtest/gtest.h" -#include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "cyber/common/file.h" - namespace apollo { namespace canbus { + class GemVehicleFactoryTest : public ::testing::Test { public: virtual void SetUp() { - std::string canbus_conf_file = - "modules/canbus/testdata/conf/gem_canbus_conf_test.pb.txt"; - cyber::common::GetProtoFromFile(canbus_conf_file, &canbus_conf_); - params_ = canbus_conf_.vehicle_parameter(); - params_.set_brand(apollo::common::GEM); - gem_factory_.SetVehicleParameter(params_); + VehicleParameter parameter; + parameter.set_brand(apollo::common::GEM); + gem_factory_.SetVehicleParameter(parameter); } virtual void TearDown() {} protected: GemVehicleFactory gem_factory_; - CanbusConf canbus_conf_; - VehicleParameter params_; }; -TEST_F(GemVehicleFactoryTest, Init) { - apollo::cyber::Init("vehicle_factory_test"); - EXPECT_EQ(gem_factory_.Init(&canbus_conf_), true); +TEST_F(GemVehicleFactoryTest, InitVehicleController) { + EXPECT_NE(gem_factory_.CreateVehicleController(), nullptr); +} + +TEST_F(GemVehicleFactoryTest, InitMessageManager) { + EXPECT_NE(gem_factory_.CreateMessageManager(), nullptr); } } // namespace canbus diff --git a/modules/canbus_vehicle/gem/protocol/BUILD b/modules/canbus/vehicle/gem/protocol/BUILD similarity index 78% rename from modules/canbus_vehicle/gem/protocol/BUILD rename to modules/canbus/vehicle/gem/protocol/BUILD index 7f420275b74..5b47cc3cdbd 100644 --- a/modules/canbus_vehicle/gem/protocol/BUILD +++ b/modules/canbus/vehicle/gem/protocol/BUILD @@ -3,8 +3,6 @@ load("//tools:cpplint.bzl", "cpplint") package(default_visibility = ["//visibility:public"]) -CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] - cc_library( name = "canbus_gem_protocol", srcs = [ @@ -71,9 +69,9 @@ cc_library( "wiper_rpt_91.h", "yaw_rate_rpt_81.h", ], - copts = CANBUS_COPTS, + copts = ["-DMODULE_NAME=\\\"canbus\\\""], deps = [ - "//modules/canbus_vehicle/gem/proto:gem_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -84,10 +82,9 @@ cc_test( size = "small", srcs = ["accel_rpt_68_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -95,10 +92,9 @@ cc_test( size = "small", srcs = ["brake_rpt_6c_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -106,7 +102,7 @@ cc_test( size = "small", srcs = ["wheel_speed_rpt_7a_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -116,7 +112,7 @@ cc_test( size = "small", srcs = ["yaw_rate_rpt_81_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -126,10 +122,9 @@ cc_test( size = "small", srcs = ["wiper_rpt_91_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -137,7 +132,7 @@ cc_test( size = "small", srcs = ["brake_motor_rpt_1_70_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -147,7 +142,7 @@ cc_test( size = "small", srcs = ["brake_motor_rpt_2_71_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -157,7 +152,7 @@ cc_test( size = "small", srcs = ["brake_motor_rpt_3_72_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -167,7 +162,7 @@ cc_test( size = "small", srcs = ["date_time_rpt_83_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -177,10 +172,9 @@ cc_test( size = "small", srcs = ["global_rpt_6a_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -188,10 +182,9 @@ cc_test( size = "small", srcs = ["lat_lon_heading_rpt_82_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -199,10 +192,9 @@ cc_test( size = "small", srcs = ["steering_motor_rpt_1_73_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -210,10 +202,9 @@ cc_test( size = "small", srcs = ["steering_motor_rpt_2_74_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -221,10 +212,9 @@ cc_test( size = "small", srcs = ["steering_motor_rpt_3_75_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -232,10 +222,9 @@ cc_test( size = "small", srcs = ["steering_rpt_1_6e_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -243,10 +232,9 @@ cc_test( size = "small", srcs = ["accel_cmd_67_test.cc"], deps = [ - "//modules/canbus_vehicle/gem/protocol:canbus_gem_protocol", + "//modules/canbus/vehicle/gem/protocol:canbus_gem_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cpplint() diff --git a/modules/canbus_vehicle/gem/protocol/accel_cmd_67.cc b/modules/canbus/vehicle/gem/protocol/accel_cmd_67.cc similarity index 97% rename from modules/canbus_vehicle/gem/protocol/accel_cmd_67.cc rename to modules/canbus/vehicle/gem/protocol/accel_cmd_67.cc index 26775c74b77..908eed0f7c6 100644 --- a/modules/canbus_vehicle/gem/protocol/accel_cmd_67.cc +++ b/modules/canbus/vehicle/gem/protocol/accel_cmd_67.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/accel_cmd_67.h" +#include "modules/canbus/vehicle/gem/protocol/accel_cmd_67.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/gem/protocol/accel_cmd_67.h b/modules/canbus/vehicle/gem/protocol/accel_cmd_67.h similarity index 90% rename from modules/canbus_vehicle/gem/protocol/accel_cmd_67.h rename to modules/canbus/vehicle/gem/protocol/accel_cmd_67.h index 64e78b5f019..e4b0afb8c08 100644 --- a/modules/canbus_vehicle/gem/protocol/accel_cmd_67.h +++ b/modules/canbus/vehicle/gem/protocol/accel_cmd_67.h @@ -16,16 +16,15 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" - +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { namespace canbus { namespace gem { -class Accelcmd67 - : public ::apollo::drivers::canbus::ProtocolData<::apollo::canbus::Gem> { +class Accelcmd67 : public ::apollo::drivers::canbus::ProtocolData< + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/gem/protocol/accel_cmd_67_test.cc b/modules/canbus/vehicle/gem/protocol/accel_cmd_67_test.cc similarity index 95% rename from modules/canbus_vehicle/gem/protocol/accel_cmd_67_test.cc rename to modules/canbus/vehicle/gem/protocol/accel_cmd_67_test.cc index aa709112494..01258b5e007 100644 --- a/modules/canbus_vehicle/gem/protocol/accel_cmd_67_test.cc +++ b/modules/canbus/vehicle/gem/protocol/accel_cmd_67_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/accel_cmd_67.h" +#include "modules/canbus/vehicle/gem/protocol/accel_cmd_67.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/gem/protocol/accel_rpt_68.cc b/modules/canbus/vehicle/gem/protocol/accel_rpt_68.cc similarity index 89% rename from modules/canbus_vehicle/gem/protocol/accel_rpt_68.cc rename to modules/canbus/vehicle/gem/protocol/accel_rpt_68.cc index 56b696205da..e7fabb51259 100644 --- a/modules/canbus_vehicle/gem/protocol/accel_rpt_68.cc +++ b/modules/canbus/vehicle/gem/protocol/accel_rpt_68.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/accel_rpt_68.h" +#include "modules/canbus/vehicle/gem/protocol/accel_rpt_68.h" #include "glog/logging.h" @@ -31,12 +31,12 @@ Accelrpt68::Accelrpt68() {} const int32_t Accelrpt68::ID = 0x68; void Accelrpt68::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_accel_rpt_68()->set_manual_input( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_accel_rpt_68()->set_manual_input( manual_input(bytes, length)); - chassis->mutable_accel_rpt_68()->set_commanded_value( + chassis->mutable_gem()->mutable_accel_rpt_68()->set_commanded_value( commanded_value(bytes, length)); - chassis->mutable_accel_rpt_68()->set_output_value( + chassis->mutable_gem()->mutable_accel_rpt_68()->set_output_value( output_value(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/accel_rpt_68.h b/modules/canbus/vehicle/gem/protocol/accel_rpt_68.h similarity index 92% rename from modules/canbus_vehicle/gem/protocol/accel_rpt_68.h rename to modules/canbus/vehicle/gem/protocol/accel_rpt_68.h index 4bc7064d87f..4338e71864a 100644 --- a/modules/canbus_vehicle/gem/protocol/accel_rpt_68.h +++ b/modules/canbus/vehicle/gem/protocol/accel_rpt_68.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Accelrpt68 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Accelrpt68(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'MANUAL_INPUT', 'offset': 0.0, 'precision': 0.001, diff --git a/modules/canbus_vehicle/gem/protocol/accel_rpt_68_test.cc b/modules/canbus/vehicle/gem/protocol/accel_rpt_68_test.cc similarity index 77% rename from modules/canbus_vehicle/gem/protocol/accel_rpt_68_test.cc rename to modules/canbus/vehicle/gem/protocol/accel_rpt_68_test.cc index 5912ee0563f..fa55fd6e9c4 100644 --- a/modules/canbus_vehicle/gem/protocol/accel_rpt_68_test.cc +++ b/modules/canbus/vehicle/gem/protocol/accel_rpt_68_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/accel_rpt_68.h" +#include "modules/canbus/vehicle/gem/protocol/accel_rpt_68.h" #include "gtest/gtest.h" @@ -30,13 +30,14 @@ class Accelrpt68Test : public ::testing::Test { TEST_F(Accelrpt68Test, reset) { Accelrpt68 acc; int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; acc.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.accel_rpt_68().manual_input(), 0.258); - EXPECT_DOUBLE_EQ(chassis_detail.accel_rpt_68().commanded_value(), 0.772); - EXPECT_DOUBLE_EQ(chassis_detail.accel_rpt_68().output_value(), 4.37); + EXPECT_DOUBLE_EQ(chassis_detail.gem().accel_rpt_68().manual_input(), 0.258); + EXPECT_DOUBLE_EQ(chassis_detail.gem().accel_rpt_68().commanded_value(), + 0.772); + EXPECT_DOUBLE_EQ(chassis_detail.gem().accel_rpt_68().output_value(), 4.37); } } // namespace gem diff --git a/modules/canbus_vehicle/gem/protocol/brake_cmd_6b.cc b/modules/canbus/vehicle/gem/protocol/brake_cmd_6b.cc similarity index 97% rename from modules/canbus_vehicle/gem/protocol/brake_cmd_6b.cc rename to modules/canbus/vehicle/gem/protocol/brake_cmd_6b.cc index 1c31de8aa97..b4c3c8c05ea 100644 --- a/modules/canbus_vehicle/gem/protocol/brake_cmd_6b.cc +++ b/modules/canbus/vehicle/gem/protocol/brake_cmd_6b.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/brake_cmd_6b.h" +#include "modules/canbus/vehicle/gem/protocol/brake_cmd_6b.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/gem/protocol/brake_cmd_6b.h b/modules/canbus/vehicle/gem/protocol/brake_cmd_6b.h similarity index 93% rename from modules/canbus_vehicle/gem/protocol/brake_cmd_6b.h rename to modules/canbus/vehicle/gem/protocol/brake_cmd_6b.h index a29c9cf3166..3f7ff95c03c 100644 --- a/modules/canbus_vehicle/gem/protocol/brake_cmd_6b.h +++ b/modules/canbus/vehicle/gem/protocol/brake_cmd_6b.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace gem { class Brakecmd6b : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_1_70.cc b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_1_70.cc similarity index 90% rename from modules/canbus_vehicle/gem/protocol/brake_motor_rpt_1_70.cc rename to modules/canbus/vehicle/gem/protocol/brake_motor_rpt_1_70.cc index 2db14068421..289ee70f4ef 100644 --- a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_1_70.cc +++ b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_1_70.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/brake_motor_rpt_1_70.h" +#include "modules/canbus/vehicle/gem/protocol/brake_motor_rpt_1_70.h" #include "glog/logging.h" @@ -31,10 +31,10 @@ Brakemotorrpt170::Brakemotorrpt170() {} const int32_t Brakemotorrpt170::ID = 0x70; void Brakemotorrpt170::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_brake_motor_rpt_1_70()->set_motor_current( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_brake_motor_rpt_1_70()->set_motor_current( motor_current(bytes, length)); - chassis->mutable_brake_motor_rpt_1_70()->set_shaft_position( + chassis->mutable_gem()->mutable_brake_motor_rpt_1_70()->set_shaft_position( shaft_position(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_1_70.h b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_1_70.h similarity index 90% rename from modules/canbus_vehicle/gem/protocol/brake_motor_rpt_1_70.h rename to modules/canbus/vehicle/gem/protocol/brake_motor_rpt_1_70.h index 21a0921b087..c844d23f3f3 100644 --- a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_1_70.h +++ b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_1_70.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Brakemotorrpt170 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Brakemotorrpt170(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'MOTOR_CURRENT', 'offset': 0.0, 'precision': 0.001, diff --git a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_1_70_test.cc b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_1_70_test.cc similarity index 83% rename from modules/canbus_vehicle/gem/protocol/brake_motor_rpt_1_70_test.cc rename to modules/canbus/vehicle/gem/protocol/brake_motor_rpt_1_70_test.cc index d8c0bd0e69a..0f45b2a8bef 100644 --- a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_1_70_test.cc +++ b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_1_70_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/brake_motor_rpt_1_70.h" +#include "modules/canbus/vehicle/gem/protocol/brake_motor_rpt_1_70.h" #include "gtest/gtest.h" @@ -30,12 +30,12 @@ class Brakemotorrpt170Test : public ::testing::Test { TEST_F(Brakemotorrpt170Test, reset) { Brakemotorrpt170 brakermotor1; int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; brakermotor1.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.brake_motor_rpt_1_70().motor_current(), + EXPECT_DOUBLE_EQ(chassis_detail.gem().brake_motor_rpt_1_70().motor_current(), 16909.060000000001); - EXPECT_DOUBLE_EQ(chassis_detail.brake_motor_rpt_1_70().shaft_position(), + EXPECT_DOUBLE_EQ(chassis_detail.gem().brake_motor_rpt_1_70().shaft_position(), 286397.20400000003); } diff --git a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_2_71.cc b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_2_71.cc similarity index 88% rename from modules/canbus_vehicle/gem/protocol/brake_motor_rpt_2_71.cc rename to modules/canbus/vehicle/gem/protocol/brake_motor_rpt_2_71.cc index 65e0ae37532..7f2303b200a 100644 --- a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_2_71.cc +++ b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_2_71.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/brake_motor_rpt_2_71.h" +#include "modules/canbus/vehicle/gem/protocol/brake_motor_rpt_2_71.h" #include "glog/logging.h" @@ -31,12 +31,13 @@ Brakemotorrpt271::Brakemotorrpt271() {} const int32_t Brakemotorrpt271::ID = 0x71; void Brakemotorrpt271::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_brake_motor_rpt_2_71()->set_encoder_temperature( - encoder_temperature(bytes, length)); - chassis->mutable_brake_motor_rpt_2_71()->set_motor_temperature( + ChassisDetail* chassis) const { + chassis->mutable_gem() + ->mutable_brake_motor_rpt_2_71() + ->set_encoder_temperature(encoder_temperature(bytes, length)); + chassis->mutable_gem()->mutable_brake_motor_rpt_2_71()->set_motor_temperature( motor_temperature(bytes, length)); - chassis->mutable_brake_motor_rpt_2_71()->set_angular_speed( + chassis->mutable_gem()->mutable_brake_motor_rpt_2_71()->set_angular_speed( angular_speed(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_2_71.h b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_2_71.h similarity index 92% rename from modules/canbus_vehicle/gem/protocol/brake_motor_rpt_2_71.h rename to modules/canbus/vehicle/gem/protocol/brake_motor_rpt_2_71.h index 570c3b9e227..d7aff2123d5 100644 --- a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_2_71.h +++ b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_2_71.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Brakemotorrpt271 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Brakemotorrpt271(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'ENCODER_TEMPERATURE', 'offset': -40.0, diff --git a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_2_71_test.cc b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_2_71_test.cc similarity index 79% rename from modules/canbus_vehicle/gem/protocol/brake_motor_rpt_2_71_test.cc rename to modules/canbus/vehicle/gem/protocol/brake_motor_rpt_2_71_test.cc index 37fe61d9c00..91d8dfb3e94 100644 --- a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_2_71_test.cc +++ b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_2_71_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/brake_motor_rpt_2_71.h" +#include "modules/canbus/vehicle/gem/protocol/brake_motor_rpt_2_71.h" #include "gtest/gtest.h" @@ -30,14 +30,14 @@ class Brakemotorrpt271Test : public ::testing::Test { TEST_F(Brakemotorrpt271Test, reset) { Brakemotorrpt271 brakermotor2; int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; brakermotor2.Parse(bytes, length, &chassis_detail); EXPECT_DOUBLE_EQ( - chassis_detail.brake_motor_rpt_2_71().encoder_temperature(), 218); + chassis_detail.gem().brake_motor_rpt_2_71().encoder_temperature(), 218); EXPECT_DOUBLE_EQ( - chassis_detail.brake_motor_rpt_2_71().motor_temperature(), 732); - EXPECT_DOUBLE_EQ(chassis_detail.brake_motor_rpt_2_71().angular_speed(), + chassis_detail.gem().brake_motor_rpt_2_71().motor_temperature(), 732); + EXPECT_DOUBLE_EQ(chassis_detail.gem().brake_motor_rpt_2_71().angular_speed(), 286397.20400000003); } diff --git a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_3_72.cc b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_3_72.cc similarity index 90% rename from modules/canbus_vehicle/gem/protocol/brake_motor_rpt_3_72.cc rename to modules/canbus/vehicle/gem/protocol/brake_motor_rpt_3_72.cc index 97d80a804b6..e440bc62bce 100644 --- a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_3_72.cc +++ b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_3_72.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/brake_motor_rpt_3_72.h" +#include "modules/canbus/vehicle/gem/protocol/brake_motor_rpt_3_72.h" #include "glog/logging.h" @@ -31,10 +31,10 @@ Brakemotorrpt372::Brakemotorrpt372() {} const int32_t Brakemotorrpt372::ID = 0x72; void Brakemotorrpt372::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_brake_motor_rpt_3_72()->set_torque_output( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_brake_motor_rpt_3_72()->set_torque_output( torque_output(bytes, length)); - chassis->mutable_brake_motor_rpt_3_72()->set_torque_input( + chassis->mutable_gem()->mutable_brake_motor_rpt_3_72()->set_torque_input( torque_input(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_3_72.h b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_3_72.h similarity index 91% rename from modules/canbus_vehicle/gem/protocol/brake_motor_rpt_3_72.h rename to modules/canbus/vehicle/gem/protocol/brake_motor_rpt_3_72.h index e94a160ef27..9b89c560e32 100644 --- a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_3_72.h +++ b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_3_72.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Brakemotorrpt372 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Brakemotorrpt372(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'TORQUE_OUTPUT', 'offset': 0.0, 'precision': 0.001, diff --git a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_3_72_test.cc b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_3_72_test.cc similarity index 83% rename from modules/canbus_vehicle/gem/protocol/brake_motor_rpt_3_72_test.cc rename to modules/canbus/vehicle/gem/protocol/brake_motor_rpt_3_72_test.cc index d8e07d724f3..51d043f6cf2 100644 --- a/modules/canbus_vehicle/gem/protocol/brake_motor_rpt_3_72_test.cc +++ b/modules/canbus/vehicle/gem/protocol/brake_motor_rpt_3_72_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/brake_motor_rpt_3_72.h" +#include "modules/canbus/vehicle/gem/protocol/brake_motor_rpt_3_72.h" #include "gtest/gtest.h" @@ -30,12 +30,12 @@ class Brakemotorrpt372Test : public ::testing::Test { TEST_F(Brakemotorrpt372Test, reset) { Brakemotorrpt372 brakermotor3; int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; brakermotor3.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.brake_motor_rpt_3_72().torque_output(), + EXPECT_DOUBLE_EQ(chassis_detail.gem().brake_motor_rpt_3_72().torque_output(), 16909.060000000001); - EXPECT_DOUBLE_EQ(chassis_detail.brake_motor_rpt_3_72().torque_input(), + EXPECT_DOUBLE_EQ(chassis_detail.gem().brake_motor_rpt_3_72().torque_input(), 286397.20400000003); } diff --git a/modules/canbus_vehicle/gem/protocol/brake_rpt_6c.cc b/modules/canbus/vehicle/gem/protocol/brake_rpt_6c.cc similarity index 89% rename from modules/canbus_vehicle/gem/protocol/brake_rpt_6c.cc rename to modules/canbus/vehicle/gem/protocol/brake_rpt_6c.cc index 8e233c6c69f..67bf92b3ba7 100644 --- a/modules/canbus_vehicle/gem/protocol/brake_rpt_6c.cc +++ b/modules/canbus/vehicle/gem/protocol/brake_rpt_6c.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/brake_rpt_6c.h" +#include "modules/canbus/vehicle/gem/protocol/brake_rpt_6c.h" #include "glog/logging.h" @@ -31,14 +31,14 @@ Brakerpt6c::Brakerpt6c() {} const int32_t Brakerpt6c::ID = 0x6C; void Brakerpt6c::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_brake_rpt_6c()->set_manual_input( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_brake_rpt_6c()->set_manual_input( manual_input(bytes, length)); - chassis->mutable_brake_rpt_6c()->set_commanded_value( + chassis->mutable_gem()->mutable_brake_rpt_6c()->set_commanded_value( commanded_value(bytes, length)); - chassis->mutable_brake_rpt_6c()->set_output_value( + chassis->mutable_gem()->mutable_brake_rpt_6c()->set_output_value( output_value(bytes, length)); - chassis->mutable_brake_rpt_6c()->set_brake_on_off( + chassis->mutable_gem()->mutable_brake_rpt_6c()->set_brake_on_off( brake_on_off(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/brake_rpt_6c.h b/modules/canbus/vehicle/gem/protocol/brake_rpt_6c.h similarity index 93% rename from modules/canbus_vehicle/gem/protocol/brake_rpt_6c.h rename to modules/canbus/vehicle/gem/protocol/brake_rpt_6c.h index 90e36e8671c..87f2d8c5adf 100644 --- a/modules/canbus_vehicle/gem/protocol/brake_rpt_6c.h +++ b/modules/canbus/vehicle/gem/protocol/brake_rpt_6c.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Brakerpt6c : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Brakerpt6c(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'MANUAL_INPUT', 'offset': 0.0, 'precision': 0.001, diff --git a/modules/canbus_vehicle/gem/protocol/brake_rpt_6c_test.cc b/modules/canbus/vehicle/gem/protocol/brake_rpt_6c_test.cc similarity index 89% rename from modules/canbus_vehicle/gem/protocol/brake_rpt_6c_test.cc rename to modules/canbus/vehicle/gem/protocol/brake_rpt_6c_test.cc index 02ec732e7ed..8993a601da3 100644 --- a/modules/canbus_vehicle/gem/protocol/brake_rpt_6c_test.cc +++ b/modules/canbus/vehicle/gem/protocol/brake_rpt_6c_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/brake_rpt_6c.h" +#include "modules/canbus/vehicle/gem/protocol/brake_rpt_6c.h" #include "gtest/gtest.h" @@ -24,13 +24,13 @@ namespace gem { TEST(Brake61Test, General) { int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; Brakerpt6c brake; brake.Parse(bytes, length, &chassis_detail); - auto &brakerpt = chassis_detail.brake_rpt_6c(); + auto &brakerpt = chassis_detail.gem().brake_rpt_6c(); EXPECT_DOUBLE_EQ(brakerpt.manual_input(), 0.258); EXPECT_DOUBLE_EQ(brakerpt.commanded_value(), 0.772); EXPECT_DOUBLE_EQ(brakerpt.output_value(), 4.37); diff --git a/modules/canbus_vehicle/gem/protocol/date_time_rpt_83.cc b/modules/canbus/vehicle/gem/protocol/date_time_rpt_83.cc similarity index 87% rename from modules/canbus_vehicle/gem/protocol/date_time_rpt_83.cc rename to modules/canbus/vehicle/gem/protocol/date_time_rpt_83.cc index f98ac2f5e5a..dbef14ddef1 100644 --- a/modules/canbus_vehicle/gem/protocol/date_time_rpt_83.cc +++ b/modules/canbus/vehicle/gem/protocol/date_time_rpt_83.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/date_time_rpt_83.h" +#include "modules/canbus/vehicle/gem/protocol/date_time_rpt_83.h" #include "glog/logging.h" @@ -31,18 +31,18 @@ Datetimerpt83::Datetimerpt83() {} const int32_t Datetimerpt83::ID = 0x83; void Datetimerpt83::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_date_time_rpt_83()->set_time_second( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_date_time_rpt_83()->set_time_second( time_second(bytes, length)); - chassis->mutable_date_time_rpt_83()->set_time_minute( + chassis->mutable_gem()->mutable_date_time_rpt_83()->set_time_minute( time_minute(bytes, length)); - chassis->mutable_date_time_rpt_83()->set_time_hour( + chassis->mutable_gem()->mutable_date_time_rpt_83()->set_time_hour( time_hour(bytes, length)); - chassis->mutable_date_time_rpt_83()->set_date_day( + chassis->mutable_gem()->mutable_date_time_rpt_83()->set_date_day( date_day(bytes, length)); - chassis->mutable_date_time_rpt_83()->set_date_month( + chassis->mutable_gem()->mutable_date_time_rpt_83()->set_date_month( date_month(bytes, length)); - chassis->mutable_date_time_rpt_83()->set_date_year( + chassis->mutable_gem()->mutable_date_time_rpt_83()->set_date_year( date_year(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/date_time_rpt_83.h b/modules/canbus/vehicle/gem/protocol/date_time_rpt_83.h similarity index 94% rename from modules/canbus_vehicle/gem/protocol/date_time_rpt_83.h rename to modules/canbus/vehicle/gem/protocol/date_time_rpt_83.h index d494eb311da..a0f91f42dfe 100644 --- a/modules/canbus_vehicle/gem/protocol/date_time_rpt_83.h +++ b/modules/canbus/vehicle/gem/protocol/date_time_rpt_83.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Datetimerpt83 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Datetimerpt83(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'TIME_SECOND', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/gem/protocol/date_time_rpt_83_test.cc b/modules/canbus/vehicle/gem/protocol/date_time_rpt_83_test.cc similarity index 68% rename from modules/canbus_vehicle/gem/protocol/date_time_rpt_83_test.cc rename to modules/canbus/vehicle/gem/protocol/date_time_rpt_83_test.cc index 058dc626bda..1b885501fae 100644 --- a/modules/canbus_vehicle/gem/protocol/date_time_rpt_83_test.cc +++ b/modules/canbus/vehicle/gem/protocol/date_time_rpt_83_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/date_time_rpt_83.h" +#include "modules/canbus/vehicle/gem/protocol/date_time_rpt_83.h" #include "gtest/gtest.h" @@ -30,15 +30,15 @@ class Datetimerpt83Test : public ::testing::Test { TEST_F(Datetimerpt83Test, reset) { Datetimerpt83 datetime; int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; datetime.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.date_time_rpt_83().time_second(), 18); - EXPECT_DOUBLE_EQ(chassis_detail.date_time_rpt_83().time_minute(), 17); - EXPECT_DOUBLE_EQ(chassis_detail.date_time_rpt_83().time_hour(), 4); - EXPECT_DOUBLE_EQ(chassis_detail.date_time_rpt_83().date_day(), 4); - EXPECT_DOUBLE_EQ(chassis_detail.date_time_rpt_83().date_month(), 3); - EXPECT_DOUBLE_EQ(chassis_detail.date_time_rpt_83().date_year(), 2001); + EXPECT_DOUBLE_EQ(chassis_detail.gem().date_time_rpt_83().time_second(), 18); + EXPECT_DOUBLE_EQ(chassis_detail.gem().date_time_rpt_83().time_minute(), 17); + EXPECT_DOUBLE_EQ(chassis_detail.gem().date_time_rpt_83().time_hour(), 4); + EXPECT_DOUBLE_EQ(chassis_detail.gem().date_time_rpt_83().date_day(), 4); + EXPECT_DOUBLE_EQ(chassis_detail.gem().date_time_rpt_83().date_month(), 3); + EXPECT_DOUBLE_EQ(chassis_detail.gem().date_time_rpt_83().date_year(), 2001); } } // namespace gem diff --git a/modules/canbus_vehicle/gem/protocol/global_cmd_69.cc b/modules/canbus/vehicle/gem/protocol/global_cmd_69.cc similarity index 98% rename from modules/canbus_vehicle/gem/protocol/global_cmd_69.cc rename to modules/canbus/vehicle/gem/protocol/global_cmd_69.cc index 79ad2714906..85db7cf0e8e 100644 --- a/modules/canbus_vehicle/gem/protocol/global_cmd_69.cc +++ b/modules/canbus/vehicle/gem/protocol/global_cmd_69.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/global_cmd_69.h" +#include "modules/canbus/vehicle/gem/protocol/global_cmd_69.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/gem/protocol/global_cmd_69.h b/modules/canbus/vehicle/gem/protocol/global_cmd_69.h similarity index 96% rename from modules/canbus_vehicle/gem/protocol/global_cmd_69.h rename to modules/canbus/vehicle/gem/protocol/global_cmd_69.h index 5218ecb7736..39e267fa552 100644 --- a/modules/canbus_vehicle/gem/protocol/global_cmd_69.h +++ b/modules/canbus/vehicle/gem/protocol/global_cmd_69.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace gem { class Globalcmd69 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/gem/protocol/global_rpt_6a.cc b/modules/canbus/vehicle/gem/protocol/global_rpt_6a.cc similarity index 88% rename from modules/canbus_vehicle/gem/protocol/global_rpt_6a.cc rename to modules/canbus/vehicle/gem/protocol/global_rpt_6a.cc index 690346e9c41..fa63530f110 100644 --- a/modules/canbus_vehicle/gem/protocol/global_rpt_6a.cc +++ b/modules/canbus/vehicle/gem/protocol/global_rpt_6a.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/global_rpt_6a.h" +#include "modules/canbus/vehicle/gem/protocol/global_rpt_6a.h" #include "glog/logging.h" @@ -31,20 +31,20 @@ Globalrpt6a::Globalrpt6a() {} const int32_t Globalrpt6a::ID = 0x6A; void Globalrpt6a::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_global_rpt_6a()->set_pacmod_status( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_global_rpt_6a()->set_pacmod_status( pacmod_status(bytes, length)); - chassis->mutable_global_rpt_6a()->set_override_status( + chassis->mutable_gem()->mutable_global_rpt_6a()->set_override_status( override_status(bytes, length)); - chassis->mutable_global_rpt_6a()->set_veh_can_timeout( + chassis->mutable_gem()->mutable_global_rpt_6a()->set_veh_can_timeout( veh_can_timeout(bytes, length)); - chassis->mutable_global_rpt_6a()->set_str_can_timeout( + chassis->mutable_gem()->mutable_global_rpt_6a()->set_str_can_timeout( str_can_timeout(bytes, length)); - chassis->mutable_global_rpt_6a()->set_brk_can_timeout( + chassis->mutable_gem()->mutable_global_rpt_6a()->set_brk_can_timeout( brk_can_timeout(bytes, length)); - chassis->mutable_global_rpt_6a()->set_usr_can_timeout( + chassis->mutable_gem()->mutable_global_rpt_6a()->set_usr_can_timeout( usr_can_timeout(bytes, length)); - chassis->mutable_global_rpt_6a()->set_usr_can_read_errors( + chassis->mutable_gem()->mutable_global_rpt_6a()->set_usr_can_read_errors( usr_can_read_errors(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/global_rpt_6a.h b/modules/canbus/vehicle/gem/protocol/global_rpt_6a.h similarity index 95% rename from modules/canbus_vehicle/gem/protocol/global_rpt_6a.h rename to modules/canbus/vehicle/gem/protocol/global_rpt_6a.h index 31235a6679b..4ac31020f83 100644 --- a/modules/canbus_vehicle/gem/protocol/global_rpt_6a.h +++ b/modules/canbus/vehicle/gem/protocol/global_rpt_6a.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Globalrpt6a : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Globalrpt6a(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'PACMOD_STATUS', 'enum': {0: diff --git a/modules/canbus_vehicle/gem/protocol/global_rpt_6a_test.cc b/modules/canbus/vehicle/gem/protocol/global_rpt_6a_test.cc similarity index 65% rename from modules/canbus_vehicle/gem/protocol/global_rpt_6a_test.cc rename to modules/canbus/vehicle/gem/protocol/global_rpt_6a_test.cc index f652c7880f5..34393de011a 100644 --- a/modules/canbus_vehicle/gem/protocol/global_rpt_6a_test.cc +++ b/modules/canbus/vehicle/gem/protocol/global_rpt_6a_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/global_rpt_6a.h" +#include "modules/canbus/vehicle/gem/protocol/global_rpt_6a.h" #include "gtest/gtest.h" @@ -30,16 +30,16 @@ class Globalrpt6aTest : public ::testing::Test { TEST_F(Globalrpt6aTest, reset) { Globalrpt6a globalrpt; int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; globalrpt.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.global_rpt_6a().pacmod_status(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.global_rpt_6a().override_status(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.global_rpt_6a().veh_can_timeout(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.global_rpt_6a().str_can_timeout(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.global_rpt_6a().brk_can_timeout(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.global_rpt_6a().usr_can_timeout(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.global_rpt_6a().usr_can_read_errors(), + EXPECT_DOUBLE_EQ(chassis_detail.gem().global_rpt_6a().pacmod_status(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.gem().global_rpt_6a().override_status(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.gem().global_rpt_6a().veh_can_timeout(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.gem().global_rpt_6a().str_can_timeout(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.gem().global_rpt_6a().brk_can_timeout(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.gem().global_rpt_6a().usr_can_timeout(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.gem().global_rpt_6a().usr_can_read_errors(), 4884); } diff --git a/modules/canbus_vehicle/gem/protocol/headlight_cmd_76.cc b/modules/canbus/vehicle/gem/protocol/headlight_cmd_76.cc similarity index 97% rename from modules/canbus_vehicle/gem/protocol/headlight_cmd_76.cc rename to modules/canbus/vehicle/gem/protocol/headlight_cmd_76.cc index e162f19c23c..4759a3af821 100644 --- a/modules/canbus_vehicle/gem/protocol/headlight_cmd_76.cc +++ b/modules/canbus/vehicle/gem/protocol/headlight_cmd_76.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/headlight_cmd_76.h" +#include "modules/canbus/vehicle/gem/protocol/headlight_cmd_76.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/gem/protocol/headlight_cmd_76.h b/modules/canbus/vehicle/gem/protocol/headlight_cmd_76.h similarity index 94% rename from modules/canbus_vehicle/gem/protocol/headlight_cmd_76.h rename to modules/canbus/vehicle/gem/protocol/headlight_cmd_76.h index 3d2d0e15247..e0fca4c1cf8 100644 --- a/modules/canbus_vehicle/gem/protocol/headlight_cmd_76.h +++ b/modules/canbus/vehicle/gem/protocol/headlight_cmd_76.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace gem { class Headlightcmd76 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/gem/protocol/headlight_rpt_77.cc b/modules/canbus/vehicle/gem/protocol/headlight_rpt_77.cc similarity index 90% rename from modules/canbus_vehicle/gem/protocol/headlight_rpt_77.cc rename to modules/canbus/vehicle/gem/protocol/headlight_rpt_77.cc index 59eb746bfcd..9f3e4d8e936 100644 --- a/modules/canbus_vehicle/gem/protocol/headlight_rpt_77.cc +++ b/modules/canbus/vehicle/gem/protocol/headlight_rpt_77.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/headlight_rpt_77.h" +#include "modules/canbus/vehicle/gem/protocol/headlight_rpt_77.h" #include "glog/logging.h" @@ -31,12 +31,12 @@ Headlightrpt77::Headlightrpt77() {} const int32_t Headlightrpt77::ID = 0x77; void Headlightrpt77::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_headlight_rpt_77()->set_output_value( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_headlight_rpt_77()->set_output_value( output_value(bytes, length)); - chassis->mutable_headlight_rpt_77()->set_manual_input( + chassis->mutable_gem()->mutable_headlight_rpt_77()->set_manual_input( manual_input(bytes, length)); - chassis->mutable_headlight_rpt_77()->set_commanded_value( + chassis->mutable_gem()->mutable_headlight_rpt_77()->set_commanded_value( commanded_value(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/headlight_rpt_77.h b/modules/canbus/vehicle/gem/protocol/headlight_rpt_77.h similarity index 93% rename from modules/canbus_vehicle/gem/protocol/headlight_rpt_77.h rename to modules/canbus/vehicle/gem/protocol/headlight_rpt_77.h index 44aa05c5ee7..4950a32c669 100644 --- a/modules/canbus_vehicle/gem/protocol/headlight_rpt_77.h +++ b/modules/canbus/vehicle/gem/protocol/headlight_rpt_77.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Headlightrpt77 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Headlightrpt77(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'OUTPUT_VALUE', 'enum': {0: diff --git a/modules/canbus_vehicle/gem/protocol/horn_cmd_78.cc b/modules/canbus/vehicle/gem/protocol/horn_cmd_78.cc similarity index 97% rename from modules/canbus_vehicle/gem/protocol/horn_cmd_78.cc rename to modules/canbus/vehicle/gem/protocol/horn_cmd_78.cc index 6cd57f47124..9b623eb5fa1 100644 --- a/modules/canbus_vehicle/gem/protocol/horn_cmd_78.cc +++ b/modules/canbus/vehicle/gem/protocol/horn_cmd_78.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/horn_cmd_78.h" +#include "modules/canbus/vehicle/gem/protocol/horn_cmd_78.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/gem/protocol/horn_cmd_78.h b/modules/canbus/vehicle/gem/protocol/horn_cmd_78.h similarity index 94% rename from modules/canbus_vehicle/gem/protocol/horn_cmd_78.h rename to modules/canbus/vehicle/gem/protocol/horn_cmd_78.h index 86fd283073d..56d44bbf6fe 100644 --- a/modules/canbus_vehicle/gem/protocol/horn_cmd_78.h +++ b/modules/canbus/vehicle/gem/protocol/horn_cmd_78.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace gem { class Horncmd78 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/gem/protocol/horn_rpt_79.cc b/modules/canbus/vehicle/gem/protocol/horn_rpt_79.cc similarity index 90% rename from modules/canbus_vehicle/gem/protocol/horn_rpt_79.cc rename to modules/canbus/vehicle/gem/protocol/horn_rpt_79.cc index c2b6948935c..f1bee093eb4 100644 --- a/modules/canbus_vehicle/gem/protocol/horn_rpt_79.cc +++ b/modules/canbus/vehicle/gem/protocol/horn_rpt_79.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/horn_rpt_79.h" +#include "modules/canbus/vehicle/gem/protocol/horn_rpt_79.h" #include "glog/logging.h" @@ -31,12 +31,12 @@ Hornrpt79::Hornrpt79() {} const int32_t Hornrpt79::ID = 0x79; void Hornrpt79::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_horn_rpt_79()->set_output_value( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_horn_rpt_79()->set_output_value( output_value(bytes, length)); - chassis->mutable_horn_rpt_79()->set_commanded_value( + chassis->mutable_gem()->mutable_horn_rpt_79()->set_commanded_value( commanded_value(bytes, length)); - chassis->mutable_horn_rpt_79()->set_manual_input( + chassis->mutable_gem()->mutable_horn_rpt_79()->set_manual_input( manual_input(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/horn_rpt_79.h b/modules/canbus/vehicle/gem/protocol/horn_rpt_79.h similarity index 93% rename from modules/canbus_vehicle/gem/protocol/horn_rpt_79.h rename to modules/canbus/vehicle/gem/protocol/horn_rpt_79.h index cd213f9bf79..4e5ae435c37 100644 --- a/modules/canbus_vehicle/gem/protocol/horn_rpt_79.h +++ b/modules/canbus/vehicle/gem/protocol/horn_rpt_79.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Hornrpt79 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Hornrpt79(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'OUTPUT_VALUE', 'enum': {0: 'OUTPUT_VALUE_OFF', 1: diff --git a/modules/canbus_vehicle/gem/protocol/lat_lon_heading_rpt_82.cc b/modules/canbus/vehicle/gem/protocol/lat_lon_heading_rpt_82.cc similarity index 82% rename from modules/canbus_vehicle/gem/protocol/lat_lon_heading_rpt_82.cc rename to modules/canbus/vehicle/gem/protocol/lat_lon_heading_rpt_82.cc index 6978a95cfd4..6a2ed4e4761 100644 --- a/modules/canbus_vehicle/gem/protocol/lat_lon_heading_rpt_82.cc +++ b/modules/canbus/vehicle/gem/protocol/lat_lon_heading_rpt_82.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/lat_lon_heading_rpt_82.h" +#include "modules/canbus/vehicle/gem/protocol/lat_lon_heading_rpt_82.h" #include "glog/logging.h" @@ -31,21 +31,27 @@ Latlonheadingrpt82::Latlonheadingrpt82() {} const int32_t Latlonheadingrpt82::ID = 0x82; void Latlonheadingrpt82::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_lat_lon_heading_rpt_82()->set_heading( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_lat_lon_heading_rpt_82()->set_heading( heading(bytes, length)); - chassis->mutable_lat_lon_heading_rpt_82()->set_longitude_seconds( - longitude_seconds(bytes, length)); - chassis->mutable_lat_lon_heading_rpt_82()->set_longitude_minutes( - longitude_minutes(bytes, length)); - chassis->mutable_lat_lon_heading_rpt_82()->set_longitude_degrees( - longitude_degrees(bytes, length)); - chassis->mutable_lat_lon_heading_rpt_82()->set_latitude_seconds( - latitude_seconds(bytes, length)); - chassis->mutable_lat_lon_heading_rpt_82()->set_latitude_minutes( - latitude_minutes(bytes, length)); - chassis->mutable_lat_lon_heading_rpt_82()->set_latitude_degrees( - latitude_degrees(bytes, length)); + chassis->mutable_gem() + ->mutable_lat_lon_heading_rpt_82() + ->set_longitude_seconds(longitude_seconds(bytes, length)); + chassis->mutable_gem() + ->mutable_lat_lon_heading_rpt_82() + ->set_longitude_minutes(longitude_minutes(bytes, length)); + chassis->mutable_gem() + ->mutable_lat_lon_heading_rpt_82() + ->set_longitude_degrees(longitude_degrees(bytes, length)); + chassis->mutable_gem() + ->mutable_lat_lon_heading_rpt_82() + ->set_latitude_seconds(latitude_seconds(bytes, length)); + chassis->mutable_gem() + ->mutable_lat_lon_heading_rpt_82() + ->set_latitude_minutes(latitude_minutes(bytes, length)); + chassis->mutable_gem() + ->mutable_lat_lon_heading_rpt_82() + ->set_latitude_degrees(latitude_degrees(bytes, length)); } // config detail: {'name': 'heading', 'offset': 0.0, 'precision': 0.01, 'len': diff --git a/modules/canbus_vehicle/gem/protocol/lat_lon_heading_rpt_82.h b/modules/canbus/vehicle/gem/protocol/lat_lon_heading_rpt_82.h similarity index 94% rename from modules/canbus_vehicle/gem/protocol/lat_lon_heading_rpt_82.h rename to modules/canbus/vehicle/gem/protocol/lat_lon_heading_rpt_82.h index 476a8db9f5b..e26f04232b6 100644 --- a/modules/canbus_vehicle/gem/protocol/lat_lon_heading_rpt_82.h +++ b/modules/canbus/vehicle/gem/protocol/lat_lon_heading_rpt_82.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Latlonheadingrpt82 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Latlonheadingrpt82(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'HEADING', 'offset': 0.0, 'precision': 0.01, 'len': diff --git a/modules/canbus_vehicle/gem/protocol/lat_lon_heading_rpt_82_test.cc b/modules/canbus/vehicle/gem/protocol/lat_lon_heading_rpt_82_test.cc similarity index 68% rename from modules/canbus_vehicle/gem/protocol/lat_lon_heading_rpt_82_test.cc rename to modules/canbus/vehicle/gem/protocol/lat_lon_heading_rpt_82_test.cc index ba4c88128f4..7c9b5c4b294 100644 --- a/modules/canbus_vehicle/gem/protocol/lat_lon_heading_rpt_82_test.cc +++ b/modules/canbus/vehicle/gem/protocol/lat_lon_heading_rpt_82_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/lat_lon_heading_rpt_82.h" +#include "modules/canbus/vehicle/gem/protocol/lat_lon_heading_rpt_82.h" #include "gtest/gtest.h" @@ -30,23 +30,23 @@ class Latlonheadingrpt82Test : public ::testing::Test { TEST_F(Latlonheadingrpt82Test, reset) { Latlonheadingrpt82 Latlonheading; int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; Latlonheading.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.lat_lon_heading_rpt_82().heading(), + EXPECT_DOUBLE_EQ(chassis_detail.gem().lat_lon_heading_rpt_82().heading(), 48.84); EXPECT_DOUBLE_EQ( - chassis_detail.lat_lon_heading_rpt_82().longitude_seconds(), 18); + chassis_detail.gem().lat_lon_heading_rpt_82().longitude_seconds(), 18); EXPECT_DOUBLE_EQ( - chassis_detail.lat_lon_heading_rpt_82().longitude_minutes(), 17); + chassis_detail.gem().lat_lon_heading_rpt_82().longitude_minutes(), 17); EXPECT_DOUBLE_EQ( - chassis_detail.lat_lon_heading_rpt_82().longitude_degrees(), 4); + chassis_detail.gem().lat_lon_heading_rpt_82().longitude_degrees(), 4); EXPECT_DOUBLE_EQ( - chassis_detail.lat_lon_heading_rpt_82().latitude_seconds(), 3); + chassis_detail.gem().lat_lon_heading_rpt_82().latitude_seconds(), 3); EXPECT_DOUBLE_EQ( - chassis_detail.lat_lon_heading_rpt_82().latitude_minutes(), 2); + chassis_detail.gem().lat_lon_heading_rpt_82().latitude_minutes(), 2); EXPECT_DOUBLE_EQ( - chassis_detail.lat_lon_heading_rpt_82().latitude_degrees(), 1); + chassis_detail.gem().lat_lon_heading_rpt_82().latitude_degrees(), 1); } } // namespace gem diff --git a/modules/canbus_vehicle/gem/protocol/parking_brake_status_rpt_80.cc b/modules/canbus/vehicle/gem/protocol/parking_brake_status_rpt_80.cc similarity index 87% rename from modules/canbus_vehicle/gem/protocol/parking_brake_status_rpt_80.cc rename to modules/canbus/vehicle/gem/protocol/parking_brake_status_rpt_80.cc index c0bd10997cf..641b31b9224 100644 --- a/modules/canbus_vehicle/gem/protocol/parking_brake_status_rpt_80.cc +++ b/modules/canbus/vehicle/gem/protocol/parking_brake_status_rpt_80.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/parking_brake_status_rpt_80.h" +#include "modules/canbus/vehicle/gem/protocol/parking_brake_status_rpt_80.h" #include "glog/logging.h" @@ -31,9 +31,10 @@ Parkingbrakestatusrpt80::Parkingbrakestatusrpt80() {} const int32_t Parkingbrakestatusrpt80::ID = 0x80; void Parkingbrakestatusrpt80::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_parking_brake_status_rpt_80()->set_parking_brake_enabled( - parking_brake_enabled(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_gem() + ->mutable_parking_brake_status_rpt_80() + ->set_parking_brake_enabled(parking_brake_enabled(bytes, length)); } // config detail: {'name': 'parking_brake_enabled', 'enum': {0: diff --git a/modules/canbus_vehicle/gem/protocol/parking_brake_status_rpt_80.h b/modules/canbus/vehicle/gem/protocol/parking_brake_status_rpt_80.h similarity index 89% rename from modules/canbus_vehicle/gem/protocol/parking_brake_status_rpt_80.h rename to modules/canbus/vehicle/gem/protocol/parking_brake_status_rpt_80.h index c750660725d..e0194f15180 100644 --- a/modules/canbus_vehicle/gem/protocol/parking_brake_status_rpt_80.h +++ b/modules/canbus/vehicle/gem/protocol/parking_brake_status_rpt_80.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Parkingbrakestatusrpt80 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Parkingbrakestatusrpt80(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'PARKING_BRAKE_ENABLED', 'enum': {0: diff --git a/modules/canbus_vehicle/gem/protocol/shift_cmd_65.cc b/modules/canbus/vehicle/gem/protocol/shift_cmd_65.cc similarity index 97% rename from modules/canbus_vehicle/gem/protocol/shift_cmd_65.cc rename to modules/canbus/vehicle/gem/protocol/shift_cmd_65.cc index b7c2dffba91..c92fa24640c 100644 --- a/modules/canbus_vehicle/gem/protocol/shift_cmd_65.cc +++ b/modules/canbus/vehicle/gem/protocol/shift_cmd_65.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/shift_cmd_65.h" +#include "modules/canbus/vehicle/gem/protocol/shift_cmd_65.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/gem/protocol/shift_cmd_65.h b/modules/canbus/vehicle/gem/protocol/shift_cmd_65.h similarity index 95% rename from modules/canbus_vehicle/gem/protocol/shift_cmd_65.h rename to modules/canbus/vehicle/gem/protocol/shift_cmd_65.h index 60fbcca34ea..efd60d677db 100644 --- a/modules/canbus_vehicle/gem/protocol/shift_cmd_65.h +++ b/modules/canbus/vehicle/gem/protocol/shift_cmd_65.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace gem { class Shiftcmd65 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/gem/protocol/shift_rpt_66.cc b/modules/canbus/vehicle/gem/protocol/shift_rpt_66.cc similarity index 90% rename from modules/canbus_vehicle/gem/protocol/shift_rpt_66.cc rename to modules/canbus/vehicle/gem/protocol/shift_rpt_66.cc index faf6bb8f01b..c7b128d4f48 100644 --- a/modules/canbus_vehicle/gem/protocol/shift_rpt_66.cc +++ b/modules/canbus/vehicle/gem/protocol/shift_rpt_66.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/shift_rpt_66.h" +#include "modules/canbus/vehicle/gem/protocol/shift_rpt_66.h" #include "glog/logging.h" @@ -31,12 +31,12 @@ Shiftrpt66::Shiftrpt66() {} const int32_t Shiftrpt66::ID = 0x66; void Shiftrpt66::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_shift_rpt_66()->set_manual_input( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_shift_rpt_66()->set_manual_input( manual_input(bytes, length)); - chassis->mutable_shift_rpt_66()->set_commanded_value( + chassis->mutable_gem()->mutable_shift_rpt_66()->set_commanded_value( commanded_value(bytes, length)); - chassis->mutable_shift_rpt_66()->set_output_value( + chassis->mutable_gem()->mutable_shift_rpt_66()->set_output_value( output_value(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/shift_rpt_66.h b/modules/canbus/vehicle/gem/protocol/shift_rpt_66.h similarity index 93% rename from modules/canbus_vehicle/gem/protocol/shift_rpt_66.h rename to modules/canbus/vehicle/gem/protocol/shift_rpt_66.h index 87dfc0864d0..3bcaf672dae 100644 --- a/modules/canbus_vehicle/gem/protocol/shift_rpt_66.h +++ b/modules/canbus/vehicle/gem/protocol/shift_rpt_66.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Shiftrpt66 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Shiftrpt66(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'MANUAL_INPUT', 'enum': {0: 'MANUAL_INPUT_PARK', 1: diff --git a/modules/canbus_vehicle/gem/protocol/steering_cmd_6d.cc b/modules/canbus/vehicle/gem/protocol/steering_cmd_6d.cc similarity index 98% rename from modules/canbus_vehicle/gem/protocol/steering_cmd_6d.cc rename to modules/canbus/vehicle/gem/protocol/steering_cmd_6d.cc index 8bb5fc55a5a..a6324f8d524 100644 --- a/modules/canbus_vehicle/gem/protocol/steering_cmd_6d.cc +++ b/modules/canbus/vehicle/gem/protocol/steering_cmd_6d.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/steering_cmd_6d.h" +#include "modules/canbus/vehicle/gem/protocol/steering_cmd_6d.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/gem/protocol/steering_cmd_6d.h b/modules/canbus/vehicle/gem/protocol/steering_cmd_6d.h similarity index 95% rename from modules/canbus_vehicle/gem/protocol/steering_cmd_6d.h rename to modules/canbus/vehicle/gem/protocol/steering_cmd_6d.h index b00ce3f4add..e3ccd3c1977 100644 --- a/modules/canbus_vehicle/gem/protocol/steering_cmd_6d.h +++ b/modules/canbus/vehicle/gem/protocol/steering_cmd_6d.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace gem { class Steeringcmd6d : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_1_73.cc b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_1_73.cc similarity index 90% rename from modules/canbus_vehicle/gem/protocol/steering_motor_rpt_1_73.cc rename to modules/canbus/vehicle/gem/protocol/steering_motor_rpt_1_73.cc index c4ab564c2d7..c1ccb12fa23 100644 --- a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_1_73.cc +++ b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_1_73.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/steering_motor_rpt_1_73.h" +#include "modules/canbus/vehicle/gem/protocol/steering_motor_rpt_1_73.h" #include "glog/logging.h" @@ -31,10 +31,10 @@ Steeringmotorrpt173::Steeringmotorrpt173() {} const int32_t Steeringmotorrpt173::ID = 0x73; void Steeringmotorrpt173::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_steering_motor_rpt_1_73()->set_motor_current( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_steering_motor_rpt_1_73()->set_motor_current( motor_current(bytes, length)); - chassis->mutable_steering_motor_rpt_1_73()->set_shaft_position( + chassis->mutable_gem()->mutable_steering_motor_rpt_1_73()->set_shaft_position( shaft_position(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_1_73.h b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_1_73.h similarity index 90% rename from modules/canbus_vehicle/gem/protocol/steering_motor_rpt_1_73.h rename to modules/canbus/vehicle/gem/protocol/steering_motor_rpt_1_73.h index 889aac2a4b2..6d5acda8037 100644 --- a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_1_73.h +++ b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_1_73.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Steeringmotorrpt173 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Steeringmotorrpt173(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'MOTOR_CURRENT', 'offset': 0.0, 'precision': 0.001, diff --git a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_1_73_test.cc b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_1_73_test.cc similarity index 85% rename from modules/canbus_vehicle/gem/protocol/steering_motor_rpt_1_73_test.cc rename to modules/canbus/vehicle/gem/protocol/steering_motor_rpt_1_73_test.cc index de89270b945..8970ee72dc4 100644 --- a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_1_73_test.cc +++ b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_1_73_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/steering_motor_rpt_1_73.h" +#include "modules/canbus/vehicle/gem/protocol/steering_motor_rpt_1_73.h" #include "gtest/gtest.h" @@ -30,14 +30,14 @@ class Steeringmotorrpt173Test : public ::testing::Test { TEST_F(Steeringmotorrpt173Test, reset) { Steeringmotorrpt173 steeringmotor1; int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; steeringmotor1.Parse(bytes, length, &chassis_detail); EXPECT_DOUBLE_EQ( - chassis_detail.steering_motor_rpt_1_73().motor_current(), + chassis_detail.gem().steering_motor_rpt_1_73().motor_current(), 16909.060000000001); EXPECT_DOUBLE_EQ( - chassis_detail.steering_motor_rpt_1_73().shaft_position(), + chassis_detail.gem().steering_motor_rpt_1_73().shaft_position(), 286397.20400000003); } diff --git a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_2_74.cc b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_2_74.cc similarity index 86% rename from modules/canbus_vehicle/gem/protocol/steering_motor_rpt_2_74.cc rename to modules/canbus/vehicle/gem/protocol/steering_motor_rpt_2_74.cc index 7040a2811a8..7bde211afb2 100644 --- a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_2_74.cc +++ b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_2_74.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/steering_motor_rpt_2_74.h" +#include "modules/canbus/vehicle/gem/protocol/steering_motor_rpt_2_74.h" #include "glog/logging.h" @@ -31,12 +31,14 @@ Steeringmotorrpt274::Steeringmotorrpt274() {} const int32_t Steeringmotorrpt274::ID = 0x74; void Steeringmotorrpt274::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_steering_motor_rpt_2_74()->set_encoder_temperature( - encoder_temperature(bytes, length)); - chassis->mutable_steering_motor_rpt_2_74()->set_motor_temperature( - motor_temperature(bytes, length)); - chassis->mutable_steering_motor_rpt_2_74()->set_angular_speed( + ChassisDetail* chassis) const { + chassis->mutable_gem() + ->mutable_steering_motor_rpt_2_74() + ->set_encoder_temperature(encoder_temperature(bytes, length)); + chassis->mutable_gem() + ->mutable_steering_motor_rpt_2_74() + ->set_motor_temperature(motor_temperature(bytes, length)); + chassis->mutable_gem()->mutable_steering_motor_rpt_2_74()->set_angular_speed( angular_speed(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_2_74.h b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_2_74.h similarity index 92% rename from modules/canbus_vehicle/gem/protocol/steering_motor_rpt_2_74.h rename to modules/canbus/vehicle/gem/protocol/steering_motor_rpt_2_74.h index 17bf3f1ecbd..234d95b0671 100644 --- a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_2_74.h +++ b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_2_74.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Steeringmotorrpt274 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Steeringmotorrpt274(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'ENCODER_TEMPERATURE', 'offset': -40.0, diff --git a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_2_74_test.cc b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_2_74_test.cc similarity index 80% rename from modules/canbus_vehicle/gem/protocol/steering_motor_rpt_2_74_test.cc rename to modules/canbus/vehicle/gem/protocol/steering_motor_rpt_2_74_test.cc index 5a7ff453137..adf85678c95 100644 --- a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_2_74_test.cc +++ b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_2_74_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/steering_motor_rpt_2_74.h" +#include "modules/canbus/vehicle/gem/protocol/steering_motor_rpt_2_74.h" #include "gtest/gtest.h" @@ -30,16 +30,16 @@ class Steeringmotorrpt274Test : public ::testing::Test { TEST_F(Steeringmotorrpt274Test, reset) { Steeringmotorrpt274 steeringmotor2; int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; steeringmotor2.Parse(bytes, length, &chassis_detail); EXPECT_DOUBLE_EQ( - chassis_detail.steering_motor_rpt_2_74().encoder_temperature(), + chassis_detail.gem().steering_motor_rpt_2_74().encoder_temperature(), 218); EXPECT_DOUBLE_EQ( - chassis_detail.steering_motor_rpt_2_74().motor_temperature(), 732); + chassis_detail.gem().steering_motor_rpt_2_74().motor_temperature(), 732); EXPECT_DOUBLE_EQ( - chassis_detail.steering_motor_rpt_2_74().angular_speed(), + chassis_detail.gem().steering_motor_rpt_2_74().angular_speed(), 286397.20400000003); } diff --git a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_3_75.cc b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_3_75.cc similarity index 90% rename from modules/canbus_vehicle/gem/protocol/steering_motor_rpt_3_75.cc rename to modules/canbus/vehicle/gem/protocol/steering_motor_rpt_3_75.cc index 663c5be1b39..307d0c7e545 100644 --- a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_3_75.cc +++ b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_3_75.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/steering_motor_rpt_3_75.h" +#include "modules/canbus/vehicle/gem/protocol/steering_motor_rpt_3_75.h" #include "glog/logging.h" @@ -31,10 +31,10 @@ Steeringmotorrpt375::Steeringmotorrpt375() {} const int32_t Steeringmotorrpt375::ID = 0x75; void Steeringmotorrpt375::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_steering_motor_rpt_3_75()->set_torque_output( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_steering_motor_rpt_3_75()->set_torque_output( torque_output(bytes, length)); - chassis->mutable_steering_motor_rpt_3_75()->set_torque_input( + chassis->mutable_gem()->mutable_steering_motor_rpt_3_75()->set_torque_input( torque_input(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_3_75.h b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_3_75.h similarity index 90% rename from modules/canbus_vehicle/gem/protocol/steering_motor_rpt_3_75.h rename to modules/canbus/vehicle/gem/protocol/steering_motor_rpt_3_75.h index 5454c821032..e1018899677 100644 --- a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_3_75.h +++ b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_3_75.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Steeringmotorrpt375 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Steeringmotorrpt375(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'TORQUE_OUTPUT', 'offset': 0.0, 'precision': 0.001, diff --git a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_3_75_test.cc b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_3_75_test.cc similarity index 85% rename from modules/canbus_vehicle/gem/protocol/steering_motor_rpt_3_75_test.cc rename to modules/canbus/vehicle/gem/protocol/steering_motor_rpt_3_75_test.cc index 5e113140616..ea50bab66a7 100644 --- a/modules/canbus_vehicle/gem/protocol/steering_motor_rpt_3_75_test.cc +++ b/modules/canbus/vehicle/gem/protocol/steering_motor_rpt_3_75_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/steering_motor_rpt_3_75.h" +#include "modules/canbus/vehicle/gem/protocol/steering_motor_rpt_3_75.h" #include "gtest/gtest.h" @@ -30,14 +30,14 @@ class Steeringmotorrpt375Test : public ::testing::Test { TEST_F(Steeringmotorrpt375Test, reset) { Steeringmotorrpt375 steeringmotor3; int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; steeringmotor3.Parse(bytes, length, &chassis_detail); EXPECT_DOUBLE_EQ( - chassis_detail.steering_motor_rpt_3_75().torque_output(), + chassis_detail.gem().steering_motor_rpt_3_75().torque_output(), 16909.060000000001); EXPECT_DOUBLE_EQ( - chassis_detail.steering_motor_rpt_3_75().torque_input(), + chassis_detail.gem().steering_motor_rpt_3_75().torque_input(), 286397.20400000003); } diff --git a/modules/canbus_vehicle/gem/protocol/steering_rpt_1_6e.cc b/modules/canbus/vehicle/gem/protocol/steering_rpt_1_6e.cc similarity index 89% rename from modules/canbus_vehicle/gem/protocol/steering_rpt_1_6e.cc rename to modules/canbus/vehicle/gem/protocol/steering_rpt_1_6e.cc index d5d2449df7e..f6b5a3af0ca 100644 --- a/modules/canbus_vehicle/gem/protocol/steering_rpt_1_6e.cc +++ b/modules/canbus/vehicle/gem/protocol/steering_rpt_1_6e.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/steering_rpt_1_6e.h" +#include "modules/canbus/vehicle/gem/protocol/steering_rpt_1_6e.h" #include "glog/logging.h" @@ -31,12 +31,12 @@ Steeringrpt16e::Steeringrpt16e() {} const int32_t Steeringrpt16e::ID = 0x6E; void Steeringrpt16e::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_steering_rpt_1_6e()->set_manual_input( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_steering_rpt_1_6e()->set_manual_input( manual_input(bytes, length)); - chassis->mutable_steering_rpt_1_6e()->set_commanded_value( + chassis->mutable_gem()->mutable_steering_rpt_1_6e()->set_commanded_value( commanded_value(bytes, length)); - chassis->mutable_steering_rpt_1_6e()->set_output_value( + chassis->mutable_gem()->mutable_steering_rpt_1_6e()->set_output_value( output_value(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/steering_rpt_1_6e.h b/modules/canbus/vehicle/gem/protocol/steering_rpt_1_6e.h similarity index 92% rename from modules/canbus_vehicle/gem/protocol/steering_rpt_1_6e.h rename to modules/canbus/vehicle/gem/protocol/steering_rpt_1_6e.h index b2fb5ad7583..15fa4823e52 100644 --- a/modules/canbus_vehicle/gem/protocol/steering_rpt_1_6e.h +++ b/modules/canbus/vehicle/gem/protocol/steering_rpt_1_6e.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Steeringrpt16e : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Steeringrpt16e(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'MANUAL_INPUT', 'offset': 0.0, 'precision': 0.001, diff --git a/modules/canbus_vehicle/gem/protocol/steering_rpt_1_6e_test.cc b/modules/canbus/vehicle/gem/protocol/steering_rpt_1_6e_test.cc similarity index 80% rename from modules/canbus_vehicle/gem/protocol/steering_rpt_1_6e_test.cc rename to modules/canbus/vehicle/gem/protocol/steering_rpt_1_6e_test.cc index 043931ae85f..f1dd825d1f1 100644 --- a/modules/canbus_vehicle/gem/protocol/steering_rpt_1_6e_test.cc +++ b/modules/canbus/vehicle/gem/protocol/steering_rpt_1_6e_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/steering_rpt_1_6e.h" +#include "modules/canbus/vehicle/gem/protocol/steering_rpt_1_6e.h" #include "gtest/gtest.h" @@ -30,15 +30,15 @@ class Steeringrpt16eTest : public ::testing::Test { TEST_F(Steeringrpt16eTest, reset) { Steeringrpt16e steeringrpt16; int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; steeringrpt16.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.steering_rpt_1_6e().manual_input(), + EXPECT_DOUBLE_EQ(chassis_detail.gem().steering_rpt_1_6e().manual_input(), 0.258); - EXPECT_DOUBLE_EQ(chassis_detail.steering_rpt_1_6e().commanded_value(), + EXPECT_DOUBLE_EQ(chassis_detail.gem().steering_rpt_1_6e().commanded_value(), 0.772); - EXPECT_DOUBLE_EQ(chassis_detail.steering_rpt_1_6e().output_value(), + EXPECT_DOUBLE_EQ(chassis_detail.gem().steering_rpt_1_6e().output_value(), 4.37); } diff --git a/modules/canbus_vehicle/gem/protocol/turn_cmd_63.cc b/modules/canbus/vehicle/gem/protocol/turn_cmd_63.cc similarity index 97% rename from modules/canbus_vehicle/gem/protocol/turn_cmd_63.cc rename to modules/canbus/vehicle/gem/protocol/turn_cmd_63.cc index 8b0c92ae5bf..6c177565282 100644 --- a/modules/canbus_vehicle/gem/protocol/turn_cmd_63.cc +++ b/modules/canbus/vehicle/gem/protocol/turn_cmd_63.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/turn_cmd_63.h" +#include "modules/canbus/vehicle/gem/protocol/turn_cmd_63.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/gem/protocol/turn_cmd_63.h b/modules/canbus/vehicle/gem/protocol/turn_cmd_63.h similarity index 94% rename from modules/canbus_vehicle/gem/protocol/turn_cmd_63.h rename to modules/canbus/vehicle/gem/protocol/turn_cmd_63.h index a2b175b459c..71853d162d7 100644 --- a/modules/canbus_vehicle/gem/protocol/turn_cmd_63.h +++ b/modules/canbus/vehicle/gem/protocol/turn_cmd_63.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace gem { class Turncmd63 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/gem/protocol/turn_rpt_64.cc b/modules/canbus/vehicle/gem/protocol/turn_rpt_64.cc similarity index 91% rename from modules/canbus_vehicle/gem/protocol/turn_rpt_64.cc rename to modules/canbus/vehicle/gem/protocol/turn_rpt_64.cc index 3598770f185..052d30d706d 100644 --- a/modules/canbus_vehicle/gem/protocol/turn_rpt_64.cc +++ b/modules/canbus/vehicle/gem/protocol/turn_rpt_64.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/turn_rpt_64.h" +#include "modules/canbus/vehicle/gem/protocol/turn_rpt_64.h" #include "glog/logging.h" @@ -31,12 +31,12 @@ Turnrpt64::Turnrpt64() {} const int32_t Turnrpt64::ID = 0x64; void Turnrpt64::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_turn_rpt_64()->set_manual_input( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_turn_rpt_64()->set_manual_input( manual_input(bytes, length)); - chassis->mutable_turn_rpt_64()->set_commanded_value( + chassis->mutable_gem()->mutable_turn_rpt_64()->set_commanded_value( commanded_value(bytes, length)); - chassis->mutable_turn_rpt_64()->set_output_value( + chassis->mutable_gem()->mutable_turn_rpt_64()->set_output_value( output_value(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/turn_rpt_64.h b/modules/canbus/vehicle/gem/protocol/turn_rpt_64.h similarity index 93% rename from modules/canbus_vehicle/gem/protocol/turn_rpt_64.h rename to modules/canbus/vehicle/gem/protocol/turn_rpt_64.h index 7005d6e37c0..7ed036bb957 100644 --- a/modules/canbus_vehicle/gem/protocol/turn_rpt_64.h +++ b/modules/canbus/vehicle/gem/protocol/turn_rpt_64.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Turnrpt64 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Turnrpt64(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'MANUAL_INPUT', 'enum': {0: 'MANUAL_INPUT_RIGHT', diff --git a/modules/canbus_vehicle/gem/protocol/vehicle_speed_rpt_6f.cc b/modules/canbus/vehicle/gem/protocol/vehicle_speed_rpt_6f.cc similarity index 88% rename from modules/canbus_vehicle/gem/protocol/vehicle_speed_rpt_6f.cc rename to modules/canbus/vehicle/gem/protocol/vehicle_speed_rpt_6f.cc index a9fdc74ce6d..62faae3156c 100644 --- a/modules/canbus_vehicle/gem/protocol/vehicle_speed_rpt_6f.cc +++ b/modules/canbus/vehicle/gem/protocol/vehicle_speed_rpt_6f.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/vehicle_speed_rpt_6f.h" +#include "modules/canbus/vehicle/gem/protocol/vehicle_speed_rpt_6f.h" #include "glog/logging.h" @@ -31,11 +31,12 @@ Vehiclespeedrpt6f::Vehiclespeedrpt6f() {} const int32_t Vehiclespeedrpt6f::ID = 0x6F; void Vehiclespeedrpt6f::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_vehicle_speed_rpt_6f()->set_vehicle_speed( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_vehicle_speed_rpt_6f()->set_vehicle_speed( vehicle_speed(bytes, length)); - chassis->mutable_vehicle_speed_rpt_6f()->set_vehicle_speed_valid( - vehicle_speed_valid(bytes, length)); + chassis->mutable_gem() + ->mutable_vehicle_speed_rpt_6f() + ->set_vehicle_speed_valid(vehicle_speed_valid(bytes, length)); } // config detail: {'name': 'vehicle_speed', 'offset': 0.0, 'precision': 0.01, diff --git a/modules/canbus_vehicle/gem/protocol/vehicle_speed_rpt_6f.h b/modules/canbus/vehicle/gem/protocol/vehicle_speed_rpt_6f.h similarity index 91% rename from modules/canbus_vehicle/gem/protocol/vehicle_speed_rpt_6f.h rename to modules/canbus/vehicle/gem/protocol/vehicle_speed_rpt_6f.h index d09b06bbca0..3ee1361a8f3 100644 --- a/modules/canbus_vehicle/gem/protocol/vehicle_speed_rpt_6f.h +++ b/modules/canbus/vehicle/gem/protocol/vehicle_speed_rpt_6f.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Vehiclespeedrpt6f : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vehiclespeedrpt6f(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VEHICLE_SPEED', 'offset': 0.0, 'precision': 0.01, diff --git a/modules/canbus_vehicle/gem/protocol/wheel_speed_rpt_7a.cc b/modules/canbus/vehicle/gem/protocol/wheel_speed_rpt_7a.cc similarity index 85% rename from modules/canbus_vehicle/gem/protocol/wheel_speed_rpt_7a.cc rename to modules/canbus/vehicle/gem/protocol/wheel_speed_rpt_7a.cc index 76de91c2700..2247ed464c7 100644 --- a/modules/canbus_vehicle/gem/protocol/wheel_speed_rpt_7a.cc +++ b/modules/canbus/vehicle/gem/protocol/wheel_speed_rpt_7a.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/wheel_speed_rpt_7a.h" +#include "modules/canbus/vehicle/gem/protocol/wheel_speed_rpt_7a.h" #include "glog/logging.h" @@ -31,15 +31,18 @@ Wheelspeedrpt7a::Wheelspeedrpt7a() {} const int32_t Wheelspeedrpt7a::ID = 0x7A; void Wheelspeedrpt7a::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_wheel_speed_rpt_7a()->set_wheel_spd_rear_right( - wheel_spd_rear_right(bytes, length)); - chassis->mutable_wheel_speed_rpt_7a()->set_wheel_spd_rear_left( + ChassisDetail* chassis) const { + chassis->mutable_gem() + ->mutable_wheel_speed_rpt_7a() + ->set_wheel_spd_rear_right(wheel_spd_rear_right(bytes, length)); + chassis->mutable_gem()->mutable_wheel_speed_rpt_7a()->set_wheel_spd_rear_left( wheel_spd_rear_left(bytes, length)); - chassis->mutable_wheel_speed_rpt_7a()->set_wheel_spd_front_right( - wheel_spd_front_right(bytes, length)); - chassis->mutable_wheel_speed_rpt_7a()->set_wheel_spd_front_left( - wheel_spd_front_left(bytes, length)); + chassis->mutable_gem() + ->mutable_wheel_speed_rpt_7a() + ->set_wheel_spd_front_right(wheel_spd_front_right(bytes, length)); + chassis->mutable_gem() + ->mutable_wheel_speed_rpt_7a() + ->set_wheel_spd_front_left(wheel_spd_front_left(bytes, length)); } // config detail: {'name': 'wheel_spd_rear_right', 'offset': 0.0, diff --git a/modules/canbus_vehicle/gem/protocol/wheel_speed_rpt_7a.h b/modules/canbus/vehicle/gem/protocol/wheel_speed_rpt_7a.h similarity index 93% rename from modules/canbus_vehicle/gem/protocol/wheel_speed_rpt_7a.h rename to modules/canbus/vehicle/gem/protocol/wheel_speed_rpt_7a.h index 41d13cce4f3..4ab57f6585d 100644 --- a/modules/canbus_vehicle/gem/protocol/wheel_speed_rpt_7a.h +++ b/modules/canbus/vehicle/gem/protocol/wheel_speed_rpt_7a.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Wheelspeedrpt7a : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Wheelspeedrpt7a(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'WHEEL_SPD_REAR_RIGHT', 'offset': 0.0, diff --git a/modules/canbus_vehicle/gem/protocol/wheel_speed_rpt_7a_test.cc b/modules/canbus/vehicle/gem/protocol/wheel_speed_rpt_7a_test.cc similarity index 76% rename from modules/canbus_vehicle/gem/protocol/wheel_speed_rpt_7a_test.cc rename to modules/canbus/vehicle/gem/protocol/wheel_speed_rpt_7a_test.cc index 27f20d52cc6..b2e9fbfca4c 100644 --- a/modules/canbus_vehicle/gem/protocol/wheel_speed_rpt_7a_test.cc +++ b/modules/canbus/vehicle/gem/protocol/wheel_speed_rpt_7a_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/wheel_speed_rpt_7a.h" +#include "modules/canbus/vehicle/gem/protocol/wheel_speed_rpt_7a.h" #include "gtest/gtest.h" @@ -30,17 +30,17 @@ class Wheelspeedrpt7aTest : public ::testing::Test { TEST_F(Wheelspeedrpt7aTest, reset) { Wheelspeedrpt7a wheelspeed; int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; wheelspeed.Parse(bytes, length, &chassis_detail); EXPECT_DOUBLE_EQ( - chassis_detail.wheel_speed_rpt_7a().wheel_spd_rear_right(), 4884); + chassis_detail.gem().wheel_speed_rpt_7a().wheel_spd_rear_right(), 4884); EXPECT_DOUBLE_EQ( - chassis_detail.wheel_speed_rpt_7a().wheel_spd_rear_left(), 4370); + chassis_detail.gem().wheel_speed_rpt_7a().wheel_spd_rear_left(), 4370); EXPECT_DOUBLE_EQ( - chassis_detail.wheel_speed_rpt_7a().wheel_spd_front_right(), 772); + chassis_detail.gem().wheel_speed_rpt_7a().wheel_spd_front_right(), 772); EXPECT_DOUBLE_EQ( - chassis_detail.wheel_speed_rpt_7a().wheel_spd_front_left(), 258); + chassis_detail.gem().wheel_speed_rpt_7a().wheel_spd_front_left(), 258); } } // namespace gem diff --git a/modules/canbus_vehicle/gem/protocol/wiper_cmd_90.cc b/modules/canbus/vehicle/gem/protocol/wiper_cmd_90.cc similarity index 97% rename from modules/canbus_vehicle/gem/protocol/wiper_cmd_90.cc rename to modules/canbus/vehicle/gem/protocol/wiper_cmd_90.cc index 81cd0d1dd98..6f0bbb5dad8 100644 --- a/modules/canbus_vehicle/gem/protocol/wiper_cmd_90.cc +++ b/modules/canbus/vehicle/gem/protocol/wiper_cmd_90.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/wiper_cmd_90.h" +#include "modules/canbus/vehicle/gem/protocol/wiper_cmd_90.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/gem/protocol/wiper_cmd_90.h b/modules/canbus/vehicle/gem/protocol/wiper_cmd_90.h similarity index 95% rename from modules/canbus_vehicle/gem/protocol/wiper_cmd_90.h rename to modules/canbus/vehicle/gem/protocol/wiper_cmd_90.h index 9466c7bc67a..43152aa8a9a 100644 --- a/modules/canbus_vehicle/gem/protocol/wiper_cmd_90.h +++ b/modules/canbus/vehicle/gem/protocol/wiper_cmd_90.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace gem { class Wipercmd90 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/gem/protocol/wiper_rpt_91.cc b/modules/canbus/vehicle/gem/protocol/wiper_rpt_91.cc similarity index 91% rename from modules/canbus_vehicle/gem/protocol/wiper_rpt_91.cc rename to modules/canbus/vehicle/gem/protocol/wiper_rpt_91.cc index cd7f699829e..5d99b5cc6cc 100644 --- a/modules/canbus_vehicle/gem/protocol/wiper_rpt_91.cc +++ b/modules/canbus/vehicle/gem/protocol/wiper_rpt_91.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/wiper_rpt_91.h" +#include "modules/canbus/vehicle/gem/protocol/wiper_rpt_91.h" #include "glog/logging.h" @@ -31,12 +31,12 @@ Wiperrpt91::Wiperrpt91() {} const int32_t Wiperrpt91::ID = 0x91; void Wiperrpt91::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_wiper_rpt_91()->set_output_value( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_wiper_rpt_91()->set_output_value( output_value(bytes, length)); - chassis->mutable_wiper_rpt_91()->set_commanded_value( + chassis->mutable_gem()->mutable_wiper_rpt_91()->set_commanded_value( commanded_value(bytes, length)); - chassis->mutable_wiper_rpt_91()->set_manual_input( + chassis->mutable_gem()->mutable_wiper_rpt_91()->set_manual_input( manual_input(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/wiper_rpt_91.h b/modules/canbus/vehicle/gem/protocol/wiper_rpt_91.h similarity index 94% rename from modules/canbus_vehicle/gem/protocol/wiper_rpt_91.h rename to modules/canbus/vehicle/gem/protocol/wiper_rpt_91.h index a3238c9b1f5..3a8dd27a9c5 100644 --- a/modules/canbus_vehicle/gem/protocol/wiper_rpt_91.h +++ b/modules/canbus/vehicle/gem/protocol/wiper_rpt_91.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Wiperrpt91 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Wiperrpt91(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'OUTPUT_VALUE', 'enum': {0: diff --git a/modules/canbus_vehicle/gem/protocol/wiper_rpt_91_test.cc b/modules/canbus/vehicle/gem/protocol/wiper_rpt_91_test.cc similarity index 78% rename from modules/canbus_vehicle/gem/protocol/wiper_rpt_91_test.cc rename to modules/canbus/vehicle/gem/protocol/wiper_rpt_91_test.cc index 31a22e5ad02..34ee5f691b1 100644 --- a/modules/canbus_vehicle/gem/protocol/wiper_rpt_91_test.cc +++ b/modules/canbus/vehicle/gem/protocol/wiper_rpt_91_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/wiper_rpt_91.h" +#include "modules/canbus/vehicle/gem/protocol/wiper_rpt_91.h" #include "gtest/gtest.h" @@ -30,12 +30,12 @@ class Wiperrpt91Test : public ::testing::Test { TEST_F(Wiperrpt91Test, reset) { Wiperrpt91 wiper; int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[3] = {0x01, 0x02, 0x03}; wiper.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.wiper_rpt_91().manual_input(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.wiper_rpt_91().commanded_value(), 2); - EXPECT_DOUBLE_EQ(chassis_detail.wiper_rpt_91().output_value(), 3); + EXPECT_DOUBLE_EQ(chassis_detail.gem().wiper_rpt_91().manual_input(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.gem().wiper_rpt_91().commanded_value(), 2); + EXPECT_DOUBLE_EQ(chassis_detail.gem().wiper_rpt_91().output_value(), 3); } } // namespace gem diff --git a/modules/canbus_vehicle/gem/protocol/yaw_rate_rpt_81.cc b/modules/canbus/vehicle/gem/protocol/yaw_rate_rpt_81.cc similarity index 90% rename from modules/canbus_vehicle/gem/protocol/yaw_rate_rpt_81.cc rename to modules/canbus/vehicle/gem/protocol/yaw_rate_rpt_81.cc index ae681c256b4..840d46d2830 100644 --- a/modules/canbus_vehicle/gem/protocol/yaw_rate_rpt_81.cc +++ b/modules/canbus/vehicle/gem/protocol/yaw_rate_rpt_81.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/yaw_rate_rpt_81.h" +#include "modules/canbus/vehicle/gem/protocol/yaw_rate_rpt_81.h" #include "glog/logging.h" @@ -31,8 +31,8 @@ Yawraterpt81::Yawraterpt81() {} const int32_t Yawraterpt81::ID = 0x81; void Yawraterpt81::Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const { - chassis->mutable_yaw_rate_rpt_81()->set_yaw_rate( + ChassisDetail* chassis) const { + chassis->mutable_gem()->mutable_yaw_rate_rpt_81()->set_yaw_rate( yaw_rate(bytes, length)); } diff --git a/modules/canbus_vehicle/gem/protocol/yaw_rate_rpt_81.h b/modules/canbus/vehicle/gem/protocol/yaw_rate_rpt_81.h similarity index 89% rename from modules/canbus_vehicle/gem/protocol/yaw_rate_rpt_81.h rename to modules/canbus/vehicle/gem/protocol/yaw_rate_rpt_81.h index 6efaa637988..9a0c1d4f49c 100644 --- a/modules/canbus_vehicle/gem/protocol/yaw_rate_rpt_81.h +++ b/modules/canbus/vehicle/gem/protocol/yaw_rate_rpt_81.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace gem { class Yawraterpt81 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Gem> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Yawraterpt81(); void Parse(const std::uint8_t* bytes, int32_t length, - Gem* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'YAW_RATE', 'offset': 0.0, 'precision': 0.01, diff --git a/modules/canbus_vehicle/gem/protocol/yaw_rate_rpt_81_test.cc b/modules/canbus/vehicle/gem/protocol/yaw_rate_rpt_81_test.cc similarity index 87% rename from modules/canbus_vehicle/gem/protocol/yaw_rate_rpt_81_test.cc rename to modules/canbus/vehicle/gem/protocol/yaw_rate_rpt_81_test.cc index f0902c67ac5..84b80f475ea 100644 --- a/modules/canbus_vehicle/gem/protocol/yaw_rate_rpt_81_test.cc +++ b/modules/canbus/vehicle/gem/protocol/yaw_rate_rpt_81_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/gem/protocol/yaw_rate_rpt_81.h" +#include "modules/canbus/vehicle/gem/protocol/yaw_rate_rpt_81.h" #include "gtest/gtest.h" @@ -30,11 +30,11 @@ class YawRatePrt81Test : public ::testing::Test { TEST_F(YawRatePrt81Test, reset) { Yawraterpt81 yaw_rate; int32_t length = 8; - Gem chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; yaw_rate.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.yaw_rate_rpt_81().yaw_rate(), 2.58); + EXPECT_DOUBLE_EQ(chassis_detail.gem().yaw_rate_rpt_81().yaw_rate(), 2.58); } } // namespace gem diff --git a/modules/canbus/vehicle/lexus/BUILD b/modules/canbus/vehicle/lexus/BUILD new file mode 100644 index 00000000000..6d0b9d6642d --- /dev/null +++ b/modules/canbus/vehicle/lexus/BUILD @@ -0,0 +1,62 @@ +load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") +load("//tools:cpplint.bzl", "cpplint") + +package(default_visibility = ["//visibility:public"]) + +CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] + +cc_library( + name = "lexus_vehicle_factory", + srcs = ["lexus_vehicle_factory.cc"], + hdrs = ["lexus_vehicle_factory.h"], + copts = CANBUS_COPTS, + deps = [ + ":lexus_controller", + ":lexus_message_manager", + "//modules/canbus/proto:canbus_conf_cc_proto", + "//modules/canbus/proto:vehicle_parameter_cc_proto", + "//modules/canbus/vehicle:abstract_vehicle_factory", + ], +) + +cc_library( + name = "lexus_message_manager", + srcs = ["lexus_message_manager.cc"], + hdrs = ["lexus_message_manager.h"], + copts = CANBUS_COPTS, + deps = [ + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle/lexus/protocol:canbus_lexus_protocol", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_library( + name = "lexus_controller", + srcs = ["lexus_controller.cc"], + hdrs = ["lexus_controller.h"], + copts = CANBUS_COPTS, + deps = [ + ":lexus_message_manager", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle:vehicle_controller_base", + "//modules/canbus/vehicle/lexus/protocol:canbus_lexus_protocol", + "//modules/drivers/canbus/can_comm:can_sender", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_test( + name = "lexus_controller_test", + size = "small", + srcs = ["lexus_controller_test.cc"], + data = ["//modules/canbus:test_data"], + deps = [ + "//modules/canbus/vehicle/lexus:lexus_controller", + "@com_google_googletest//:gtest_main", + ], +) + +cpplint() diff --git a/modules/canbus_vehicle/lexus/lexus_controller.cc b/modules/canbus/vehicle/lexus/lexus_controller.cc similarity index 87% rename from modules/canbus_vehicle/lexus/lexus_controller.cc rename to modules/canbus/vehicle/lexus/lexus_controller.cc index 2a001e59f5f..08582d5356c 100644 --- a/modules/canbus_vehicle/lexus/lexus_controller.cc +++ b/modules/canbus/vehicle/lexus/lexus_controller.cc @@ -14,14 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/lexus_controller.h" - -#include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" +#include "modules/canbus/vehicle/lexus/lexus_controller.h" #include "cyber/common/log.h" #include "cyber/time/time.h" -#include "modules/canbus_vehicle/lexus/lexus_message_manager.h" +#include "modules/canbus/vehicle/lexus/lexus_message_manager.h" #include "modules/canbus/vehicle/vehicle_controller.h" +#include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "modules/drivers/canbus/can_comm/can_sender.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" @@ -43,8 +42,8 @@ const int32_t CHECK_RESPONSE_SPEED_UNIT_FLAG = 2; ErrorCode LexusController::Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Lexus>* const can_sender, - MessageManager<::apollo::canbus::Lexus>* const message_manager) { + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) { if (is_initialized_) { AINFO << "LexusController has already been initiated."; return ErrorCode::CANBUS_ERROR; @@ -147,7 +146,7 @@ void LexusController::Stop() { Chassis LexusController::chassis() { chassis_.Clear(); - Lexus chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); // 21, 22, previously 1, 2 @@ -162,20 +161,20 @@ Chassis LexusController::chassis() { chassis_.set_engine_started(true); // 5 - if (chassis_detail.has_vehicle_speed_rpt_400() && - chassis_detail.vehicle_speed_rpt_400().has_vehicle_speed()) { + if (chassis_detail.lexus().has_vehicle_speed_rpt_400() && + chassis_detail.lexus().vehicle_speed_rpt_400().has_vehicle_speed()) { chassis_.set_speed_mps(static_cast( - chassis_detail.vehicle_speed_rpt_400().vehicle_speed())); + chassis_detail.lexus().vehicle_speed_rpt_400().vehicle_speed())); } else { chassis_.set_speed_mps(0); } - if (chassis_detail.has_wheel_speed_rpt_407()) { + if (chassis_detail.lexus().has_wheel_speed_rpt_407()) { // TODO(QiL) : No wheel speed valid bit in lexus, so default valid chassis_.mutable_wheel_speed()->set_is_wheel_spd_rr_valid(true); // chassis_.mutable_wheel_speed()->set_wheel_direction_rr(true); chassis_.mutable_wheel_speed()->set_wheel_spd_rr( - chassis_detail.wheel_speed_rpt_407().wheel_spd_rear_right()); + chassis_detail.lexus().wheel_speed_rpt_407().wheel_spd_rear_right()); chassis_.mutable_wheel_speed()->set_is_wheel_spd_rl_valid(true); /* @@ -183,7 +182,7 @@ Chassis LexusController::chassis() { chassis_detail.vehicle_spd().wheel_direction_rl()); */ chassis_.mutable_wheel_speed()->set_wheel_spd_rl( - chassis_detail.wheel_speed_rpt_407().wheel_spd_rear_left()); + chassis_detail.lexus().wheel_speed_rpt_407().wheel_spd_rear_left()); chassis_.mutable_wheel_speed()->set_is_wheel_spd_fr_valid(true); /* @@ -191,7 +190,7 @@ Chassis LexusController::chassis() { chassis_detail.vehicle_spd().wheel_direction_fr()); */ chassis_.mutable_wheel_speed()->set_wheel_spd_fr( - chassis_detail.wheel_speed_rpt_407().wheel_spd_front_right()); + chassis_detail.lexus().wheel_speed_rpt_407().wheel_spd_front_right()); chassis_.mutable_wheel_speed()->set_is_wheel_spd_fl_valid(true); /* @@ -199,50 +198,50 @@ Chassis LexusController::chassis() { chassis_detail.vehicle_spd().wheel_direction_fl()); */ chassis_.mutable_wheel_speed()->set_wheel_spd_fl( - chassis_detail.wheel_speed_rpt_407().wheel_spd_front_left()); + chassis_detail.lexus().wheel_speed_rpt_407().wheel_spd_front_left()); } // 7 chassis_.set_fuel_range_m(0); // 8 - if (chassis_detail.has_accel_rpt_200() && - chassis_detail.accel_rpt_200().has_output_value()) { + if (chassis_detail.lexus().has_accel_rpt_200() && + chassis_detail.lexus().accel_rpt_200().has_output_value()) { // TODO(snehagn): Temp fix until AS to fix the scaling chassis_.set_throttle_percentage(static_cast( - chassis_detail.accel_rpt_200().output_value() * 100)); + chassis_detail.lexus().accel_rpt_200().output_value() * 100)); } else { chassis_.set_throttle_percentage(0); } // 9 - if (chassis_detail.has_brake_rpt_204() && - chassis_detail.brake_rpt_204().has_output_value()) { + if (chassis_detail.lexus().has_brake_rpt_204() && + chassis_detail.lexus().brake_rpt_204().has_output_value()) { // TODO(snehagn): Temp fix until AS to fix the scaling chassis_.set_brake_percentage(static_cast( - chassis_detail.brake_rpt_204().output_value() * 100)); + chassis_detail.lexus().brake_rpt_204().output_value() * 100)); } else { chassis_.set_brake_percentage(0); } // 23, previously 10 - if (chassis_detail.has_shift_rpt_228() && - chassis_detail.shift_rpt_228().has_output_value()) { + if (chassis_detail.lexus().has_shift_rpt_228() && + chassis_detail.lexus().shift_rpt_228().has_output_value()) { AINFO << "Start reading shift values"; Chassis::GearPosition gear_pos = Chassis::GEAR_INVALID; - if (chassis_detail.shift_rpt_228().output_value() == + if (chassis_detail.lexus().shift_rpt_228().output_value() == Shift_rpt_228::OUTPUT_VALUE_PARK) { gear_pos = Chassis::GEAR_PARKING; } - if (chassis_detail.shift_rpt_228().output_value() == + if (chassis_detail.lexus().shift_rpt_228().output_value() == Shift_rpt_228::OUTPUT_VALUE_NEUTRAL) { gear_pos = Chassis::GEAR_NEUTRAL; } - if (chassis_detail.shift_rpt_228().output_value() == + if (chassis_detail.lexus().shift_rpt_228().output_value() == Shift_rpt_228::OUTPUT_VALUE_REVERSE) { gear_pos = Chassis::GEAR_REVERSE; } - if (chassis_detail.shift_rpt_228().output_value() == + if (chassis_detail.lexus().shift_rpt_228().output_value() == Shift_rpt_228::OUTPUT_VALUE_FORWARD_HIGH) { gear_pos = Chassis::GEAR_DRIVE; } @@ -254,25 +253,25 @@ Chassis LexusController::chassis() { // 11 // TODO(QiL) : verify the unit here. - if (chassis_detail.has_steering_rpt_22c() && - chassis_detail.steering_rpt_22c().has_output_value()) { - chassis_.set_steering_percentage( - static_cast(chassis_detail.steering_rpt_22c().output_value() * - 100.0 / vehicle_params_.max_steer_angle())); + if (chassis_detail.lexus().has_steering_rpt_22c() && + chassis_detail.lexus().steering_rpt_22c().has_output_value()) { + chassis_.set_steering_percentage(static_cast( + chassis_detail.lexus().steering_rpt_22c().output_value() * 100.0 / + vehicle_params_.max_steer_angle())); } else { chassis_.set_steering_percentage(0); } // 16, 17 - if (chassis_detail.has_turn_rpt_230() && - chassis_detail.turn_rpt_230().has_output_value() && - chassis_detail.turn_rpt_230().output_value() != + if (chassis_detail.lexus().has_turn_rpt_230() && + chassis_detail.lexus().turn_rpt_230().has_output_value() && + chassis_detail.lexus().turn_rpt_230().output_value() != Turn_rpt_230::OUTPUT_VALUE_NONE) { - if (chassis_detail.turn_rpt_230().output_value() == + if (chassis_detail.lexus().turn_rpt_230().output_value() == Turn_rpt_230::OUTPUT_VALUE_LEFT) { chassis_.mutable_signal()->set_turn_signal( common::VehicleSignal::TURN_LEFT); - } else if (chassis_detail.turn_rpt_230().output_value() == + } else if (chassis_detail.lexus().turn_rpt_230().output_value() == Turn_rpt_230::OUTPUT_VALUE_RIGHT) { chassis_.mutable_signal()->set_turn_signal( common::VehicleSignal::TURN_RIGHT); @@ -305,8 +304,6 @@ Chassis LexusController::chassis() { return chassis_; } -bool LexusController::VerifyID() { return true; } - void LexusController::Emergency() { set_driving_mode(Chassis::EMERGENCY_MODE); ResetProtocol(); @@ -514,7 +511,7 @@ void LexusController::Steer(double angle, double angle_spd) { const double real_angle = vehicle_params_.max_steer_angle() * angle / 100.0; const double real_angle_spd = - ProtocolData<::apollo::canbus::Lexus>::BoundedValue( + ProtocolData<::apollo::canbus::ChassisDetail>::BoundedValue( vehicle_params_.min_steer_angle_rate(), vehicle_params_.max_steer_angle_rate(), vehicle_params_.max_steer_angle_rate() * angle_spd / 100.0); @@ -640,7 +637,7 @@ bool LexusController::CheckResponse(const int32_t flags, bool need_wait) { // TODO(Yu) : check whether the current retry_num match the assumed time // consumption int32_t retry_num = 20; - Lexus chassis_detail; + ChassisDetail chassis_detail; bool is_accel_enabled = false; bool is_brake_enabled = false; bool is_steering_enabled = false; @@ -652,19 +649,20 @@ bool LexusController::CheckResponse(const int32_t flags, bool need_wait) { } bool check_ok = true; if (flags & CHECK_RESPONSE_STEER_UNIT_FLAG) { - is_steering_enabled = chassis_detail.has_steering_rpt_22c() && - chassis_detail.steering_rpt_22c().has_enabled() && - chassis_detail.steering_rpt_22c().enabled(); + is_steering_enabled = + chassis_detail.lexus().has_steering_rpt_22c() && + chassis_detail.lexus().steering_rpt_22c().has_enabled() && + chassis_detail.lexus().steering_rpt_22c().enabled(); check_ok = check_ok && is_steering_enabled; } if (flags & CHECK_RESPONSE_SPEED_UNIT_FLAG) { - is_brake_enabled = chassis_detail.has_brake_rpt_204() && - chassis_detail.brake_rpt_204().has_enabled() && - chassis_detail.brake_rpt_204().enabled(); - is_accel_enabled = chassis_detail.has_accel_rpt_200() && - chassis_detail.accel_rpt_200().has_enabled() && - chassis_detail.accel_rpt_200().enabled(); + is_brake_enabled = chassis_detail.lexus().has_brake_rpt_204() && + chassis_detail.lexus().brake_rpt_204().has_enabled() && + chassis_detail.lexus().brake_rpt_204().enabled(); + is_accel_enabled = chassis_detail.lexus().has_accel_rpt_200() && + chassis_detail.lexus().accel_rpt_200().has_enabled() && + chassis_detail.lexus().accel_rpt_200().enabled(); check_ok = check_ok && is_brake_enabled && is_accel_enabled; } if (check_ok) { diff --git a/modules/canbus_vehicle/lexus/lexus_controller.h b/modules/canbus/vehicle/lexus/lexus_controller.h similarity index 81% rename from modules/canbus_vehicle/lexus/lexus_controller.h rename to modules/canbus/vehicle/lexus/lexus_controller.h index 63e4dfa68d6..90c4cb92628 100644 --- a/modules/canbus_vehicle/lexus/lexus_controller.h +++ b/modules/canbus/vehicle/lexus/lexus_controller.h @@ -21,40 +21,41 @@ #include "gtest/gtest_prod.h" +#include "modules/canbus/vehicle/vehicle_controller.h" + #include "modules/canbus/proto/canbus_conf.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" #include "modules/common_msgs/basic_msgs/error_code.pb.h" -#include "modules/common_msgs/chassis_msgs/chassis.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" -#include "modules/canbus_vehicle/lexus/protocol/accel_cmd_100.h" -#include "modules/canbus_vehicle/lexus/protocol/brake_cmd_104.h" -#include "modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_cmd_108.h" -#include "modules/canbus_vehicle/lexus/protocol/dash_controls_right_rpt_210.h" -#include "modules/canbus_vehicle/lexus/protocol/hazard_lights_cmd_114.h" -#include "modules/canbus_vehicle/lexus/protocol/headlight_cmd_118.h" -#include "modules/canbus_vehicle/lexus/protocol/horn_cmd_11c.h" -#include "modules/canbus_vehicle/lexus/protocol/parking_brake_cmd_124.h" -#include "modules/canbus_vehicle/lexus/protocol/shift_cmd_128.h" -#include "modules/canbus_vehicle/lexus/protocol/steering_cmd_12c.h" -#include "modules/canbus_vehicle/lexus/protocol/turn_cmd_130.h" -#include "modules/canbus_vehicle/lexus/protocol/wiper_cmd_134.h" -#include "modules/canbus/vehicle/vehicle_controller.h" +#include "modules/canbus/vehicle/lexus/protocol/accel_cmd_100.h" +#include "modules/canbus/vehicle/lexus/protocol/brake_cmd_104.h" +#include "modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_cmd_108.h" +#include "modules/canbus/vehicle/lexus/protocol/dash_controls_right_rpt_210.h" +#include "modules/canbus/vehicle/lexus/protocol/hazard_lights_cmd_114.h" +#include "modules/canbus/vehicle/lexus/protocol/headlight_cmd_118.h" +#include "modules/canbus/vehicle/lexus/protocol/horn_cmd_11c.h" +#include "modules/canbus/vehicle/lexus/protocol/parking_brake_cmd_124.h" +#include "modules/canbus/vehicle/lexus/protocol/shift_cmd_128.h" +#include "modules/canbus/vehicle/lexus/protocol/steering_cmd_12c.h" +#include "modules/canbus/vehicle/lexus/protocol/turn_cmd_130.h" +#include "modules/canbus/vehicle/lexus/protocol/wiper_cmd_134.h" namespace apollo { namespace canbus { namespace lexus { -class LexusController final - : public VehicleController<::apollo::canbus::Lexus> { +class LexusController final : public VehicleController { public: virtual ~LexusController(); ::apollo::common::ErrorCode Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Lexus>* const can_sender, - MessageManager<::apollo::canbus::Lexus>* const message_manager) override; + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) + override; bool Start() override; @@ -113,7 +114,6 @@ class LexusController final void SetTurningSignal( const ::apollo::control::ControlCommand& command) override; - bool VerifyID() override; void ResetProtocol(); bool CheckChassisError(); diff --git a/modules/canbus_vehicle/lexus/lexus_controller_test.cc b/modules/canbus/vehicle/lexus/lexus_controller_test.cc similarity index 93% rename from modules/canbus_vehicle/lexus/lexus_controller_test.cc rename to modules/canbus/vehicle/lexus/lexus_controller_test.cc index f7e1f531a77..0c8f42171da 100644 --- a/modules/canbus_vehicle/lexus/lexus_controller_test.cc +++ b/modules/canbus/vehicle/lexus/lexus_controller_test.cc @@ -13,15 +13,15 @@ *implied. See the License for the specific language governing permissions *and limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/lexus_controller.h" +#include "modules/canbus/vehicle/lexus/lexus_controller.h" #include "cyber/common/file.h" #include "gtest/gtest.h" #include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" -#include "modules/canbus_vehicle/lexus/lexus_message_manager.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" +#include "modules/canbus/vehicle/lexus/lexus_message_manager.h" #include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" #include "modules/drivers/canbus/can_comm/can_sender.h" @@ -51,7 +51,7 @@ class LexusControllerTest : public ::testing::Test { LexusController controller_; ControlCommand control_cmd_; VehicleSignal vehicle_signal_; - CanSender<::apollo::canbus::Lexus> sender_; + CanSender<::apollo::canbus::ChassisDetail> sender_; LexusMessageManager msg_manager_; CanbusConf canbus_conf_; VehicleParameter params_; diff --git a/modules/canbus_vehicle/lexus/lexus_message_manager.cc b/modules/canbus/vehicle/lexus/lexus_message_manager.cc similarity index 52% rename from modules/canbus_vehicle/lexus/lexus_message_manager.cc rename to modules/canbus/vehicle/lexus/lexus_message_manager.cc index b87317405e4..3a3f205638f 100644 --- a/modules/canbus_vehicle/lexus/lexus_message_manager.cc +++ b/modules/canbus/vehicle/lexus/lexus_message_manager.cc @@ -13,65 +13,65 @@ See the License for the specific language governing permissions and limitations under the License. ==============================================================================*/ -#include "modules/canbus_vehicle/lexus/lexus_message_manager.h" +#include "modules/canbus/vehicle/lexus/lexus_message_manager.h" -#include "modules/canbus_vehicle/lexus/protocol/accel_cmd_100.h" -#include "modules/canbus_vehicle/lexus/protocol/brake_cmd_104.h" -#include "modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_cmd_108.h" -#include "modules/canbus_vehicle/lexus/protocol/dash_controls_right_rpt_210.h" -#include "modules/canbus_vehicle/lexus/protocol/hazard_lights_cmd_114.h" -#include "modules/canbus_vehicle/lexus/protocol/headlight_cmd_118.h" -#include "modules/canbus_vehicle/lexus/protocol/horn_cmd_11c.h" -#include "modules/canbus_vehicle/lexus/protocol/parking_brake_cmd_124.h" -#include "modules/canbus_vehicle/lexus/protocol/shift_cmd_128.h" -#include "modules/canbus_vehicle/lexus/protocol/steering_cmd_12c.h" -#include "modules/canbus_vehicle/lexus/protocol/turn_cmd_130.h" -#include "modules/canbus_vehicle/lexus/protocol/wiper_cmd_134.h" +#include "modules/canbus/vehicle/lexus/protocol/accel_cmd_100.h" +#include "modules/canbus/vehicle/lexus/protocol/brake_cmd_104.h" +#include "modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_cmd_108.h" +#include "modules/canbus/vehicle/lexus/protocol/dash_controls_right_rpt_210.h" +#include "modules/canbus/vehicle/lexus/protocol/hazard_lights_cmd_114.h" +#include "modules/canbus/vehicle/lexus/protocol/headlight_cmd_118.h" +#include "modules/canbus/vehicle/lexus/protocol/horn_cmd_11c.h" +#include "modules/canbus/vehicle/lexus/protocol/parking_brake_cmd_124.h" +#include "modules/canbus/vehicle/lexus/protocol/shift_cmd_128.h" +#include "modules/canbus/vehicle/lexus/protocol/steering_cmd_12c.h" +#include "modules/canbus/vehicle/lexus/protocol/turn_cmd_130.h" +#include "modules/canbus/vehicle/lexus/protocol/wiper_cmd_134.h" -#include "modules/canbus_vehicle/lexus/protocol/accel_aux_rpt_300.h" -#include "modules/canbus_vehicle/lexus/protocol/accel_rpt_200.h" -#include "modules/canbus_vehicle/lexus/protocol/brake_aux_rpt_304.h" -#include "modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_1_401.h" -#include "modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_2_402.h" -#include "modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_3_403.h" -#include "modules/canbus_vehicle/lexus/protocol/brake_rpt_204.h" -#include "modules/canbus_vehicle/lexus/protocol/component_rpt_20.h" -#include "modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_rpt_208.h" -#include "modules/canbus_vehicle/lexus/protocol/dash_controls_left_cmd_10c.h" -#include "modules/canbus_vehicle/lexus/protocol/dash_controls_left_rpt_20c.h" -#include "modules/canbus_vehicle/lexus/protocol/dash_controls_right_cmd_110.h" -#include "modules/canbus_vehicle/lexus/protocol/date_time_rpt_40f.h" -#include "modules/canbus_vehicle/lexus/protocol/detected_object_rpt_411.h" -#include "modules/canbus_vehicle/lexus/protocol/door_rpt_417.h" -#include "modules/canbus_vehicle/lexus/protocol/global_rpt_10.h" -#include "modules/canbus_vehicle/lexus/protocol/hazard_lights_rpt_214.h" -#include "modules/canbus_vehicle/lexus/protocol/headlight_aux_rpt_318.h" -#include "modules/canbus_vehicle/lexus/protocol/headlight_rpt_218.h" -#include "modules/canbus_vehicle/lexus/protocol/horn_rpt_21c.h" -#include "modules/canbus_vehicle/lexus/protocol/interior_lights_rpt_416.h" -#include "modules/canbus_vehicle/lexus/protocol/lat_lon_heading_rpt_40e.h" -#include "modules/canbus_vehicle/lexus/protocol/media_controls_cmd_120.h" -#include "modules/canbus_vehicle/lexus/protocol/media_controls_rpt_220.h" -#include "modules/canbus_vehicle/lexus/protocol/occupancy_rpt_415.h" -#include "modules/canbus_vehicle/lexus/protocol/parking_brake_rpt_224.h" -#include "modules/canbus_vehicle/lexus/protocol/rear_lights_rpt_418.h" -#include "modules/canbus_vehicle/lexus/protocol/shift_aux_rpt_328.h" -#include "modules/canbus_vehicle/lexus/protocol/shift_rpt_228.h" -#include "modules/canbus_vehicle/lexus/protocol/steering_aux_rpt_32c.h" -#include "modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_1_404.h" -#include "modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_2_405.h" -#include "modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_3_406.h" -#include "modules/canbus_vehicle/lexus/protocol/steering_rpt_22c.h" -#include "modules/canbus_vehicle/lexus/protocol/turn_aux_rpt_330.h" -#include "modules/canbus_vehicle/lexus/protocol/turn_rpt_230.h" -#include "modules/canbus_vehicle/lexus/protocol/veh_dynamics_rpt_413.h" -#include "modules/canbus_vehicle/lexus/protocol/veh_specific_rpt_1_412.h" -#include "modules/canbus_vehicle/lexus/protocol/vehicle_speed_rpt_400.h" -#include "modules/canbus_vehicle/lexus/protocol/vin_rpt_414.h" -#include "modules/canbus_vehicle/lexus/protocol/wheel_speed_rpt_407.h" -#include "modules/canbus_vehicle/lexus/protocol/wiper_aux_rpt_334.h" -#include "modules/canbus_vehicle/lexus/protocol/wiper_rpt_234.h" -#include "modules/canbus_vehicle/lexus/protocol/yaw_rate_rpt_40d.h" +#include "modules/canbus/vehicle/lexus/protocol/accel_aux_rpt_300.h" +#include "modules/canbus/vehicle/lexus/protocol/accel_rpt_200.h" +#include "modules/canbus/vehicle/lexus/protocol/brake_aux_rpt_304.h" +#include "modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_1_401.h" +#include "modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_2_402.h" +#include "modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_3_403.h" +#include "modules/canbus/vehicle/lexus/protocol/brake_rpt_204.h" +#include "modules/canbus/vehicle/lexus/protocol/component_rpt_20.h" +#include "modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_rpt_208.h" +#include "modules/canbus/vehicle/lexus/protocol/dash_controls_left_cmd_10c.h" +#include "modules/canbus/vehicle/lexus/protocol/dash_controls_left_rpt_20c.h" +#include "modules/canbus/vehicle/lexus/protocol/dash_controls_right_cmd_110.h" +#include "modules/canbus/vehicle/lexus/protocol/date_time_rpt_40f.h" +#include "modules/canbus/vehicle/lexus/protocol/detected_object_rpt_411.h" +#include "modules/canbus/vehicle/lexus/protocol/door_rpt_417.h" +#include "modules/canbus/vehicle/lexus/protocol/global_rpt_10.h" +#include "modules/canbus/vehicle/lexus/protocol/hazard_lights_rpt_214.h" +#include "modules/canbus/vehicle/lexus/protocol/headlight_aux_rpt_318.h" +#include "modules/canbus/vehicle/lexus/protocol/headlight_rpt_218.h" +#include "modules/canbus/vehicle/lexus/protocol/horn_rpt_21c.h" +#include "modules/canbus/vehicle/lexus/protocol/interior_lights_rpt_416.h" +#include "modules/canbus/vehicle/lexus/protocol/lat_lon_heading_rpt_40e.h" +#include "modules/canbus/vehicle/lexus/protocol/media_controls_cmd_120.h" +#include "modules/canbus/vehicle/lexus/protocol/media_controls_rpt_220.h" +#include "modules/canbus/vehicle/lexus/protocol/occupancy_rpt_415.h" +#include "modules/canbus/vehicle/lexus/protocol/parking_brake_rpt_224.h" +#include "modules/canbus/vehicle/lexus/protocol/rear_lights_rpt_418.h" +#include "modules/canbus/vehicle/lexus/protocol/shift_aux_rpt_328.h" +#include "modules/canbus/vehicle/lexus/protocol/shift_rpt_228.h" +#include "modules/canbus/vehicle/lexus/protocol/steering_aux_rpt_32c.h" +#include "modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_1_404.h" +#include "modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_2_405.h" +#include "modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_3_406.h" +#include "modules/canbus/vehicle/lexus/protocol/steering_rpt_22c.h" +#include "modules/canbus/vehicle/lexus/protocol/turn_aux_rpt_330.h" +#include "modules/canbus/vehicle/lexus/protocol/turn_rpt_230.h" +#include "modules/canbus/vehicle/lexus/protocol/veh_dynamics_rpt_413.h" +#include "modules/canbus/vehicle/lexus/protocol/veh_specific_rpt_1_412.h" +#include "modules/canbus/vehicle/lexus/protocol/vehicle_speed_rpt_400.h" +#include "modules/canbus/vehicle/lexus/protocol/vin_rpt_414.h" +#include "modules/canbus/vehicle/lexus/protocol/wheel_speed_rpt_407.h" +#include "modules/canbus/vehicle/lexus/protocol/wiper_aux_rpt_334.h" +#include "modules/canbus/vehicle/lexus/protocol/wiper_rpt_234.h" +#include "modules/canbus/vehicle/lexus/protocol/yaw_rate_rpt_40d.h" namespace apollo { namespace canbus { diff --git a/modules/canbus_vehicle/lexus/lexus_message_manager.h b/modules/canbus/vehicle/lexus/lexus_message_manager.h similarity index 88% rename from modules/canbus_vehicle/lexus/lexus_message_manager.h rename to modules/canbus/vehicle/lexus/lexus_message_manager.h index 8375b41b822..d2a9c0a9b78 100644 --- a/modules/canbus_vehicle/lexus/lexus_message_manager.h +++ b/modules/canbus/vehicle/lexus/lexus_message_manager.h @@ -15,7 +15,7 @@ limitations under the License. #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/message_manager.h" namespace apollo { @@ -25,7 +25,7 @@ namespace lexus { using ::apollo::drivers::canbus::MessageManager; class LexusMessageManager - : public MessageManager<::apollo::canbus::Lexus> { + : public MessageManager<::apollo::canbus::ChassisDetail> { public: LexusMessageManager(); virtual ~LexusMessageManager(); diff --git a/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_server_test.cc b/modules/canbus/vehicle/lexus/lexus_vehicle_factory.cc similarity index 54% rename from modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_server_test.cc rename to modules/canbus/vehicle/lexus/lexus_vehicle_factory.cc index 4ec8a7df578..cb5f3c86805 100644 --- a/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_server_test.cc +++ b/modules/canbus/vehicle/lexus/lexus_vehicle_factory.cc @@ -14,27 +14,26 @@ * limitations under the License. *****************************************************************************/ -/** - * @file grpc_server_test.cc - * @brief test v2x proxy module and onboard unit interface grpc implement - */ +#include "modules/canbus/vehicle/lexus/lexus_vehicle_factory.h" -#include "modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_server.h" - -#include "gtest/gtest.h" +#include "cyber/common/log.h" +#include "modules/canbus/vehicle/lexus/lexus_controller.h" +#include "modules/canbus/vehicle/lexus/lexus_message_manager.h" +#include "modules/common/util/util.h" namespace apollo { -namespace v2x { +namespace canbus { + +std::unique_ptr +LexusVehicleFactory::CreateVehicleController() { + return std::unique_ptr(new lexus::LexusController()); +} -TEST(GrpcServerImplTest, Construct) { - apollo::cyber::Init("grpc_server_test"); - bool init_succ = false; - GrpcServerImpl grpc_server; - init_succ = grpc_server.InitFlag(); - EXPECT_TRUE(init_succ); - std::shared_ptr<::apollo::v2x::obu::ObuTrafficLight> ptr = nullptr; - grpc_server.GetMsgFromGrpc(&ptr); - EXPECT_EQ(nullptr, ptr); +std::unique_ptr> +LexusVehicleFactory::CreateMessageManager() { + return std::unique_ptr>( + new lexus::LexusMessageManager()); } -} // namespace v2x + +} // namespace canbus } // namespace apollo diff --git a/modules/canbus/vehicle/lexus/lexus_vehicle_factory.h b/modules/canbus/vehicle/lexus/lexus_vehicle_factory.h new file mode 100644 index 00000000000..c795067703e --- /dev/null +++ b/modules/canbus/vehicle/lexus/lexus_vehicle_factory.h @@ -0,0 +1,65 @@ +/****************************************************************************** + * 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. + *****************************************************************************/ + +/** + * @file lexus_vehicle_factory.h + */ + +#pragma once + +#include + +#include "modules/canbus/proto/vehicle_parameter.pb.h" +#include "modules/canbus/vehicle/abstract_vehicle_factory.h" +#include "modules/canbus/vehicle/vehicle_controller.h" +#include "modules/drivers/canbus/can_comm/message_manager.h" + +/** + * @namespace apollo::canbus + * @brief apollo::canbus + */ +namespace apollo { +namespace canbus { + +/** + * @class LexusVehicleFactory + * + * @brief this class is inherited from AbstractVehicleFactory. It can be used to + * create controller and message manager for lexus vehicle. + */ +class LexusVehicleFactory : public AbstractVehicleFactory { + public: + /** + * @brief destructor + */ + virtual ~LexusVehicleFactory() = default; + + /** + * @brief create lexus vehicle controller + * @returns a unique_ptr that points to the created controller + */ + std::unique_ptr CreateVehicleController() override; + + /** + * @brief create lexus message manager + * @returns a unique_ptr that points to the created message manager + */ + std::unique_ptr> + CreateMessageManager() override; +}; + +} // namespace canbus +} // namespace apollo diff --git a/modules/tools/gen_vehicle_protocol/template/protocol_BUILD.tpl b/modules/canbus/vehicle/lexus/protocol/BUILD similarity index 76% rename from modules/tools/gen_vehicle_protocol/template/protocol_BUILD.tpl rename to modules/canbus/vehicle/lexus/protocol/BUILD index fd44cd350d6..e89a6fcb8f1 100644 --- a/modules/tools/gen_vehicle_protocol/template/protocol_BUILD.tpl +++ b/modules/canbus/vehicle/lexus/protocol/BUILD @@ -1,19 +1,21 @@ +load("@rules_cc//cc:defs.bzl", "cc_library") load("//tools:cpplint.bzl", "cpplint") package(default_visibility = ["//visibility:public"]) cc_library( - name = "canbus_%(car_type)s_protocol", + name = "canbus_lexus_protocol", srcs = glob([ "*.cc", ]), hdrs = glob([ "*.h", ]), + copts = ["-DMODULE_NAME=\\\"canbus\\\""], deps = [ - "//modules/drivers/canbus/common:canbus_common", "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", ], ) diff --git a/modules/canbus_vehicle/lexus/protocol/accel_aux_rpt_300.cc b/modules/canbus/vehicle/lexus/protocol/accel_aux_rpt_300.cc similarity index 84% rename from modules/canbus_vehicle/lexus/protocol/accel_aux_rpt_300.cc rename to modules/canbus/vehicle/lexus/protocol/accel_aux_rpt_300.cc index 2bbf0b1513b..90de116371f 100644 --- a/modules/canbus_vehicle/lexus/protocol/accel_aux_rpt_300.cc +++ b/modules/canbus/vehicle/lexus/protocol/accel_aux_rpt_300.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/accel_aux_rpt_300.h" +#include "modules/canbus/vehicle/lexus/protocol/accel_aux_rpt_300.h" #include "glog/logging.h" @@ -31,18 +31,21 @@ Accelauxrpt300::Accelauxrpt300() {} const int32_t Accelauxrpt300::ID = 0x300; void Accelauxrpt300::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_accel_aux_rpt_300()->set_user_interaction_is_valid( - user_interaction_is_valid(bytes, length)); - chassis->mutable_accel_aux_rpt_300()->set_user_interaction( + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_accel_aux_rpt_300() + ->set_user_interaction_is_valid(user_interaction_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_accel_aux_rpt_300()->set_user_interaction( user_interaction(bytes, length)); - chassis->mutable_accel_aux_rpt_300()->set_raw_pedal_force_is_valid( - raw_pedal_force_is_valid(bytes, length)); - chassis->mutable_accel_aux_rpt_300()->set_raw_pedal_force( + chassis->mutable_lexus() + ->mutable_accel_aux_rpt_300() + ->set_raw_pedal_force_is_valid(raw_pedal_force_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_accel_aux_rpt_300()->set_raw_pedal_force( raw_pedal_force(bytes, length)); - chassis->mutable_accel_aux_rpt_300()->set_raw_pedal_pos_is_valid( - raw_pedal_pos_is_valid(bytes, length)); - chassis->mutable_accel_aux_rpt_300()->set_raw_pedal_pos( + chassis->mutable_lexus() + ->mutable_accel_aux_rpt_300() + ->set_raw_pedal_pos_is_valid(raw_pedal_pos_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_accel_aux_rpt_300()->set_raw_pedal_pos( raw_pedal_pos(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/accel_aux_rpt_300.h b/modules/canbus/vehicle/lexus/protocol/accel_aux_rpt_300.h similarity index 94% rename from modules/canbus_vehicle/lexus/protocol/accel_aux_rpt_300.h rename to modules/canbus/vehicle/lexus/protocol/accel_aux_rpt_300.h index 3ab3a519b92..2a4100889fa 100644 --- a/modules/canbus_vehicle/lexus/protocol/accel_aux_rpt_300.h +++ b/modules/canbus/vehicle/lexus/protocol/accel_aux_rpt_300.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Accelauxrpt300 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Accelauxrpt300(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'USER_INTERACTION_IS_VALID', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/accel_cmd_100.cc b/modules/canbus/vehicle/lexus/protocol/accel_cmd_100.cc similarity index 98% rename from modules/canbus_vehicle/lexus/protocol/accel_cmd_100.cc rename to modules/canbus/vehicle/lexus/protocol/accel_cmd_100.cc index 6fdb25468e7..3d2aaf5cbeb 100644 --- a/modules/canbus_vehicle/lexus/protocol/accel_cmd_100.cc +++ b/modules/canbus/vehicle/lexus/protocol/accel_cmd_100.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/accel_cmd_100.h" +#include "modules/canbus/vehicle/lexus/protocol/accel_cmd_100.h" #include diff --git a/modules/canbus_vehicle/lexus/protocol/accel_cmd_100.h b/modules/canbus/vehicle/lexus/protocol/accel_cmd_100.h similarity index 97% rename from modules/canbus_vehicle/lexus/protocol/accel_cmd_100.h rename to modules/canbus/vehicle/lexus/protocol/accel_cmd_100.h index 1e915c0c5e7..8385e1db36a 100644 --- a/modules/canbus_vehicle/lexus/protocol/accel_cmd_100.h +++ b/modules/canbus/vehicle/lexus/protocol/accel_cmd_100.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace lexus { class Accelcmd100 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lexus/protocol/accel_rpt_200.cc b/modules/canbus/vehicle/lexus/protocol/accel_rpt_200.cc similarity index 87% rename from modules/canbus_vehicle/lexus/protocol/accel_rpt_200.cc rename to modules/canbus/vehicle/lexus/protocol/accel_rpt_200.cc index b3bc8f37592..cf8a905a7da 100644 --- a/modules/canbus_vehicle/lexus/protocol/accel_rpt_200.cc +++ b/modules/canbus/vehicle/lexus/protocol/accel_rpt_200.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/accel_rpt_200.h" +#include "modules/canbus/vehicle/lexus/protocol/accel_rpt_200.h" #include "glog/logging.h" @@ -31,26 +31,26 @@ Accelrpt200::Accelrpt200() {} const int32_t Accelrpt200::ID = 0x200; void Accelrpt200::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_accel_rpt_200()->set_vehicle_fault( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_accel_rpt_200()->set_vehicle_fault( vehicle_fault(bytes, length)); - chassis->mutable_accel_rpt_200()->set_pacmod_fault( + chassis->mutable_lexus()->mutable_accel_rpt_200()->set_pacmod_fault( pacmod_fault(bytes, length)); - chassis->mutable_accel_rpt_200()->set_output_reported_fault( + chassis->mutable_lexus()->mutable_accel_rpt_200()->set_output_reported_fault( output_reported_fault(bytes, length)); - chassis->mutable_accel_rpt_200()->set_input_output_fault( + chassis->mutable_lexus()->mutable_accel_rpt_200()->set_input_output_fault( input_output_fault(bytes, length)); - chassis->mutable_accel_rpt_200()->set_command_output_fault( + chassis->mutable_lexus()->mutable_accel_rpt_200()->set_command_output_fault( command_output_fault(bytes, length)); - chassis->mutable_accel_rpt_200()->set_override_active( + chassis->mutable_lexus()->mutable_accel_rpt_200()->set_override_active( override_active(bytes, length)); - chassis->mutable_accel_rpt_200()->set_enabled( + chassis->mutable_lexus()->mutable_accel_rpt_200()->set_enabled( enabled(bytes, length)); - chassis->mutable_accel_rpt_200()->set_manual_input( + chassis->mutable_lexus()->mutable_accel_rpt_200()->set_manual_input( manual_input(bytes, length)); - chassis->mutable_accel_rpt_200()->set_commanded_value( + chassis->mutable_lexus()->mutable_accel_rpt_200()->set_commanded_value( commanded_value(bytes, length)); - chassis->mutable_accel_rpt_200()->set_output_value( + chassis->mutable_lexus()->mutable_accel_rpt_200()->set_output_value( output_value(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/accel_rpt_200.h b/modules/canbus/vehicle/lexus/protocol/accel_rpt_200.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/accel_rpt_200.h rename to modules/canbus/vehicle/lexus/protocol/accel_rpt_200.h index 134596fb07d..ba5f41ec5f1 100644 --- a/modules/canbus_vehicle/lexus/protocol/accel_rpt_200.h +++ b/modules/canbus/vehicle/lexus/protocol/accel_rpt_200.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Accelrpt200 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Accelrpt200(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VEHICLE_FAULT', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/brake_aux_rpt_304.cc b/modules/canbus/vehicle/lexus/protocol/brake_aux_rpt_304.cc similarity index 84% rename from modules/canbus_vehicle/lexus/protocol/brake_aux_rpt_304.cc rename to modules/canbus/vehicle/lexus/protocol/brake_aux_rpt_304.cc index af490da6792..eb7583f499e 100644 --- a/modules/canbus_vehicle/lexus/protocol/brake_aux_rpt_304.cc +++ b/modules/canbus/vehicle/lexus/protocol/brake_aux_rpt_304.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/brake_aux_rpt_304.h" +#include "modules/canbus/vehicle/lexus/protocol/brake_aux_rpt_304.h" #include "glog/logging.h" @@ -31,26 +31,32 @@ Brakeauxrpt304::Brakeauxrpt304() {} const int32_t Brakeauxrpt304::ID = 0x304; void Brakeauxrpt304::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_brake_aux_rpt_304() + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_brake_aux_rpt_304() ->set_brake_on_off_is_valid(brake_on_off_is_valid(bytes, length)); - chassis->mutable_brake_aux_rpt_304()->set_brake_on_off( + chassis->mutable_lexus()->mutable_brake_aux_rpt_304()->set_brake_on_off( brake_on_off(bytes, length)); - chassis->mutable_brake_aux_rpt_304()->set_user_interaction_is_valid( - user_interaction_is_valid(bytes, length)); - chassis->mutable_brake_aux_rpt_304()->set_user_interaction( + chassis->mutable_lexus() + ->mutable_brake_aux_rpt_304() + ->set_user_interaction_is_valid(user_interaction_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_brake_aux_rpt_304()->set_user_interaction( user_interaction(bytes, length)); - chassis->mutable_brake_aux_rpt_304()->set_raw_brake_pressure_is_valid( - raw_brake_pressure_is_valid(bytes, length)); - chassis->mutable_brake_aux_rpt_304()->set_raw_brake_pressure( + chassis->mutable_lexus() + ->mutable_brake_aux_rpt_304() + ->set_raw_brake_pressure_is_valid( + raw_brake_pressure_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_brake_aux_rpt_304()->set_raw_brake_pressure( raw_brake_pressure(bytes, length)); - chassis->mutable_brake_aux_rpt_304()->set_raw_pedal_force_is_valid( - raw_pedal_force_is_valid(bytes, length)); - chassis->mutable_brake_aux_rpt_304()->set_raw_pedal_force( + chassis->mutable_lexus() + ->mutable_brake_aux_rpt_304() + ->set_raw_pedal_force_is_valid(raw_pedal_force_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_brake_aux_rpt_304()->set_raw_pedal_force( raw_pedal_force(bytes, length)); - chassis->mutable_brake_aux_rpt_304()->set_raw_pedal_pos_is_valid( - raw_pedal_pos_is_valid(bytes, length)); - chassis->mutable_brake_aux_rpt_304()->set_raw_pedal_pos( + chassis->mutable_lexus() + ->mutable_brake_aux_rpt_304() + ->set_raw_pedal_pos_is_valid(raw_pedal_pos_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_brake_aux_rpt_304()->set_raw_pedal_pos( raw_pedal_pos(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/brake_aux_rpt_304.h b/modules/canbus/vehicle/lexus/protocol/brake_aux_rpt_304.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/brake_aux_rpt_304.h rename to modules/canbus/vehicle/lexus/protocol/brake_aux_rpt_304.h index 9a03aec78d8..309806d6c3a 100644 --- a/modules/canbus_vehicle/lexus/protocol/brake_aux_rpt_304.h +++ b/modules/canbus/vehicle/lexus/protocol/brake_aux_rpt_304.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Brakeauxrpt304 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Brakeauxrpt304(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'BRAKE_ON_OFF_IS_VALID', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/brake_cmd_104.cc b/modules/canbus/vehicle/lexus/protocol/brake_cmd_104.cc similarity index 98% rename from modules/canbus_vehicle/lexus/protocol/brake_cmd_104.cc rename to modules/canbus/vehicle/lexus/protocol/brake_cmd_104.cc index 2bc5e315b13..793c6008a69 100644 --- a/modules/canbus_vehicle/lexus/protocol/brake_cmd_104.cc +++ b/modules/canbus/vehicle/lexus/protocol/brake_cmd_104.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/brake_cmd_104.h" +#include "modules/canbus/vehicle/lexus/protocol/brake_cmd_104.h" #include diff --git a/modules/canbus_vehicle/lexus/protocol/brake_cmd_104.h b/modules/canbus/vehicle/lexus/protocol/brake_cmd_104.h similarity index 97% rename from modules/canbus_vehicle/lexus/protocol/brake_cmd_104.h rename to modules/canbus/vehicle/lexus/protocol/brake_cmd_104.h index 5e06a4e232f..efda7ed91cc 100644 --- a/modules/canbus_vehicle/lexus/protocol/brake_cmd_104.h +++ b/modules/canbus/vehicle/lexus/protocol/brake_cmd_104.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace lexus { class Brakecmd104 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_1_401.cc b/modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_1_401.cc similarity index 90% rename from modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_1_401.cc rename to modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_1_401.cc index 7c3e7b33b0a..190a4380595 100644 --- a/modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_1_401.cc +++ b/modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_1_401.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_1_401.h" +#include "modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_1_401.h" #include "glog/logging.h" @@ -31,10 +31,10 @@ Brakemotorrpt1401::Brakemotorrpt1401() {} const int32_t Brakemotorrpt1401::ID = 0x401; void Brakemotorrpt1401::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_brake_motor_rpt_1_401()->set_motor_current( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_brake_motor_rpt_1_401()->set_motor_current( motor_current(bytes, length)); - chassis->mutable_brake_motor_rpt_1_401()->set_shaft_position( + chassis->mutable_lexus()->mutable_brake_motor_rpt_1_401()->set_shaft_position( shaft_position(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_1_401.h b/modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_1_401.h similarity index 90% rename from modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_1_401.h rename to modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_1_401.h index 03dedc6ec75..fdecb153cef 100644 --- a/modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_1_401.h +++ b/modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_1_401.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Brakemotorrpt1401 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Brakemotorrpt1401(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'MOTOR_CURRENT', 'offset': 0.0, 'precision': 0.001, diff --git a/modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_2_402.cc b/modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_2_402.cc similarity index 86% rename from modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_2_402.cc rename to modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_2_402.cc index 45544ae0d9e..43b58e3371b 100644 --- a/modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_2_402.cc +++ b/modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_2_402.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_2_402.h" +#include "modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_2_402.h" #include "glog/logging.h" @@ -31,12 +31,14 @@ Brakemotorrpt2402::Brakemotorrpt2402() {} const int32_t Brakemotorrpt2402::ID = 0x402; void Brakemotorrpt2402::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_brake_motor_rpt_2_402()->set_encoder_temperature( - encoder_temperature(bytes, length)); - chassis->mutable_brake_motor_rpt_2_402()->set_motor_temperature( - motor_temperature(bytes, length)); - chassis->mutable_brake_motor_rpt_2_402()->set_angular_speed( + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_brake_motor_rpt_2_402() + ->set_encoder_temperature(encoder_temperature(bytes, length)); + chassis->mutable_lexus() + ->mutable_brake_motor_rpt_2_402() + ->set_motor_temperature(motor_temperature(bytes, length)); + chassis->mutable_lexus()->mutable_brake_motor_rpt_2_402()->set_angular_speed( angular_speed(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_2_402.h b/modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_2_402.h similarity index 92% rename from modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_2_402.h rename to modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_2_402.h index 1a773cc5026..484b508f093 100644 --- a/modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_2_402.h +++ b/modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_2_402.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Brakemotorrpt2402 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Brakemotorrpt2402(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'ENCODER_TEMPERATURE', 'offset': -40.0, diff --git a/modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_3_403.cc b/modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_3_403.cc similarity index 90% rename from modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_3_403.cc rename to modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_3_403.cc index dbf10ab9ea4..469fefec6c5 100644 --- a/modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_3_403.cc +++ b/modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_3_403.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_3_403.h" +#include "modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_3_403.h" #include "glog/logging.h" @@ -31,10 +31,10 @@ Brakemotorrpt3403::Brakemotorrpt3403() {} const int32_t Brakemotorrpt3403::ID = 0x403; void Brakemotorrpt3403::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_brake_motor_rpt_3_403()->set_torque_output( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_brake_motor_rpt_3_403()->set_torque_output( torque_output(bytes, length)); - chassis->mutable_brake_motor_rpt_3_403()->set_torque_input( + chassis->mutable_lexus()->mutable_brake_motor_rpt_3_403()->set_torque_input( torque_input(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_3_403.h b/modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_3_403.h similarity index 90% rename from modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_3_403.h rename to modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_3_403.h index f38ab0ca14e..7e280dcc846 100644 --- a/modules/canbus_vehicle/lexus/protocol/brake_motor_rpt_3_403.h +++ b/modules/canbus/vehicle/lexus/protocol/brake_motor_rpt_3_403.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Brakemotorrpt3403 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Brakemotorrpt3403(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'TORQUE_OUTPUT', 'offset': 0.0, 'precision': 0.001, diff --git a/modules/canbus_vehicle/lexus/protocol/brake_rpt_204.cc b/modules/canbus/vehicle/lexus/protocol/brake_rpt_204.cc similarity index 87% rename from modules/canbus_vehicle/lexus/protocol/brake_rpt_204.cc rename to modules/canbus/vehicle/lexus/protocol/brake_rpt_204.cc index a237f730241..dc3ef8f5b05 100644 --- a/modules/canbus_vehicle/lexus/protocol/brake_rpt_204.cc +++ b/modules/canbus/vehicle/lexus/protocol/brake_rpt_204.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/brake_rpt_204.h" +#include "modules/canbus/vehicle/lexus/protocol/brake_rpt_204.h" #include "glog/logging.h" @@ -31,26 +31,26 @@ Brakerpt204::Brakerpt204() {} const int32_t Brakerpt204::ID = 0x204; void Brakerpt204::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_brake_rpt_204()->set_command_output_fault( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_brake_rpt_204()->set_command_output_fault( command_output_fault(bytes, length)); - chassis->mutable_brake_rpt_204()->set_vehicle_fault( + chassis->mutable_lexus()->mutable_brake_rpt_204()->set_vehicle_fault( vehicle_fault(bytes, length)); - chassis->mutable_brake_rpt_204()->set_pacmod_fault( + chassis->mutable_lexus()->mutable_brake_rpt_204()->set_pacmod_fault( pacmod_fault(bytes, length)); - chassis->mutable_brake_rpt_204()->set_override_active( + chassis->mutable_lexus()->mutable_brake_rpt_204()->set_override_active( override_active(bytes, length)); - chassis->mutable_brake_rpt_204()->set_output_reported_fault( + chassis->mutable_lexus()->mutable_brake_rpt_204()->set_output_reported_fault( output_reported_fault(bytes, length)); - chassis->mutable_brake_rpt_204()->set_input_output_fault( + chassis->mutable_lexus()->mutable_brake_rpt_204()->set_input_output_fault( input_output_fault(bytes, length)); - chassis->mutable_brake_rpt_204()->set_enabled( + chassis->mutable_lexus()->mutable_brake_rpt_204()->set_enabled( enabled(bytes, length)); - chassis->mutable_brake_rpt_204()->set_manual_input( + chassis->mutable_lexus()->mutable_brake_rpt_204()->set_manual_input( manual_input(bytes, length)); - chassis->mutable_brake_rpt_204()->set_commanded_value( + chassis->mutable_lexus()->mutable_brake_rpt_204()->set_commanded_value( commanded_value(bytes, length)); - chassis->mutable_brake_rpt_204()->set_output_value( + chassis->mutable_lexus()->mutable_brake_rpt_204()->set_output_value( output_value(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/brake_rpt_204.h b/modules/canbus/vehicle/lexus/protocol/brake_rpt_204.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/brake_rpt_204.h rename to modules/canbus/vehicle/lexus/protocol/brake_rpt_204.h index 85f81f5af61..441b468778d 100644 --- a/modules/canbus_vehicle/lexus/protocol/brake_rpt_204.h +++ b/modules/canbus/vehicle/lexus/protocol/brake_rpt_204.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Brakerpt204 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Brakerpt204(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'COMMAND_OUTPUT_FAULT', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/component_rpt_20.cc b/modules/canbus/vehicle/lexus/protocol/component_rpt_20.cc similarity index 89% rename from modules/canbus_vehicle/lexus/protocol/component_rpt_20.cc rename to modules/canbus/vehicle/lexus/protocol/component_rpt_20.cc index 7c6468ec071..84c69fa8be3 100644 --- a/modules/canbus_vehicle/lexus/protocol/component_rpt_20.cc +++ b/modules/canbus/vehicle/lexus/protocol/component_rpt_20.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/component_rpt_20.h" +#include "modules/canbus/vehicle/lexus/protocol/component_rpt_20.h" #include "glog/logging.h" @@ -31,16 +31,16 @@ Componentrpt20::Componentrpt20() {} const int32_t Componentrpt20::ID = 0x20; void Componentrpt20::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_component_rpt_20()->set_component_type( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_component_rpt_20()->set_component_type( component_type(bytes, length)); - chassis->mutable_component_rpt_20()->set_component_func( + chassis->mutable_lexus()->mutable_component_rpt_20()->set_component_func( component_func(bytes, length)); - chassis->mutable_component_rpt_20()->set_counter( + chassis->mutable_lexus()->mutable_component_rpt_20()->set_counter( counter(bytes, length)); - chassis->mutable_component_rpt_20()->set_complement( + chassis->mutable_lexus()->mutable_component_rpt_20()->set_complement( complement(bytes, length)); - chassis->mutable_component_rpt_20()->set_config_fault( + chassis->mutable_lexus()->mutable_component_rpt_20()->set_config_fault( config_fault(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/component_rpt_20.h b/modules/canbus/vehicle/lexus/protocol/component_rpt_20.h similarity index 94% rename from modules/canbus_vehicle/lexus/protocol/component_rpt_20.h rename to modules/canbus/vehicle/lexus/protocol/component_rpt_20.h index c93d15fd045..8cb279997ff 100644 --- a/modules/canbus_vehicle/lexus/protocol/component_rpt_20.h +++ b/modules/canbus/vehicle/lexus/protocol/component_rpt_20.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Componentrpt20 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Componentrpt20(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'COMPONENT_TYPE', 'enum': {0: diff --git a/modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_cmd_108.cc b/modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_cmd_108.cc similarity index 98% rename from modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_cmd_108.cc rename to modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_cmd_108.cc index 8051d800164..e2062138624 100644 --- a/modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_cmd_108.cc +++ b/modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_cmd_108.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_cmd_108.h" +#include "modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_cmd_108.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_cmd_108.h b/modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_cmd_108.h similarity index 97% rename from modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_cmd_108.h rename to modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_cmd_108.h index a38becae546..ebc1e2c3d38 100644 --- a/modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_cmd_108.h +++ b/modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_cmd_108.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,7 +25,7 @@ namespace lexus { class Cruisecontrolbuttonscmd108 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_rpt_208.cc b/modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_rpt_208.cc similarity index 82% rename from modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_rpt_208.cc rename to modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_rpt_208.cc index 79210120573..1e3cf8c1344 100644 --- a/modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_rpt_208.cc +++ b/modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_rpt_208.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_rpt_208.h" +#include "modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_rpt_208.h" #include "glog/logging.h" @@ -32,27 +32,37 @@ const int32_t Cruisecontrolbuttonsrpt208::ID = 0x208; void Cruisecontrolbuttonsrpt208::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_cruise_control_buttons_rpt_208()->set_output_value( - output_value(bytes, length)); - chassis->mutable_cruise_control_buttons_rpt_208()->set_manual_input( - manual_input(bytes, length)); - chassis->mutable_cruise_control_buttons_rpt_208()->set_commanded_value( - commanded_value(bytes, length)); - chassis->mutable_cruise_control_buttons_rpt_208()->set_vehicle_fault( - vehicle_fault(bytes, length)); - chassis->mutable_cruise_control_buttons_rpt_208()->set_pacmod_fault( - pacmod_fault(bytes, length)); - chassis->mutable_cruise_control_buttons_rpt_208()->set_override_active( - override_active(bytes, length)); - chassis->mutable_cruise_control_buttons_rpt_208()->set_output_reported_fault( - output_reported_fault(bytes, length)); - chassis->mutable_cruise_control_buttons_rpt_208()->set_input_output_fault( - input_output_fault(bytes, length)); - chassis->mutable_cruise_control_buttons_rpt_208()->set_enabled( - enabled(bytes, length)); - chassis->mutable_cruise_control_buttons_rpt_208()->set_command_output_fault( - command_output_fault(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_cruise_control_buttons_rpt_208() + ->set_output_value(output_value(bytes, length)); + chassis->mutable_lexus() + ->mutable_cruise_control_buttons_rpt_208() + ->set_manual_input(manual_input(bytes, length)); + chassis->mutable_lexus() + ->mutable_cruise_control_buttons_rpt_208() + ->set_commanded_value(commanded_value(bytes, length)); + chassis->mutable_lexus() + ->mutable_cruise_control_buttons_rpt_208() + ->set_vehicle_fault(vehicle_fault(bytes, length)); + chassis->mutable_lexus() + ->mutable_cruise_control_buttons_rpt_208() + ->set_pacmod_fault(pacmod_fault(bytes, length)); + chassis->mutable_lexus() + ->mutable_cruise_control_buttons_rpt_208() + ->set_override_active(override_active(bytes, length)); + chassis->mutable_lexus() + ->mutable_cruise_control_buttons_rpt_208() + ->set_output_reported_fault(output_reported_fault(bytes, length)); + chassis->mutable_lexus() + ->mutable_cruise_control_buttons_rpt_208() + ->set_input_output_fault(input_output_fault(bytes, length)); + chassis->mutable_lexus() + ->mutable_cruise_control_buttons_rpt_208() + ->set_enabled(enabled(bytes, length)); + chassis->mutable_lexus() + ->mutable_cruise_control_buttons_rpt_208() + ->set_command_output_fault(command_output_fault(bytes, length)); } // config detail: {'name': 'output_value', 'enum': {0: diff --git a/modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_rpt_208.h b/modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_rpt_208.h similarity index 97% rename from modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_rpt_208.h rename to modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_rpt_208.h index 6fe1b0b9e84..63ab0ad627b 100644 --- a/modules/canbus_vehicle/lexus/protocol/cruise_control_buttons_rpt_208.h +++ b/modules/canbus/vehicle/lexus/protocol/cruise_control_buttons_rpt_208.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,12 +25,12 @@ namespace lexus { class Cruisecontrolbuttonsrpt208 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Cruisecontrolbuttonsrpt208(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'OUTPUT_VALUE', 'enum': {0: diff --git a/modules/canbus_vehicle/lexus/protocol/dash_controls_left_cmd_10c.cc b/modules/canbus/vehicle/lexus/protocol/dash_controls_left_cmd_10c.cc similarity index 84% rename from modules/canbus_vehicle/lexus/protocol/dash_controls_left_cmd_10c.cc rename to modules/canbus/vehicle/lexus/protocol/dash_controls_left_cmd_10c.cc index cc8ed0d00cb..c6bda62d7e2 100644 --- a/modules/canbus_vehicle/lexus/protocol/dash_controls_left_cmd_10c.cc +++ b/modules/canbus/vehicle/lexus/protocol/dash_controls_left_cmd_10c.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/dash_controls_left_cmd_10c.h" +#include "modules/canbus/vehicle/lexus/protocol/dash_controls_left_cmd_10c.h" #include "glog/logging.h" @@ -31,17 +31,21 @@ Dashcontrolsleftcmd10c::Dashcontrolsleftcmd10c() {} const int32_t Dashcontrolsleftcmd10c::ID = 0x10C; void Dashcontrolsleftcmd10c::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_dash_controls_left_cmd_10c()->set_ignore_overrides( - ignore_overrides(bytes, length)); - chassis->mutable_dash_controls_left_cmd_10c()->set_enable( + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_dash_controls_left_cmd_10c() + ->set_ignore_overrides(ignore_overrides(bytes, length)); + chassis->mutable_lexus()->mutable_dash_controls_left_cmd_10c()->set_enable( enable(bytes, length)); - chassis->mutable_dash_controls_left_cmd_10c()->set_clear_override( - clear_override(bytes, length)); - chassis->mutable_dash_controls_left_cmd_10c()->set_clear_faults( - clear_faults(bytes, length)); - chassis->mutable_dash_controls_left_cmd_10c()->set_dash_controls_button( - dash_controls_button(bytes, length)); + chassis->mutable_lexus() + ->mutable_dash_controls_left_cmd_10c() + ->set_clear_override(clear_override(bytes, length)); + chassis->mutable_lexus() + ->mutable_dash_controls_left_cmd_10c() + ->set_clear_faults(clear_faults(bytes, length)); + chassis->mutable_lexus() + ->mutable_dash_controls_left_cmd_10c() + ->set_dash_controls_button(dash_controls_button(bytes, length)); } // config detail: {'name': 'ignore_overrides', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/dash_controls_left_cmd_10c.h b/modules/canbus/vehicle/lexus/protocol/dash_controls_left_cmd_10c.h similarity index 94% rename from modules/canbus_vehicle/lexus/protocol/dash_controls_left_cmd_10c.h rename to modules/canbus/vehicle/lexus/protocol/dash_controls_left_cmd_10c.h index 48decacb7a5..9effaa814e7 100644 --- a/modules/canbus_vehicle/lexus/protocol/dash_controls_left_cmd_10c.h +++ b/modules/canbus/vehicle/lexus/protocol/dash_controls_left_cmd_10c.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Dashcontrolsleftcmd10c : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Dashcontrolsleftcmd10c(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'IGNORE_OVERRIDES', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/dash_controls_left_rpt_20c.cc b/modules/canbus/vehicle/lexus/protocol/dash_controls_left_rpt_20c.cc similarity index 83% rename from modules/canbus_vehicle/lexus/protocol/dash_controls_left_rpt_20c.cc rename to modules/canbus/vehicle/lexus/protocol/dash_controls_left_rpt_20c.cc index efbd4ae0d40..9a4cdea0797 100644 --- a/modules/canbus_vehicle/lexus/protocol/dash_controls_left_rpt_20c.cc +++ b/modules/canbus/vehicle/lexus/protocol/dash_controls_left_rpt_20c.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/dash_controls_left_rpt_20c.h" +#include "modules/canbus/vehicle/lexus/protocol/dash_controls_left_rpt_20c.h" #include "glog/logging.h" @@ -31,27 +31,36 @@ Dashcontrolsleftrpt20c::Dashcontrolsleftrpt20c() {} const int32_t Dashcontrolsleftrpt20c::ID = 0x20C; void Dashcontrolsleftrpt20c::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_dash_controls_left_rpt_20c()->set_output_value( - output_value(bytes, length)); - chassis->mutable_dash_controls_left_rpt_20c()->set_commanded_value( - commanded_value(bytes, length)); - chassis->mutable_dash_controls_left_rpt_20c()->set_manual_input( - manual_input(bytes, length)); - chassis->mutable_dash_controls_left_rpt_20c()->set_vehicle_fault( - vehicle_fault(bytes, length)); - chassis->mutable_dash_controls_left_rpt_20c()->set_pacmod_fault( - pacmod_fault(bytes, length)); - chassis->mutable_dash_controls_left_rpt_20c()->set_override_active( - override_active(bytes, length)); - chassis->mutable_dash_controls_left_rpt_20c()->set_output_reported_fault( - output_reported_fault(bytes, length)); - chassis->mutable_dash_controls_left_rpt_20c()->set_input_output_fault( - input_output_fault(bytes, length)); - chassis->mutable_dash_controls_left_rpt_20c()->set_enabled( + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_dash_controls_left_rpt_20c() + ->set_output_value(output_value(bytes, length)); + chassis->mutable_lexus() + ->mutable_dash_controls_left_rpt_20c() + ->set_commanded_value(commanded_value(bytes, length)); + chassis->mutable_lexus() + ->mutable_dash_controls_left_rpt_20c() + ->set_manual_input(manual_input(bytes, length)); + chassis->mutable_lexus() + ->mutable_dash_controls_left_rpt_20c() + ->set_vehicle_fault(vehicle_fault(bytes, length)); + chassis->mutable_lexus() + ->mutable_dash_controls_left_rpt_20c() + ->set_pacmod_fault(pacmod_fault(bytes, length)); + chassis->mutable_lexus() + ->mutable_dash_controls_left_rpt_20c() + ->set_override_active(override_active(bytes, length)); + chassis->mutable_lexus() + ->mutable_dash_controls_left_rpt_20c() + ->set_output_reported_fault(output_reported_fault(bytes, length)); + chassis->mutable_lexus() + ->mutable_dash_controls_left_rpt_20c() + ->set_input_output_fault(input_output_fault(bytes, length)); + chassis->mutable_lexus()->mutable_dash_controls_left_rpt_20c()->set_enabled( enabled(bytes, length)); - chassis->mutable_dash_controls_left_rpt_20c()->set_command_output_fault( - command_output_fault(bytes, length)); + chassis->mutable_lexus() + ->mutable_dash_controls_left_rpt_20c() + ->set_command_output_fault(command_output_fault(bytes, length)); } // config detail: {'name': 'output_value', 'enum': {0: diff --git a/modules/canbus_vehicle/lexus/protocol/dash_controls_left_rpt_20c.h b/modules/canbus/vehicle/lexus/protocol/dash_controls_left_rpt_20c.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/dash_controls_left_rpt_20c.h rename to modules/canbus/vehicle/lexus/protocol/dash_controls_left_rpt_20c.h index 8ffffa74336..65e9e5b80ca 100644 --- a/modules/canbus_vehicle/lexus/protocol/dash_controls_left_rpt_20c.h +++ b/modules/canbus/vehicle/lexus/protocol/dash_controls_left_rpt_20c.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Dashcontrolsleftrpt20c : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Dashcontrolsleftrpt20c(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'OUTPUT_VALUE', 'enum': {0: diff --git a/modules/canbus_vehicle/lexus/protocol/dash_controls_right_cmd_110.cc b/modules/canbus/vehicle/lexus/protocol/dash_controls_right_cmd_110.cc similarity index 84% rename from modules/canbus_vehicle/lexus/protocol/dash_controls_right_cmd_110.cc rename to modules/canbus/vehicle/lexus/protocol/dash_controls_right_cmd_110.cc index 350d0babcb0..dce54fe0e25 100644 --- a/modules/canbus_vehicle/lexus/protocol/dash_controls_right_cmd_110.cc +++ b/modules/canbus/vehicle/lexus/protocol/dash_controls_right_cmd_110.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/dash_controls_right_cmd_110.h" +#include "modules/canbus/vehicle/lexus/protocol/dash_controls_right_cmd_110.h" #include "glog/logging.h" @@ -31,17 +31,21 @@ Dashcontrolsrightcmd110::Dashcontrolsrightcmd110() {} const int32_t Dashcontrolsrightcmd110::ID = 0x110; void Dashcontrolsrightcmd110::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_dash_controls_right_cmd_110()->set_ignore_overrides( - ignore_overrides(bytes, length)); - chassis->mutable_dash_controls_right_cmd_110()->set_enable( + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_dash_controls_right_cmd_110() + ->set_ignore_overrides(ignore_overrides(bytes, length)); + chassis->mutable_lexus()->mutable_dash_controls_right_cmd_110()->set_enable( enable(bytes, length)); - chassis->mutable_dash_controls_right_cmd_110()->set_clear_override( - clear_override(bytes, length)); - chassis->mutable_dash_controls_right_cmd_110()->set_clear_faults( - clear_faults(bytes, length)); - chassis->mutable_dash_controls_right_cmd_110()->set_dash_controls_button( - dash_controls_button(bytes, length)); + chassis->mutable_lexus() + ->mutable_dash_controls_right_cmd_110() + ->set_clear_override(clear_override(bytes, length)); + chassis->mutable_lexus() + ->mutable_dash_controls_right_cmd_110() + ->set_clear_faults(clear_faults(bytes, length)); + chassis->mutable_lexus() + ->mutable_dash_controls_right_cmd_110() + ->set_dash_controls_button(dash_controls_button(bytes, length)); } // config detail: {'name': 'ignore_overrides', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/dash_controls_right_cmd_110.h b/modules/canbus/vehicle/lexus/protocol/dash_controls_right_cmd_110.h similarity index 94% rename from modules/canbus_vehicle/lexus/protocol/dash_controls_right_cmd_110.h rename to modules/canbus/vehicle/lexus/protocol/dash_controls_right_cmd_110.h index ff7809b82a4..9f96e3761b7 100644 --- a/modules/canbus_vehicle/lexus/protocol/dash_controls_right_cmd_110.h +++ b/modules/canbus/vehicle/lexus/protocol/dash_controls_right_cmd_110.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Dashcontrolsrightcmd110 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Dashcontrolsrightcmd110(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'IGNORE_OVERRIDES', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/dash_controls_right_rpt_210.cc b/modules/canbus/vehicle/lexus/protocol/dash_controls_right_rpt_210.cc similarity index 99% rename from modules/canbus_vehicle/lexus/protocol/dash_controls_right_rpt_210.cc rename to modules/canbus/vehicle/lexus/protocol/dash_controls_right_rpt_210.cc index 49769eb4322..79f5c209eb7 100644 --- a/modules/canbus_vehicle/lexus/protocol/dash_controls_right_rpt_210.cc +++ b/modules/canbus/vehicle/lexus/protocol/dash_controls_right_rpt_210.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/dash_controls_right_rpt_210.h" +#include "modules/canbus/vehicle/lexus/protocol/dash_controls_right_rpt_210.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lexus/protocol/dash_controls_right_rpt_210.h b/modules/canbus/vehicle/lexus/protocol/dash_controls_right_rpt_210.h similarity index 98% rename from modules/canbus_vehicle/lexus/protocol/dash_controls_right_rpt_210.h rename to modules/canbus/vehicle/lexus/protocol/dash_controls_right_rpt_210.h index e05bd07d473..8f88b4df3cb 100644 --- a/modules/canbus_vehicle/lexus/protocol/dash_controls_right_rpt_210.h +++ b/modules/canbus/vehicle/lexus/protocol/dash_controls_right_rpt_210.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace lexus { class Dashcontrolsrightrpt210 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lexus/protocol/date_time_rpt_40f.cc b/modules/canbus/vehicle/lexus/protocol/date_time_rpt_40f.cc similarity index 87% rename from modules/canbus_vehicle/lexus/protocol/date_time_rpt_40f.cc rename to modules/canbus/vehicle/lexus/protocol/date_time_rpt_40f.cc index 32462ed143a..6d4860696a5 100644 --- a/modules/canbus_vehicle/lexus/protocol/date_time_rpt_40f.cc +++ b/modules/canbus/vehicle/lexus/protocol/date_time_rpt_40f.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/date_time_rpt_40f.h" +#include "modules/canbus/vehicle/lexus/protocol/date_time_rpt_40f.h" #include "glog/logging.h" @@ -31,18 +31,18 @@ Datetimerpt40f::Datetimerpt40f() {} const int32_t Datetimerpt40f::ID = 0x40F; void Datetimerpt40f::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_date_time_rpt_40f()->set_time_second( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_date_time_rpt_40f()->set_time_second( time_second(bytes, length)); - chassis->mutable_date_time_rpt_40f()->set_time_minute( + chassis->mutable_lexus()->mutable_date_time_rpt_40f()->set_time_minute( time_minute(bytes, length)); - chassis->mutable_date_time_rpt_40f()->set_time_hour( + chassis->mutable_lexus()->mutable_date_time_rpt_40f()->set_time_hour( time_hour(bytes, length)); - chassis->mutable_date_time_rpt_40f()->set_date_day( + chassis->mutable_lexus()->mutable_date_time_rpt_40f()->set_date_day( date_day(bytes, length)); - chassis->mutable_date_time_rpt_40f()->set_date_month( + chassis->mutable_lexus()->mutable_date_time_rpt_40f()->set_date_month( date_month(bytes, length)); - chassis->mutable_date_time_rpt_40f()->set_date_year( + chassis->mutable_lexus()->mutable_date_time_rpt_40f()->set_date_year( date_year(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/date_time_rpt_40f.h b/modules/canbus/vehicle/lexus/protocol/date_time_rpt_40f.h similarity index 94% rename from modules/canbus_vehicle/lexus/protocol/date_time_rpt_40f.h rename to modules/canbus/vehicle/lexus/protocol/date_time_rpt_40f.h index 8c9b110e6a7..466296648c5 100644 --- a/modules/canbus_vehicle/lexus/protocol/date_time_rpt_40f.h +++ b/modules/canbus/vehicle/lexus/protocol/date_time_rpt_40f.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Datetimerpt40f : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Datetimerpt40f(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'TIME_SECOND', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/detected_object_rpt_411.cc b/modules/canbus/vehicle/lexus/protocol/detected_object_rpt_411.cc similarity index 87% rename from modules/canbus_vehicle/lexus/protocol/detected_object_rpt_411.cc rename to modules/canbus/vehicle/lexus/protocol/detected_object_rpt_411.cc index 13428a94267..7da0b52a001 100644 --- a/modules/canbus_vehicle/lexus/protocol/detected_object_rpt_411.cc +++ b/modules/canbus/vehicle/lexus/protocol/detected_object_rpt_411.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/detected_object_rpt_411.h" +#include "modules/canbus/vehicle/lexus/protocol/detected_object_rpt_411.h" #include "glog/logging.h" @@ -31,12 +31,15 @@ Detectedobjectrpt411::Detectedobjectrpt411() {} const int32_t Detectedobjectrpt411::ID = 0x411; void Detectedobjectrpt411::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_detected_object_rpt_411() + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_detected_object_rpt_411() ->set_front_object_distance_high_res( front_object_distance_high_res(bytes, length)); - chassis->mutable_detected_object_rpt_411()->set_front_object_distance_low_res( - front_object_distance_low_res(bytes, length)); + chassis->mutable_lexus() + ->mutable_detected_object_rpt_411() + ->set_front_object_distance_low_res( + front_object_distance_low_res(bytes, length)); } // config detail: {'name': 'front_object_distance_high_res', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/detected_object_rpt_411.h b/modules/canbus/vehicle/lexus/protocol/detected_object_rpt_411.h similarity index 91% rename from modules/canbus_vehicle/lexus/protocol/detected_object_rpt_411.h rename to modules/canbus/vehicle/lexus/protocol/detected_object_rpt_411.h index 8aa6593dad1..371848a98d3 100644 --- a/modules/canbus_vehicle/lexus/protocol/detected_object_rpt_411.h +++ b/modules/canbus/vehicle/lexus/protocol/detected_object_rpt_411.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Detectedobjectrpt411 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Detectedobjectrpt411(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'FRONT_OBJECT_DISTANCE_HIGH_RES', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/door_rpt_417.cc b/modules/canbus/vehicle/lexus/protocol/door_rpt_417.cc similarity index 84% rename from modules/canbus_vehicle/lexus/protocol/door_rpt_417.cc rename to modules/canbus/vehicle/lexus/protocol/door_rpt_417.cc index bc47f66c934..01f5775501a 100644 --- a/modules/canbus_vehicle/lexus/protocol/door_rpt_417.cc +++ b/modules/canbus/vehicle/lexus/protocol/door_rpt_417.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/door_rpt_417.h" +#include "modules/canbus/vehicle/lexus/protocol/door_rpt_417.h" #include "glog/logging.h" @@ -31,34 +31,39 @@ Doorrpt417::Doorrpt417() {} const int32_t Doorrpt417::ID = 0x417; void Doorrpt417::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_door_rpt_417()->set_fuel_door_open_is_valid( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_door_rpt_417()->set_fuel_door_open_is_valid( fuel_door_open_is_valid(bytes, length)); - chassis->mutable_door_rpt_417()->set_trunk_open_is_valid( + chassis->mutable_lexus()->mutable_door_rpt_417()->set_trunk_open_is_valid( trunk_open_is_valid(bytes, length)); - chassis->mutable_door_rpt_417()->set_hood_open_is_valid( + chassis->mutable_lexus()->mutable_door_rpt_417()->set_hood_open_is_valid( hood_open_is_valid(bytes, length)); - chassis->mutable_door_rpt_417()->set_rear_pass_door_open_is_valid( - rear_pass_door_open_is_valid(bytes, length)); - chassis->mutable_door_rpt_417()->set_rear_driver_door_open_is_valid( - rear_driver_door_open_is_valid(bytes, length)); - chassis->mutable_door_rpt_417()->set_pass_door_open_is_valid( + chassis->mutable_lexus() + ->mutable_door_rpt_417() + ->set_rear_pass_door_open_is_valid( + rear_pass_door_open_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_door_rpt_417() + ->set_rear_driver_door_open_is_valid( + rear_driver_door_open_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_door_rpt_417()->set_pass_door_open_is_valid( pass_door_open_is_valid(bytes, length)); - chassis->mutable_door_rpt_417()->set_driver_door_open_is_valid( - driver_door_open_is_valid(bytes, length)); - chassis->mutable_door_rpt_417()->set_fuel_door_open( + chassis->mutable_lexus() + ->mutable_door_rpt_417() + ->set_driver_door_open_is_valid(driver_door_open_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_door_rpt_417()->set_fuel_door_open( fuel_door_open(bytes, length)); - chassis->mutable_door_rpt_417()->set_trunk_open( + chassis->mutable_lexus()->mutable_door_rpt_417()->set_trunk_open( trunk_open(bytes, length)); - chassis->mutable_door_rpt_417()->set_hood_open( + chassis->mutable_lexus()->mutable_door_rpt_417()->set_hood_open( hood_open(bytes, length)); - chassis->mutable_door_rpt_417()->set_rear_pass_door_open( + chassis->mutable_lexus()->mutable_door_rpt_417()->set_rear_pass_door_open( rear_pass_door_open(bytes, length)); - chassis->mutable_door_rpt_417()->set_rear_driver_door_open( + chassis->mutable_lexus()->mutable_door_rpt_417()->set_rear_driver_door_open( rear_driver_door_open(bytes, length)); - chassis->mutable_door_rpt_417()->set_pass_door_open( + chassis->mutable_lexus()->mutable_door_rpt_417()->set_pass_door_open( pass_door_open(bytes, length)); - chassis->mutable_door_rpt_417()->set_driver_door_open( + chassis->mutable_lexus()->mutable_door_rpt_417()->set_driver_door_open( driver_door_open(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/door_rpt_417.h b/modules/canbus/vehicle/lexus/protocol/door_rpt_417.h similarity index 97% rename from modules/canbus_vehicle/lexus/protocol/door_rpt_417.h rename to modules/canbus/vehicle/lexus/protocol/door_rpt_417.h index f4525010cde..8e0ceab7835 100644 --- a/modules/canbus_vehicle/lexus/protocol/door_rpt_417.h +++ b/modules/canbus/vehicle/lexus/protocol/door_rpt_417.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Doorrpt417 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Doorrpt417(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'FUEL_DOOR_OPEN_IS_VALID', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/global_rpt_10.cc b/modules/canbus/vehicle/lexus/protocol/global_rpt_10.cc similarity index 85% rename from modules/canbus_vehicle/lexus/protocol/global_rpt_10.cc rename to modules/canbus/vehicle/lexus/protocol/global_rpt_10.cc index 6ebb73d8225..a4e60621ee1 100644 --- a/modules/canbus_vehicle/lexus/protocol/global_rpt_10.cc +++ b/modules/canbus/vehicle/lexus/protocol/global_rpt_10.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/global_rpt_10.h" +#include "modules/canbus/vehicle/lexus/protocol/global_rpt_10.h" #include "glog/logging.h" @@ -31,26 +31,31 @@ Globalrpt10::Globalrpt10() {} const int32_t Globalrpt10::ID = 0x10; void Globalrpt10::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_global_rpt_10()->set_config_fault_active( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_global_rpt_10()->set_config_fault_active( config_fault_active(bytes, length)); - chassis->mutable_global_rpt_10()->set_pacmod_subsystem_timeout( - pacmod_subsystem_timeout(bytes, length)); - chassis->mutable_global_rpt_10()->set_pacmod_system_enabled( + chassis->mutable_lexus() + ->mutable_global_rpt_10() + ->set_pacmod_subsystem_timeout(pacmod_subsystem_timeout(bytes, length)); + chassis->mutable_lexus()->mutable_global_rpt_10()->set_pacmod_system_enabled( pacmod_system_enabled(bytes, length)); - chassis->mutable_global_rpt_10()->set_pacmod_system_override_active( - pacmod_system_override_active(bytes, length)); - chassis->mutable_global_rpt_10()->set_pacmod_system_fault_active( - pacmod_system_fault_active(bytes, length)); - chassis->mutable_global_rpt_10()->set_veh_can_timeout( + chassis->mutable_lexus() + ->mutable_global_rpt_10() + ->set_pacmod_system_override_active( + pacmod_system_override_active(bytes, length)); + chassis->mutable_lexus() + ->mutable_global_rpt_10() + ->set_pacmod_system_fault_active( + pacmod_system_fault_active(bytes, length)); + chassis->mutable_lexus()->mutable_global_rpt_10()->set_veh_can_timeout( veh_can_timeout(bytes, length)); - chassis->mutable_global_rpt_10()->set_str_can_timeout( + chassis->mutable_lexus()->mutable_global_rpt_10()->set_str_can_timeout( str_can_timeout(bytes, length)); - chassis->mutable_global_rpt_10()->set_brk_can_timeout( + chassis->mutable_lexus()->mutable_global_rpt_10()->set_brk_can_timeout( brk_can_timeout(bytes, length)); - chassis->mutable_global_rpt_10()->set_usr_can_timeout( + chassis->mutable_lexus()->mutable_global_rpt_10()->set_usr_can_timeout( usr_can_timeout(bytes, length)); - chassis->mutable_global_rpt_10()->set_usr_can_read_errors( + chassis->mutable_lexus()->mutable_global_rpt_10()->set_usr_can_read_errors( usr_can_read_errors(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/global_rpt_10.h b/modules/canbus/vehicle/lexus/protocol/global_rpt_10.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/global_rpt_10.h rename to modules/canbus/vehicle/lexus/protocol/global_rpt_10.h index 29663d2cfce..f08b122694b 100644 --- a/modules/canbus_vehicle/lexus/protocol/global_rpt_10.h +++ b/modules/canbus/vehicle/lexus/protocol/global_rpt_10.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Globalrpt10 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Globalrpt10(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'CONFIG_FAULT_ACTIVE', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/hazard_lights_cmd_114.cc b/modules/canbus/vehicle/lexus/protocol/hazard_lights_cmd_114.cc similarity index 98% rename from modules/canbus_vehicle/lexus/protocol/hazard_lights_cmd_114.cc rename to modules/canbus/vehicle/lexus/protocol/hazard_lights_cmd_114.cc index ee1c07e6922..6085aa7bdcd 100644 --- a/modules/canbus_vehicle/lexus/protocol/hazard_lights_cmd_114.cc +++ b/modules/canbus/vehicle/lexus/protocol/hazard_lights_cmd_114.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/hazard_lights_cmd_114.h" +#include "modules/canbus/vehicle/lexus/protocol/hazard_lights_cmd_114.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lexus/protocol/hazard_lights_cmd_114.h b/modules/canbus/vehicle/lexus/protocol/hazard_lights_cmd_114.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/hazard_lights_cmd_114.h rename to modules/canbus/vehicle/lexus/protocol/hazard_lights_cmd_114.h index 2e556623045..e11600833bd 100644 --- a/modules/canbus_vehicle/lexus/protocol/hazard_lights_cmd_114.h +++ b/modules/canbus/vehicle/lexus/protocol/hazard_lights_cmd_114.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace lexus { class Hazardlightscmd114 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lexus/protocol/hazard_lights_rpt_214.cc b/modules/canbus/vehicle/lexus/protocol/hazard_lights_rpt_214.cc similarity index 82% rename from modules/canbus_vehicle/lexus/protocol/hazard_lights_rpt_214.cc rename to modules/canbus/vehicle/lexus/protocol/hazard_lights_rpt_214.cc index f07a56a2b3c..e1783ec2e2e 100644 --- a/modules/canbus_vehicle/lexus/protocol/hazard_lights_rpt_214.cc +++ b/modules/canbus/vehicle/lexus/protocol/hazard_lights_rpt_214.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/hazard_lights_rpt_214.h" +#include "modules/canbus/vehicle/lexus/protocol/hazard_lights_rpt_214.h" #include "glog/logging.h" @@ -31,27 +31,32 @@ Hazardlightsrpt214::Hazardlightsrpt214() {} const int32_t Hazardlightsrpt214::ID = 0x214; void Hazardlightsrpt214::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_hazard_lights_rpt_214()->set_output_value( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_hazard_lights_rpt_214()->set_output_value( output_value(bytes, length)); - chassis->mutable_hazard_lights_rpt_214()->set_commanded_value( - commanded_value(bytes, length)); - chassis->mutable_hazard_lights_rpt_214()->set_manual_input( + chassis->mutable_lexus() + ->mutable_hazard_lights_rpt_214() + ->set_commanded_value(commanded_value(bytes, length)); + chassis->mutable_lexus()->mutable_hazard_lights_rpt_214()->set_manual_input( manual_input(bytes, length)); - chassis->mutable_hazard_lights_rpt_214()->set_vehicle_fault( + chassis->mutable_lexus()->mutable_hazard_lights_rpt_214()->set_vehicle_fault( vehicle_fault(bytes, length)); - chassis->mutable_hazard_lights_rpt_214()->set_pacmod_fault( + chassis->mutable_lexus()->mutable_hazard_lights_rpt_214()->set_pacmod_fault( pacmod_fault(bytes, length)); - chassis->mutable_hazard_lights_rpt_214()->set_override_active( - override_active(bytes, length)); - chassis->mutable_hazard_lights_rpt_214()->set_output_reported_fault( - output_reported_fault(bytes, length)); - chassis->mutable_hazard_lights_rpt_214()->set_input_output_fault( - input_output_fault(bytes, length)); - chassis->mutable_hazard_lights_rpt_214()->set_enabled( + chassis->mutable_lexus() + ->mutable_hazard_lights_rpt_214() + ->set_override_active(override_active(bytes, length)); + chassis->mutable_lexus() + ->mutable_hazard_lights_rpt_214() + ->set_output_reported_fault(output_reported_fault(bytes, length)); + chassis->mutable_lexus() + ->mutable_hazard_lights_rpt_214() + ->set_input_output_fault(input_output_fault(bytes, length)); + chassis->mutable_lexus()->mutable_hazard_lights_rpt_214()->set_enabled( enabled(bytes, length)); - chassis->mutable_hazard_lights_rpt_214()->set_command_output_fault( - command_output_fault(bytes, length)); + chassis->mutable_lexus() + ->mutable_hazard_lights_rpt_214() + ->set_command_output_fault(command_output_fault(bytes, length)); } // config detail: {'name': 'output_value', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/hazard_lights_rpt_214.h b/modules/canbus/vehicle/lexus/protocol/hazard_lights_rpt_214.h similarity index 95% rename from modules/canbus_vehicle/lexus/protocol/hazard_lights_rpt_214.h rename to modules/canbus/vehicle/lexus/protocol/hazard_lights_rpt_214.h index dd5b0c11674..208301d0490 100644 --- a/modules/canbus_vehicle/lexus/protocol/hazard_lights_rpt_214.h +++ b/modules/canbus/vehicle/lexus/protocol/hazard_lights_rpt_214.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Hazardlightsrpt214 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Hazardlightsrpt214(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'OUTPUT_VALUE', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/headlight_aux_rpt_318.cc b/modules/canbus/vehicle/lexus/protocol/headlight_aux_rpt_318.cc similarity index 81% rename from modules/canbus_vehicle/lexus/protocol/headlight_aux_rpt_318.cc rename to modules/canbus/vehicle/lexus/protocol/headlight_aux_rpt_318.cc index b44d0c6af24..599fb5de4b3 100644 --- a/modules/canbus_vehicle/lexus/protocol/headlight_aux_rpt_318.cc +++ b/modules/canbus/vehicle/lexus/protocol/headlight_aux_rpt_318.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/headlight_aux_rpt_318.h" +#include "modules/canbus/vehicle/lexus/protocol/headlight_aux_rpt_318.h" #include "glog/logging.h" @@ -31,22 +31,29 @@ Headlightauxrpt318::Headlightauxrpt318() {} const int32_t Headlightauxrpt318::ID = 0x318; void Headlightauxrpt318::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_headlight_aux_rpt_318()->set_headlights_mode_is_valid( - headlights_mode_is_valid(bytes, length)); - chassis->mutable_headlight_aux_rpt_318()->set_headlights_mode( - headlights_mode(bytes, length)); - chassis->mutable_headlight_aux_rpt_318()->set_fog_lights_on_is_valid( - fog_lights_on_is_valid(bytes, length)); - chassis->mutable_headlight_aux_rpt_318()->set_fog_lights_on( + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_headlight_aux_rpt_318() + ->set_headlights_mode_is_valid(headlights_mode_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_headlight_aux_rpt_318() + ->set_headlights_mode(headlights_mode(bytes, length)); + chassis->mutable_lexus() + ->mutable_headlight_aux_rpt_318() + ->set_fog_lights_on_is_valid(fog_lights_on_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_headlight_aux_rpt_318()->set_fog_lights_on( fog_lights_on(bytes, length)); - chassis->mutable_headlight_aux_rpt_318()->set_headlights_on_bright_is_valid( - headlights_on_bright_is_valid(bytes, length)); - chassis->mutable_headlight_aux_rpt_318()->set_headlights_on_bright( - headlights_on_bright(bytes, length)); - chassis->mutable_headlight_aux_rpt_318()->set_headlights_on_is_valid( - headlights_on_is_valid(bytes, length)); - chassis->mutable_headlight_aux_rpt_318()->set_headlights_on( + chassis->mutable_lexus() + ->mutable_headlight_aux_rpt_318() + ->set_headlights_on_bright_is_valid( + headlights_on_bright_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_headlight_aux_rpt_318() + ->set_headlights_on_bright(headlights_on_bright(bytes, length)); + chassis->mutable_lexus() + ->mutable_headlight_aux_rpt_318() + ->set_headlights_on_is_valid(headlights_on_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_headlight_aux_rpt_318()->set_headlights_on( headlights_on(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/headlight_aux_rpt_318.h b/modules/canbus/vehicle/lexus/protocol/headlight_aux_rpt_318.h similarity index 95% rename from modules/canbus_vehicle/lexus/protocol/headlight_aux_rpt_318.h rename to modules/canbus/vehicle/lexus/protocol/headlight_aux_rpt_318.h index 90ce119a20f..0eb2d6a70fd 100644 --- a/modules/canbus_vehicle/lexus/protocol/headlight_aux_rpt_318.h +++ b/modules/canbus/vehicle/lexus/protocol/headlight_aux_rpt_318.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Headlightauxrpt318 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Headlightauxrpt318(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'HEADLIGHTS_MODE_IS_VALID', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/headlight_cmd_118.cc b/modules/canbus/vehicle/lexus/protocol/headlight_cmd_118.cc similarity index 98% rename from modules/canbus_vehicle/lexus/protocol/headlight_cmd_118.cc rename to modules/canbus/vehicle/lexus/protocol/headlight_cmd_118.cc index 3349c89bda5..9b5c0f5bdb6 100644 --- a/modules/canbus_vehicle/lexus/protocol/headlight_cmd_118.cc +++ b/modules/canbus/vehicle/lexus/protocol/headlight_cmd_118.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/headlight_cmd_118.h" +#include "modules/canbus/vehicle/lexus/protocol/headlight_cmd_118.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lexus/protocol/headlight_cmd_118.h b/modules/canbus/vehicle/lexus/protocol/headlight_cmd_118.h similarity index 97% rename from modules/canbus_vehicle/lexus/protocol/headlight_cmd_118.h rename to modules/canbus/vehicle/lexus/protocol/headlight_cmd_118.h index 2d0c1d31d3b..8179ec62466 100644 --- a/modules/canbus_vehicle/lexus/protocol/headlight_cmd_118.h +++ b/modules/canbus/vehicle/lexus/protocol/headlight_cmd_118.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace lexus { class Headlightcmd118 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lexus/protocol/headlight_rpt_218.cc b/modules/canbus/vehicle/lexus/protocol/headlight_rpt_218.cc similarity index 86% rename from modules/canbus_vehicle/lexus/protocol/headlight_rpt_218.cc rename to modules/canbus/vehicle/lexus/protocol/headlight_rpt_218.cc index 3ebd1249ab3..83c6a8fa789 100644 --- a/modules/canbus_vehicle/lexus/protocol/headlight_rpt_218.cc +++ b/modules/canbus/vehicle/lexus/protocol/headlight_rpt_218.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/headlight_rpt_218.h" +#include "modules/canbus/vehicle/lexus/protocol/headlight_rpt_218.h" #include "glog/logging.h" @@ -31,26 +31,28 @@ Headlightrpt218::Headlightrpt218() {} const int32_t Headlightrpt218::ID = 0x218; void Headlightrpt218::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_headlight_rpt_218()->set_vehicle_fault( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_headlight_rpt_218()->set_vehicle_fault( vehicle_fault(bytes, length)); - chassis->mutable_headlight_rpt_218()->set_pacmod_fault( + chassis->mutable_lexus()->mutable_headlight_rpt_218()->set_pacmod_fault( pacmod_fault(bytes, length)); - chassis->mutable_headlight_rpt_218()->set_override_active( + chassis->mutable_lexus()->mutable_headlight_rpt_218()->set_override_active( override_active(bytes, length)); - chassis->mutable_headlight_rpt_218()->set_output_reported_fault( - output_reported_fault(bytes, length)); - chassis->mutable_headlight_rpt_218()->set_input_output_fault( + chassis->mutable_lexus() + ->mutable_headlight_rpt_218() + ->set_output_reported_fault(output_reported_fault(bytes, length)); + chassis->mutable_lexus()->mutable_headlight_rpt_218()->set_input_output_fault( input_output_fault(bytes, length)); - chassis->mutable_headlight_rpt_218()->set_enabled( + chassis->mutable_lexus()->mutable_headlight_rpt_218()->set_enabled( enabled(bytes, length)); - chassis->mutable_headlight_rpt_218()->set_command_output_fault( - command_output_fault(bytes, length)); - chassis->mutable_headlight_rpt_218()->set_output_value( + chassis->mutable_lexus() + ->mutable_headlight_rpt_218() + ->set_command_output_fault(command_output_fault(bytes, length)); + chassis->mutable_lexus()->mutable_headlight_rpt_218()->set_output_value( output_value(bytes, length)); - chassis->mutable_headlight_rpt_218()->set_manual_input( + chassis->mutable_lexus()->mutable_headlight_rpt_218()->set_manual_input( manual_input(bytes, length)); - chassis->mutable_headlight_rpt_218()->set_commanded_value( + chassis->mutable_lexus()->mutable_headlight_rpt_218()->set_commanded_value( commanded_value(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/headlight_rpt_218.h b/modules/canbus/vehicle/lexus/protocol/headlight_rpt_218.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/headlight_rpt_218.h rename to modules/canbus/vehicle/lexus/protocol/headlight_rpt_218.h index 15ec2685f61..bad412e3df7 100644 --- a/modules/canbus_vehicle/lexus/protocol/headlight_rpt_218.h +++ b/modules/canbus/vehicle/lexus/protocol/headlight_rpt_218.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Headlightrpt218 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Headlightrpt218(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VEHICLE_FAULT', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/horn_cmd_11c.cc b/modules/canbus/vehicle/lexus/protocol/horn_cmd_11c.cc similarity index 98% rename from modules/canbus_vehicle/lexus/protocol/horn_cmd_11c.cc rename to modules/canbus/vehicle/lexus/protocol/horn_cmd_11c.cc index 7061bba4962..46ee7959447 100644 --- a/modules/canbus_vehicle/lexus/protocol/horn_cmd_11c.cc +++ b/modules/canbus/vehicle/lexus/protocol/horn_cmd_11c.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/horn_cmd_11c.h" +#include "modules/canbus/vehicle/lexus/protocol/horn_cmd_11c.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lexus/protocol/horn_cmd_11c.h b/modules/canbus/vehicle/lexus/protocol/horn_cmd_11c.h similarity index 97% rename from modules/canbus_vehicle/lexus/protocol/horn_cmd_11c.h rename to modules/canbus/vehicle/lexus/protocol/horn_cmd_11c.h index 8076d9369dd..2ae42061d2b 100644 --- a/modules/canbus_vehicle/lexus/protocol/horn_cmd_11c.h +++ b/modules/canbus/vehicle/lexus/protocol/horn_cmd_11c.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace lexus { class Horncmd11c : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lexus/protocol/horn_rpt_21c.cc b/modules/canbus/vehicle/lexus/protocol/horn_rpt_21c.cc similarity index 87% rename from modules/canbus_vehicle/lexus/protocol/horn_rpt_21c.cc rename to modules/canbus/vehicle/lexus/protocol/horn_rpt_21c.cc index 909c03fb613..73d24b7e32b 100644 --- a/modules/canbus_vehicle/lexus/protocol/horn_rpt_21c.cc +++ b/modules/canbus/vehicle/lexus/protocol/horn_rpt_21c.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/horn_rpt_21c.h" +#include "modules/canbus/vehicle/lexus/protocol/horn_rpt_21c.h" #include "glog/logging.h" @@ -31,26 +31,26 @@ Hornrpt21c::Hornrpt21c() {} const int32_t Hornrpt21c::ID = 0x21C; void Hornrpt21c::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_horn_rpt_21c()->set_vehicle_fault( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_horn_rpt_21c()->set_vehicle_fault( vehicle_fault(bytes, length)); - chassis->mutable_horn_rpt_21c()->set_pacmod_fault( + chassis->mutable_lexus()->mutable_horn_rpt_21c()->set_pacmod_fault( pacmod_fault(bytes, length)); - chassis->mutable_horn_rpt_21c()->set_override_active( + chassis->mutable_lexus()->mutable_horn_rpt_21c()->set_override_active( override_active(bytes, length)); - chassis->mutable_horn_rpt_21c()->set_output_reported_fault( + chassis->mutable_lexus()->mutable_horn_rpt_21c()->set_output_reported_fault( output_reported_fault(bytes, length)); - chassis->mutable_horn_rpt_21c()->set_input_output_fault( + chassis->mutable_lexus()->mutable_horn_rpt_21c()->set_input_output_fault( input_output_fault(bytes, length)); - chassis->mutable_horn_rpt_21c()->set_enabled( + chassis->mutable_lexus()->mutable_horn_rpt_21c()->set_enabled( enabled(bytes, length)); - chassis->mutable_horn_rpt_21c()->set_command_output_fault( + chassis->mutable_lexus()->mutable_horn_rpt_21c()->set_command_output_fault( command_output_fault(bytes, length)); - chassis->mutable_horn_rpt_21c()->set_output_value( + chassis->mutable_lexus()->mutable_horn_rpt_21c()->set_output_value( output_value(bytes, length)); - chassis->mutable_horn_rpt_21c()->set_commanded_value( + chassis->mutable_lexus()->mutable_horn_rpt_21c()->set_commanded_value( commanded_value(bytes, length)); - chassis->mutable_horn_rpt_21c()->set_manual_input( + chassis->mutable_lexus()->mutable_horn_rpt_21c()->set_manual_input( manual_input(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/horn_rpt_21c.h b/modules/canbus/vehicle/lexus/protocol/horn_rpt_21c.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/horn_rpt_21c.h rename to modules/canbus/vehicle/lexus/protocol/horn_rpt_21c.h index 0e40b344659..52bcf069f27 100644 --- a/modules/canbus_vehicle/lexus/protocol/horn_rpt_21c.h +++ b/modules/canbus/vehicle/lexus/protocol/horn_rpt_21c.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Hornrpt21c : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Hornrpt21c(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VEHICLE_FAULT', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/interior_lights_rpt_416.cc b/modules/canbus/vehicle/lexus/protocol/interior_lights_rpt_416.cc similarity index 81% rename from modules/canbus_vehicle/lexus/protocol/interior_lights_rpt_416.cc rename to modules/canbus/vehicle/lexus/protocol/interior_lights_rpt_416.cc index 3447e977086..a58ecd87828 100644 --- a/modules/canbus_vehicle/lexus/protocol/interior_lights_rpt_416.cc +++ b/modules/canbus/vehicle/lexus/protocol/interior_lights_rpt_416.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/interior_lights_rpt_416.h" +#include "modules/canbus/vehicle/lexus/protocol/interior_lights_rpt_416.h" #include "glog/logging.h" @@ -31,23 +31,32 @@ Interiorlightsrpt416::Interiorlightsrpt416() {} const int32_t Interiorlightsrpt416::ID = 0x416; void Interiorlightsrpt416::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_interior_lights_rpt_416()->set_dim_level_is_valid( - dim_level_is_valid(bytes, length)); - chassis->mutable_interior_lights_rpt_416()->set_mood_lights_on_is_valid( - mood_lights_on_is_valid(bytes, length)); - chassis->mutable_interior_lights_rpt_416()->set_rear_dome_lights_on_is_valid( - rear_dome_lights_on_is_valid(bytes, length)); - chassis->mutable_interior_lights_rpt_416()->set_front_dome_lights_on_is_valid( - front_dome_lights_on_is_valid(bytes, length)); - chassis->mutable_interior_lights_rpt_416()->set_dim_level( + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_interior_lights_rpt_416() + ->set_dim_level_is_valid(dim_level_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_interior_lights_rpt_416() + ->set_mood_lights_on_is_valid(mood_lights_on_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_interior_lights_rpt_416() + ->set_rear_dome_lights_on_is_valid( + rear_dome_lights_on_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_interior_lights_rpt_416() + ->set_front_dome_lights_on_is_valid( + front_dome_lights_on_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_interior_lights_rpt_416()->set_dim_level( dim_level(bytes, length)); - chassis->mutable_interior_lights_rpt_416()->set_mood_lights_on( - mood_lights_on(bytes, length)); - chassis->mutable_interior_lights_rpt_416()->set_rear_dome_lights_on( - rear_dome_lights_on(bytes, length)); - chassis->mutable_interior_lights_rpt_416()->set_front_dome_lights_on( - front_dome_lights_on(bytes, length)); + chassis->mutable_lexus() + ->mutable_interior_lights_rpt_416() + ->set_mood_lights_on(mood_lights_on(bytes, length)); + chassis->mutable_lexus() + ->mutable_interior_lights_rpt_416() + ->set_rear_dome_lights_on(rear_dome_lights_on(bytes, length)); + chassis->mutable_lexus() + ->mutable_interior_lights_rpt_416() + ->set_front_dome_lights_on(front_dome_lights_on(bytes, length)); } // config detail: {'name': 'dim_level_is_valid', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/interior_lights_rpt_416.h b/modules/canbus/vehicle/lexus/protocol/interior_lights_rpt_416.h similarity index 95% rename from modules/canbus_vehicle/lexus/protocol/interior_lights_rpt_416.h rename to modules/canbus/vehicle/lexus/protocol/interior_lights_rpt_416.h index 5b014236077..9274069975b 100644 --- a/modules/canbus_vehicle/lexus/protocol/interior_lights_rpt_416.h +++ b/modules/canbus/vehicle/lexus/protocol/interior_lights_rpt_416.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Interiorlightsrpt416 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Interiorlightsrpt416(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'DIM_LEVEL_IS_VALID', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/lat_lon_heading_rpt_40e.cc b/modules/canbus/vehicle/lexus/protocol/lat_lon_heading_rpt_40e.cc similarity index 82% rename from modules/canbus_vehicle/lexus/protocol/lat_lon_heading_rpt_40e.cc rename to modules/canbus/vehicle/lexus/protocol/lat_lon_heading_rpt_40e.cc index d5d5e188f2b..289fd07dc3f 100644 --- a/modules/canbus_vehicle/lexus/protocol/lat_lon_heading_rpt_40e.cc +++ b/modules/canbus/vehicle/lexus/protocol/lat_lon_heading_rpt_40e.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/lat_lon_heading_rpt_40e.h" +#include "modules/canbus/vehicle/lexus/protocol/lat_lon_heading_rpt_40e.h" #include "glog/logging.h" @@ -31,21 +31,27 @@ Latlonheadingrpt40e::Latlonheadingrpt40e() {} const int32_t Latlonheadingrpt40e::ID = 0x40E; void Latlonheadingrpt40e::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_lat_lon_heading_rpt_40e()->set_heading( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_lat_lon_heading_rpt_40e()->set_heading( heading(bytes, length)); - chassis->mutable_lat_lon_heading_rpt_40e()->set_longitude_seconds( - longitude_seconds(bytes, length)); - chassis->mutable_lat_lon_heading_rpt_40e()->set_longitude_minutes( - longitude_minutes(bytes, length)); - chassis->mutable_lat_lon_heading_rpt_40e()->set_longitude_degrees( - longitude_degrees(bytes, length)); - chassis->mutable_lat_lon_heading_rpt_40e()->set_latitude_seconds( - latitude_seconds(bytes, length)); - chassis->mutable_lat_lon_heading_rpt_40e()->set_latitude_minutes( - latitude_minutes(bytes, length)); - chassis->mutable_lat_lon_heading_rpt_40e()->set_latitude_degrees( - latitude_degrees(bytes, length)); + chassis->mutable_lexus() + ->mutable_lat_lon_heading_rpt_40e() + ->set_longitude_seconds(longitude_seconds(bytes, length)); + chassis->mutable_lexus() + ->mutable_lat_lon_heading_rpt_40e() + ->set_longitude_minutes(longitude_minutes(bytes, length)); + chassis->mutable_lexus() + ->mutable_lat_lon_heading_rpt_40e() + ->set_longitude_degrees(longitude_degrees(bytes, length)); + chassis->mutable_lexus() + ->mutable_lat_lon_heading_rpt_40e() + ->set_latitude_seconds(latitude_seconds(bytes, length)); + chassis->mutable_lexus() + ->mutable_lat_lon_heading_rpt_40e() + ->set_latitude_minutes(latitude_minutes(bytes, length)); + chassis->mutable_lexus() + ->mutable_lat_lon_heading_rpt_40e() + ->set_latitude_degrees(latitude_degrees(bytes, length)); } // config detail: {'name': 'heading', 'offset': 0.0, 'precision': 0.01, 'len': diff --git a/modules/canbus_vehicle/lexus/protocol/lat_lon_heading_rpt_40e.h b/modules/canbus/vehicle/lexus/protocol/lat_lon_heading_rpt_40e.h similarity index 94% rename from modules/canbus_vehicle/lexus/protocol/lat_lon_heading_rpt_40e.h rename to modules/canbus/vehicle/lexus/protocol/lat_lon_heading_rpt_40e.h index c2e68d6f2a0..c2c7b72aee8 100644 --- a/modules/canbus_vehicle/lexus/protocol/lat_lon_heading_rpt_40e.h +++ b/modules/canbus/vehicle/lexus/protocol/lat_lon_heading_rpt_40e.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Latlonheadingrpt40e : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Latlonheadingrpt40e(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'HEADING', 'offset': 0.0, 'precision': 0.01, 'len': diff --git a/modules/canbus_vehicle/lexus/protocol/media_controls_cmd_120.cc b/modules/canbus/vehicle/lexus/protocol/media_controls_cmd_120.cc similarity index 85% rename from modules/canbus_vehicle/lexus/protocol/media_controls_cmd_120.cc rename to modules/canbus/vehicle/lexus/protocol/media_controls_cmd_120.cc index 05502c712de..b7edd09c2e9 100644 --- a/modules/canbus_vehicle/lexus/protocol/media_controls_cmd_120.cc +++ b/modules/canbus/vehicle/lexus/protocol/media_controls_cmd_120.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/media_controls_cmd_120.h" +#include "modules/canbus/vehicle/lexus/protocol/media_controls_cmd_120.h" #include "glog/logging.h" @@ -31,16 +31,19 @@ Mediacontrolscmd120::Mediacontrolscmd120() {} const int32_t Mediacontrolscmd120::ID = 0x120; void Mediacontrolscmd120::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_media_controls_cmd_120()->set_media_controls_cmd( - media_controls_cmd(bytes, length)); - chassis->mutable_media_controls_cmd_120()->set_ignore_overrides( - ignore_overrides(bytes, length)); - chassis->mutable_media_controls_cmd_120()->set_clear_override( - clear_override(bytes, length)); - chassis->mutable_media_controls_cmd_120()->set_clear_faults( + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_media_controls_cmd_120() + ->set_media_controls_cmd(media_controls_cmd(bytes, length)); + chassis->mutable_lexus() + ->mutable_media_controls_cmd_120() + ->set_ignore_overrides(ignore_overrides(bytes, length)); + chassis->mutable_lexus() + ->mutable_media_controls_cmd_120() + ->set_clear_override(clear_override(bytes, length)); + chassis->mutable_lexus()->mutable_media_controls_cmd_120()->set_clear_faults( clear_faults(bytes, length)); - chassis->mutable_media_controls_cmd_120()->set_enable( + chassis->mutable_lexus()->mutable_media_controls_cmd_120()->set_enable( enable(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/media_controls_cmd_120.h b/modules/canbus/vehicle/lexus/protocol/media_controls_cmd_120.h similarity index 94% rename from modules/canbus_vehicle/lexus/protocol/media_controls_cmd_120.h rename to modules/canbus/vehicle/lexus/protocol/media_controls_cmd_120.h index ef1bd09510d..999e0b718c7 100644 --- a/modules/canbus_vehicle/lexus/protocol/media_controls_cmd_120.h +++ b/modules/canbus/vehicle/lexus/protocol/media_controls_cmd_120.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Mediacontrolscmd120 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Mediacontrolscmd120(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'MEDIA_CONTROLS_CMD', 'enum': {0: diff --git a/modules/canbus_vehicle/lexus/protocol/media_controls_rpt_220.cc b/modules/canbus/vehicle/lexus/protocol/media_controls_rpt_220.cc similarity index 85% rename from modules/canbus_vehicle/lexus/protocol/media_controls_rpt_220.cc rename to modules/canbus/vehicle/lexus/protocol/media_controls_rpt_220.cc index 9b43a4ccafe..5d3894a1467 100644 --- a/modules/canbus_vehicle/lexus/protocol/media_controls_rpt_220.cc +++ b/modules/canbus/vehicle/lexus/protocol/media_controls_rpt_220.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/media_controls_rpt_220.h" +#include "modules/canbus/vehicle/lexus/protocol/media_controls_rpt_220.h" #include "glog/logging.h" @@ -31,27 +31,32 @@ Mediacontrolsrpt220::Mediacontrolsrpt220() {} const int32_t Mediacontrolsrpt220::ID = 0x220; void Mediacontrolsrpt220::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_media_controls_rpt_220()->set_output_value( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_media_controls_rpt_220()->set_output_value( output_value(bytes, length)); - chassis->mutable_media_controls_rpt_220()->set_commanded_value( - commanded_value(bytes, length)); - chassis->mutable_media_controls_rpt_220()->set_manual_input( + chassis->mutable_lexus() + ->mutable_media_controls_rpt_220() + ->set_commanded_value(commanded_value(bytes, length)); + chassis->mutable_lexus()->mutable_media_controls_rpt_220()->set_manual_input( manual_input(bytes, length)); - chassis->mutable_media_controls_rpt_220()->set_vehicle_fault( + chassis->mutable_lexus()->mutable_media_controls_rpt_220()->set_vehicle_fault( vehicle_fault(bytes, length)); - chassis->mutable_media_controls_rpt_220()->set_pacmod_fault( + chassis->mutable_lexus()->mutable_media_controls_rpt_220()->set_pacmod_fault( pacmod_fault(bytes, length)); - chassis->mutable_media_controls_rpt_220()->set_override_active( - override_active(bytes, length)); - chassis->mutable_media_controls_rpt_220()->set_output_reported_fault( - output_reported_fault(bytes, length)); - chassis->mutable_media_controls_rpt_220()->set_input_output_fault( - input_output_fault(bytes, length)); - chassis->mutable_media_controls_rpt_220()->set_enabled( + chassis->mutable_lexus() + ->mutable_media_controls_rpt_220() + ->set_override_active(override_active(bytes, length)); + chassis->mutable_lexus() + ->mutable_media_controls_rpt_220() + ->set_output_reported_fault(output_reported_fault(bytes, length)); + chassis->mutable_lexus() + ->mutable_media_controls_rpt_220() + ->set_input_output_fault(input_output_fault(bytes, length)); + chassis->mutable_lexus()->mutable_media_controls_rpt_220()->set_enabled( enabled(bytes, length)); - chassis->mutable_media_controls_rpt_220()->set_command_output_fault( - command_output_fault(bytes, length)); + chassis->mutable_lexus() + ->mutable_media_controls_rpt_220() + ->set_command_output_fault(command_output_fault(bytes, length)); } // config detail: {'name': 'output_value', 'enum': {0: diff --git a/modules/canbus_vehicle/lexus/protocol/media_controls_rpt_220.h b/modules/canbus/vehicle/lexus/protocol/media_controls_rpt_220.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/media_controls_rpt_220.h rename to modules/canbus/vehicle/lexus/protocol/media_controls_rpt_220.h index 7b0bb4515af..5f692132ade 100644 --- a/modules/canbus_vehicle/lexus/protocol/media_controls_rpt_220.h +++ b/modules/canbus/vehicle/lexus/protocol/media_controls_rpt_220.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Mediacontrolsrpt220 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Mediacontrolsrpt220(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'OUTPUT_VALUE', 'enum': {0: diff --git a/modules/canbus_vehicle/lexus/protocol/occupancy_rpt_415.cc b/modules/canbus/vehicle/lexus/protocol/occupancy_rpt_415.cc similarity index 78% rename from modules/canbus_vehicle/lexus/protocol/occupancy_rpt_415.cc rename to modules/canbus/vehicle/lexus/protocol/occupancy_rpt_415.cc index ed224060ce6..b38662612c7 100644 --- a/modules/canbus_vehicle/lexus/protocol/occupancy_rpt_415.cc +++ b/modules/canbus/vehicle/lexus/protocol/occupancy_rpt_415.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/occupancy_rpt_415.h" +#include "modules/canbus/vehicle/lexus/protocol/occupancy_rpt_415.h" #include "glog/logging.h" @@ -31,31 +31,47 @@ Occupancyrpt415::Occupancyrpt415() {} const int32_t Occupancyrpt415::ID = 0x415; void Occupancyrpt415::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_occupancy_rpt_415()->set_rear_seatbelt_buckled_is_valid( - rear_seatbelt_buckled_is_valid(bytes, length)); - chassis->mutable_occupancy_rpt_415()->set_pass_seatbelt_buckled_is_valid( - pass_seatbelt_buckled_is_valid(bytes, length)); - chassis->mutable_occupancy_rpt_415()->set_driver_seatbelt_buckled_is_valid( - driver_seatbelt_buckled_is_valid(bytes, length)); - chassis->mutable_occupancy_rpt_415()->set_rear_seat_occupied_is_valid( - rear_seat_occupied_is_valid(bytes, length)); - chassis->mutable_occupancy_rpt_415()->set_pass_seat_occupied_is_valid( - pass_seat_occupied_is_valid(bytes, length)); - chassis->mutable_occupancy_rpt_415()->set_driver_seat_occupied_is_valid( - driver_seat_occupied_is_valid(bytes, length)); - chassis->mutable_occupancy_rpt_415()->set_rear_seatbelt_buckled( - rear_seatbelt_buckled(bytes, length)); - chassis->mutable_occupancy_rpt_415()->set_pass_seatbelt_buckled( - pass_seatbelt_buckled(bytes, length)); - chassis->mutable_occupancy_rpt_415()->set_driver_seatbelt_buckled( - driver_seatbelt_buckled(bytes, length)); - chassis->mutable_occupancy_rpt_415()->set_rear_seat_occupied( + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_occupancy_rpt_415() + ->set_rear_seatbelt_buckled_is_valid( + rear_seatbelt_buckled_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_occupancy_rpt_415() + ->set_pass_seatbelt_buckled_is_valid( + pass_seatbelt_buckled_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_occupancy_rpt_415() + ->set_driver_seatbelt_buckled_is_valid( + driver_seatbelt_buckled_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_occupancy_rpt_415() + ->set_rear_seat_occupied_is_valid( + rear_seat_occupied_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_occupancy_rpt_415() + ->set_pass_seat_occupied_is_valid( + pass_seat_occupied_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_occupancy_rpt_415() + ->set_driver_seat_occupied_is_valid( + driver_seat_occupied_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_occupancy_rpt_415() + ->set_rear_seatbelt_buckled(rear_seatbelt_buckled(bytes, length)); + chassis->mutable_lexus() + ->mutable_occupancy_rpt_415() + ->set_pass_seatbelt_buckled(pass_seatbelt_buckled(bytes, length)); + chassis->mutable_lexus() + ->mutable_occupancy_rpt_415() + ->set_driver_seatbelt_buckled(driver_seatbelt_buckled(bytes, length)); + chassis->mutable_lexus()->mutable_occupancy_rpt_415()->set_rear_seat_occupied( rear_seat_occupied(bytes, length)); - chassis->mutable_occupancy_rpt_415()->set_pass_seat_occupied( + chassis->mutable_lexus()->mutable_occupancy_rpt_415()->set_pass_seat_occupied( pass_seat_occupied(bytes, length)); - chassis->mutable_occupancy_rpt_415()->set_driver_seat_occupied( - driver_seat_occupied(bytes, length)); + chassis->mutable_lexus() + ->mutable_occupancy_rpt_415() + ->set_driver_seat_occupied(driver_seat_occupied(bytes, length)); } // config detail: {'name': 'rear_seatbelt_buckled_is_valid', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/occupancy_rpt_415.h b/modules/canbus/vehicle/lexus/protocol/occupancy_rpt_415.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/occupancy_rpt_415.h rename to modules/canbus/vehicle/lexus/protocol/occupancy_rpt_415.h index d84b2587475..6b854c9d617 100644 --- a/modules/canbus_vehicle/lexus/protocol/occupancy_rpt_415.h +++ b/modules/canbus/vehicle/lexus/protocol/occupancy_rpt_415.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Occupancyrpt415 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Occupancyrpt415(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'REAR_SEATBELT_BUCKLED_IS_VALID', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/parking_brake_cmd_124.cc b/modules/canbus/vehicle/lexus/protocol/parking_brake_cmd_124.cc similarity index 98% rename from modules/canbus_vehicle/lexus/protocol/parking_brake_cmd_124.cc rename to modules/canbus/vehicle/lexus/protocol/parking_brake_cmd_124.cc index 099ff986430..b71d8a2f391 100644 --- a/modules/canbus_vehicle/lexus/protocol/parking_brake_cmd_124.cc +++ b/modules/canbus/vehicle/lexus/protocol/parking_brake_cmd_124.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/parking_brake_cmd_124.h" +#include "modules/canbus/vehicle/lexus/protocol/parking_brake_cmd_124.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lexus/protocol/parking_brake_cmd_124.h b/modules/canbus/vehicle/lexus/protocol/parking_brake_cmd_124.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/parking_brake_cmd_124.h rename to modules/canbus/vehicle/lexus/protocol/parking_brake_cmd_124.h index 039c863c40e..3f519d00ed6 100644 --- a/modules/canbus_vehicle/lexus/protocol/parking_brake_cmd_124.h +++ b/modules/canbus/vehicle/lexus/protocol/parking_brake_cmd_124.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace lexus { class Parkingbrakecmd124 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lexus/protocol/parking_brake_rpt_224.cc b/modules/canbus/vehicle/lexus/protocol/parking_brake_rpt_224.cc similarity index 82% rename from modules/canbus_vehicle/lexus/protocol/parking_brake_rpt_224.cc rename to modules/canbus/vehicle/lexus/protocol/parking_brake_rpt_224.cc index 3332c6da74c..5cbc42d4c56 100644 --- a/modules/canbus_vehicle/lexus/protocol/parking_brake_rpt_224.cc +++ b/modules/canbus/vehicle/lexus/protocol/parking_brake_rpt_224.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/parking_brake_rpt_224.h" +#include "modules/canbus/vehicle/lexus/protocol/parking_brake_rpt_224.h" #include "glog/logging.h" @@ -31,26 +31,31 @@ Parkingbrakerpt224::Parkingbrakerpt224() {} const int32_t Parkingbrakerpt224::ID = 0x224; void Parkingbrakerpt224::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_parking_brake_rpt_224()->set_vehicle_fault( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_parking_brake_rpt_224()->set_vehicle_fault( vehicle_fault(bytes, length)); - chassis->mutable_parking_brake_rpt_224()->set_pacmod_fault( + chassis->mutable_lexus()->mutable_parking_brake_rpt_224()->set_pacmod_fault( pacmod_fault(bytes, length)); - chassis->mutable_parking_brake_rpt_224()->set_override_active( - override_active(bytes, length)); - chassis->mutable_parking_brake_rpt_224()->set_output_reported_fault( - output_reported_fault(bytes, length)); - chassis->mutable_parking_brake_rpt_224()->set_input_output_fault( - input_output_fault(bytes, length)); - chassis->mutable_parking_brake_rpt_224()->set_enabled( + chassis->mutable_lexus() + ->mutable_parking_brake_rpt_224() + ->set_override_active(override_active(bytes, length)); + chassis->mutable_lexus() + ->mutable_parking_brake_rpt_224() + ->set_output_reported_fault(output_reported_fault(bytes, length)); + chassis->mutable_lexus() + ->mutable_parking_brake_rpt_224() + ->set_input_output_fault(input_output_fault(bytes, length)); + chassis->mutable_lexus()->mutable_parking_brake_rpt_224()->set_enabled( enabled(bytes, length)); - chassis->mutable_parking_brake_rpt_224()->set_command_output_fault( - command_output_fault(bytes, length)); - chassis->mutable_parking_brake_rpt_224()->set_output_value( + chassis->mutable_lexus() + ->mutable_parking_brake_rpt_224() + ->set_command_output_fault(command_output_fault(bytes, length)); + chassis->mutable_lexus()->mutable_parking_brake_rpt_224()->set_output_value( output_value(bytes, length)); - chassis->mutable_parking_brake_rpt_224()->set_commanded_value( - commanded_value(bytes, length)); - chassis->mutable_parking_brake_rpt_224()->set_manual_input( + chassis->mutable_lexus() + ->mutable_parking_brake_rpt_224() + ->set_commanded_value(commanded_value(bytes, length)); + chassis->mutable_lexus()->mutable_parking_brake_rpt_224()->set_manual_input( manual_input(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/parking_brake_rpt_224.h b/modules/canbus/vehicle/lexus/protocol/parking_brake_rpt_224.h similarity index 95% rename from modules/canbus_vehicle/lexus/protocol/parking_brake_rpt_224.h rename to modules/canbus/vehicle/lexus/protocol/parking_brake_rpt_224.h index ccd199821d1..bef761f189f 100644 --- a/modules/canbus_vehicle/lexus/protocol/parking_brake_rpt_224.h +++ b/modules/canbus/vehicle/lexus/protocol/parking_brake_rpt_224.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Parkingbrakerpt224 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Parkingbrakerpt224(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VEHICLE_FAULT', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/rear_lights_rpt_418.cc b/modules/canbus/vehicle/lexus/protocol/rear_lights_rpt_418.cc similarity index 82% rename from modules/canbus_vehicle/lexus/protocol/rear_lights_rpt_418.cc rename to modules/canbus/vehicle/lexus/protocol/rear_lights_rpt_418.cc index 1e28481680d..b31c558aa6c 100644 --- a/modules/canbus_vehicle/lexus/protocol/rear_lights_rpt_418.cc +++ b/modules/canbus/vehicle/lexus/protocol/rear_lights_rpt_418.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/rear_lights_rpt_418.h" +#include "modules/canbus/vehicle/lexus/protocol/rear_lights_rpt_418.h" #include "glog/logging.h" @@ -31,14 +31,18 @@ Rearlightsrpt418::Rearlightsrpt418() {} const int32_t Rearlightsrpt418::ID = 0x418; void Rearlightsrpt418::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_rear_lights_rpt_418()->set_reverse_lights_on_is_valid( - reverse_lights_on_is_valid(bytes, length)); - chassis->mutable_rear_lights_rpt_418()->set_brake_lights_on_is_valid( - brake_lights_on_is_valid(bytes, length)); - chassis->mutable_rear_lights_rpt_418()->set_reverse_lights_on( - reverse_lights_on(bytes, length)); - chassis->mutable_rear_lights_rpt_418()->set_brake_lights_on( + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_rear_lights_rpt_418() + ->set_reverse_lights_on_is_valid( + reverse_lights_on_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_rear_lights_rpt_418() + ->set_brake_lights_on_is_valid(brake_lights_on_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_rear_lights_rpt_418() + ->set_reverse_lights_on(reverse_lights_on(bytes, length)); + chassis->mutable_lexus()->mutable_rear_lights_rpt_418()->set_brake_lights_on( brake_lights_on(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/rear_lights_rpt_418.h b/modules/canbus/vehicle/lexus/protocol/rear_lights_rpt_418.h similarity index 93% rename from modules/canbus_vehicle/lexus/protocol/rear_lights_rpt_418.h rename to modules/canbus/vehicle/lexus/protocol/rear_lights_rpt_418.h index 9612563778f..f35a2311ff8 100644 --- a/modules/canbus_vehicle/lexus/protocol/rear_lights_rpt_418.h +++ b/modules/canbus/vehicle/lexus/protocol/rear_lights_rpt_418.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Rearlightsrpt418 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Rearlightsrpt418(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'REVERSE_LIGHTS_ON_IS_VALID', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/shift_aux_rpt_328.cc b/modules/canbus/vehicle/lexus/protocol/shift_aux_rpt_328.cc similarity index 79% rename from modules/canbus_vehicle/lexus/protocol/shift_aux_rpt_328.cc rename to modules/canbus/vehicle/lexus/protocol/shift_aux_rpt_328.cc index f0fd8cf188e..1faf2f49d32 100644 --- a/modules/canbus_vehicle/lexus/protocol/shift_aux_rpt_328.cc +++ b/modules/canbus/vehicle/lexus/protocol/shift_aux_rpt_328.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/shift_aux_rpt_328.h" +#include "modules/canbus/vehicle/lexus/protocol/shift_aux_rpt_328.h" #include "glog/logging.h" @@ -31,22 +31,32 @@ Shiftauxrpt328::Shiftauxrpt328() {} const int32_t Shiftauxrpt328::ID = 0x328; void Shiftauxrpt328::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_shift_aux_rpt_328()->set_speed_interlock_active_is_valid( - speed_interlock_active_is_valid(bytes, length)); - chassis->mutable_shift_aux_rpt_328()->set_speed_interlock_active( - speed_interlock_active(bytes, length)); - chassis->mutable_shift_aux_rpt_328()->set_brake_interlock_active_is_valid( - brake_interlock_active_is_valid(bytes, length)); - chassis->mutable_shift_aux_rpt_328()->set_brake_interlock_active( - brake_interlock_active(bytes, length)); - chassis->mutable_shift_aux_rpt_328()->set_stay_in_neutral_mode_is_valid( - stay_in_neutral_mode_is_valid(bytes, length)); - chassis->mutable_shift_aux_rpt_328()->set_stay_in_neutral_mode( - stay_in_neutral_mode(bytes, length)); - chassis->mutable_shift_aux_rpt_328()->set_between_gears_is_valid( - between_gears_is_valid(bytes, length)); - chassis->mutable_shift_aux_rpt_328()->set_between_gears( + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_shift_aux_rpt_328() + ->set_speed_interlock_active_is_valid( + speed_interlock_active_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_shift_aux_rpt_328() + ->set_speed_interlock_active(speed_interlock_active(bytes, length)); + chassis->mutable_lexus() + ->mutable_shift_aux_rpt_328() + ->set_brake_interlock_active_is_valid( + brake_interlock_active_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_shift_aux_rpt_328() + ->set_brake_interlock_active(brake_interlock_active(bytes, length)); + chassis->mutable_lexus() + ->mutable_shift_aux_rpt_328() + ->set_stay_in_neutral_mode_is_valid( + stay_in_neutral_mode_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_shift_aux_rpt_328() + ->set_stay_in_neutral_mode(stay_in_neutral_mode(bytes, length)); + chassis->mutable_lexus() + ->mutable_shift_aux_rpt_328() + ->set_between_gears_is_valid(between_gears_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_shift_aux_rpt_328()->set_between_gears( between_gears(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/shift_aux_rpt_328.h b/modules/canbus/vehicle/lexus/protocol/shift_aux_rpt_328.h similarity index 95% rename from modules/canbus_vehicle/lexus/protocol/shift_aux_rpt_328.h rename to modules/canbus/vehicle/lexus/protocol/shift_aux_rpt_328.h index 7ff4bcc04b6..a4037827df6 100644 --- a/modules/canbus_vehicle/lexus/protocol/shift_aux_rpt_328.h +++ b/modules/canbus/vehicle/lexus/protocol/shift_aux_rpt_328.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Shiftauxrpt328 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Shiftauxrpt328(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'SPEED_INTERLOCK_ACTIVE_IS_VALID', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/shift_cmd_128.cc b/modules/canbus/vehicle/lexus/protocol/shift_cmd_128.cc similarity index 98% rename from modules/canbus_vehicle/lexus/protocol/shift_cmd_128.cc rename to modules/canbus/vehicle/lexus/protocol/shift_cmd_128.cc index ebaed018ad9..b76192e6414 100644 --- a/modules/canbus_vehicle/lexus/protocol/shift_cmd_128.cc +++ b/modules/canbus/vehicle/lexus/protocol/shift_cmd_128.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/shift_cmd_128.h" +#include "modules/canbus/vehicle/lexus/protocol/shift_cmd_128.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lexus/protocol/shift_cmd_128.h b/modules/canbus/vehicle/lexus/protocol/shift_cmd_128.h similarity index 97% rename from modules/canbus_vehicle/lexus/protocol/shift_cmd_128.h rename to modules/canbus/vehicle/lexus/protocol/shift_cmd_128.h index 30ff6d69b57..58915a01350 100644 --- a/modules/canbus_vehicle/lexus/protocol/shift_cmd_128.h +++ b/modules/canbus/vehicle/lexus/protocol/shift_cmd_128.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace lexus { class Shiftcmd128 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lexus/protocol/shift_rpt_228.cc b/modules/canbus/vehicle/lexus/protocol/shift_rpt_228.cc similarity index 88% rename from modules/canbus_vehicle/lexus/protocol/shift_rpt_228.cc rename to modules/canbus/vehicle/lexus/protocol/shift_rpt_228.cc index b7b3abced73..643e65550fd 100644 --- a/modules/canbus_vehicle/lexus/protocol/shift_rpt_228.cc +++ b/modules/canbus/vehicle/lexus/protocol/shift_rpt_228.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/shift_rpt_228.h" +#include "modules/canbus/vehicle/lexus/protocol/shift_rpt_228.h" #include "glog/logging.h" @@ -31,26 +31,26 @@ Shiftrpt228::Shiftrpt228() {} const int32_t Shiftrpt228::ID = 0x228; void Shiftrpt228::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_shift_rpt_228()->set_vehicle_fault( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_shift_rpt_228()->set_vehicle_fault( vehicle_fault(bytes, length)); - chassis->mutable_shift_rpt_228()->set_pacmod_fault( + chassis->mutable_lexus()->mutable_shift_rpt_228()->set_pacmod_fault( pacmod_fault(bytes, length)); - chassis->mutable_shift_rpt_228()->set_override_active( + chassis->mutable_lexus()->mutable_shift_rpt_228()->set_override_active( override_active(bytes, length)); - chassis->mutable_shift_rpt_228()->set_output_reported_fault( + chassis->mutable_lexus()->mutable_shift_rpt_228()->set_output_reported_fault( output_reported_fault(bytes, length)); - chassis->mutable_shift_rpt_228()->set_input_output_fault( + chassis->mutable_lexus()->mutable_shift_rpt_228()->set_input_output_fault( input_output_fault(bytes, length)); - chassis->mutable_shift_rpt_228()->set_enabled( + chassis->mutable_lexus()->mutable_shift_rpt_228()->set_enabled( enabled(bytes, length)); - chassis->mutable_shift_rpt_228()->set_command_output_fault( + chassis->mutable_lexus()->mutable_shift_rpt_228()->set_command_output_fault( command_output_fault(bytes, length)); - chassis->mutable_shift_rpt_228()->set_manual_input( + chassis->mutable_lexus()->mutable_shift_rpt_228()->set_manual_input( manual_input(bytes, length)); - chassis->mutable_shift_rpt_228()->set_commanded_value( + chassis->mutable_lexus()->mutable_shift_rpt_228()->set_commanded_value( commanded_value(bytes, length)); - chassis->mutable_shift_rpt_228()->set_output_value( + chassis->mutable_lexus()->mutable_shift_rpt_228()->set_output_value( output_value(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/shift_rpt_228.h b/modules/canbus/vehicle/lexus/protocol/shift_rpt_228.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/shift_rpt_228.h rename to modules/canbus/vehicle/lexus/protocol/shift_rpt_228.h index a9035e9bace..3908d000df3 100644 --- a/modules/canbus_vehicle/lexus/protocol/shift_rpt_228.h +++ b/modules/canbus/vehicle/lexus/protocol/shift_rpt_228.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Shiftrpt228 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Shiftrpt228(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VEHICLE_FAULT', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/steering_aux_rpt_32c.cc b/modules/canbus/vehicle/lexus/protocol/steering_aux_rpt_32c.cc similarity index 83% rename from modules/canbus_vehicle/lexus/protocol/steering_aux_rpt_32c.cc rename to modules/canbus/vehicle/lexus/protocol/steering_aux_rpt_32c.cc index c4567744bd4..578f05575cd 100644 --- a/modules/canbus_vehicle/lexus/protocol/steering_aux_rpt_32c.cc +++ b/modules/canbus/vehicle/lexus/protocol/steering_aux_rpt_32c.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/steering_aux_rpt_32c.h" +#include "modules/canbus/vehicle/lexus/protocol/steering_aux_rpt_32c.h" #include "glog/logging.h" @@ -31,22 +31,27 @@ Steeringauxrpt32c::Steeringauxrpt32c() {} const int32_t Steeringauxrpt32c::ID = 0x32C; void Steeringauxrpt32c::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_steering_aux_rpt_32c()->set_user_interaction_is_valid( - user_interaction_is_valid(bytes, length)); - chassis->mutable_steering_aux_rpt_32c()->set_user_interaction( - user_interaction(bytes, length)); - chassis->mutable_steering_aux_rpt_32c()->set_rotation_rate_is_valid( - rotation_rate_is_valid(bytes, length)); - chassis->mutable_steering_aux_rpt_32c()->set_rotation_rate( + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_steering_aux_rpt_32c() + ->set_user_interaction_is_valid(user_interaction_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_steering_aux_rpt_32c() + ->set_user_interaction(user_interaction(bytes, length)); + chassis->mutable_lexus() + ->mutable_steering_aux_rpt_32c() + ->set_rotation_rate_is_valid(rotation_rate_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_steering_aux_rpt_32c()->set_rotation_rate( rotation_rate(bytes, length)); - chassis->mutable_steering_aux_rpt_32c()->set_raw_torque_is_valid( - raw_torque_is_valid(bytes, length)); - chassis->mutable_steering_aux_rpt_32c()->set_raw_torque( + chassis->mutable_lexus() + ->mutable_steering_aux_rpt_32c() + ->set_raw_torque_is_valid(raw_torque_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_steering_aux_rpt_32c()->set_raw_torque( raw_torque(bytes, length)); - chassis->mutable_steering_aux_rpt_32c()->set_raw_position_is_valid( - raw_position_is_valid(bytes, length)); - chassis->mutable_steering_aux_rpt_32c()->set_raw_position( + chassis->mutable_lexus() + ->mutable_steering_aux_rpt_32c() + ->set_raw_position_is_valid(raw_position_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_steering_aux_rpt_32c()->set_raw_position( raw_position(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/steering_aux_rpt_32c.h b/modules/canbus/vehicle/lexus/protocol/steering_aux_rpt_32c.h similarity index 95% rename from modules/canbus_vehicle/lexus/protocol/steering_aux_rpt_32c.h rename to modules/canbus/vehicle/lexus/protocol/steering_aux_rpt_32c.h index 1c9a3a430a6..c0616576bd2 100644 --- a/modules/canbus_vehicle/lexus/protocol/steering_aux_rpt_32c.h +++ b/modules/canbus/vehicle/lexus/protocol/steering_aux_rpt_32c.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Steeringauxrpt32c : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Steeringauxrpt32c(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'USER_INTERACTION_IS_VALID', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/steering_cmd_12c.cc b/modules/canbus/vehicle/lexus/protocol/steering_cmd_12c.cc similarity index 98% rename from modules/canbus_vehicle/lexus/protocol/steering_cmd_12c.cc rename to modules/canbus/vehicle/lexus/protocol/steering_cmd_12c.cc index fcc89729474..69fcd3a4b93 100644 --- a/modules/canbus_vehicle/lexus/protocol/steering_cmd_12c.cc +++ b/modules/canbus/vehicle/lexus/protocol/steering_cmd_12c.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/steering_cmd_12c.h" +#include "modules/canbus/vehicle/lexus/protocol/steering_cmd_12c.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lexus/protocol/steering_cmd_12c.h b/modules/canbus/vehicle/lexus/protocol/steering_cmd_12c.h similarity index 97% rename from modules/canbus_vehicle/lexus/protocol/steering_cmd_12c.h rename to modules/canbus/vehicle/lexus/protocol/steering_cmd_12c.h index 48c74e9918f..2a23dbaa70c 100644 --- a/modules/canbus_vehicle/lexus/protocol/steering_cmd_12c.h +++ b/modules/canbus/vehicle/lexus/protocol/steering_cmd_12c.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace lexus { class Steeringcmd12c : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_1_404.cc b/modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_1_404.cc similarity index 87% rename from modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_1_404.cc rename to modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_1_404.cc index 76f08736aea..0a4d2584707 100644 --- a/modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_1_404.cc +++ b/modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_1_404.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_1_404.h" +#include "modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_1_404.h" #include "glog/logging.h" @@ -31,11 +31,13 @@ Steeringmotorrpt1404::Steeringmotorrpt1404() {} const int32_t Steeringmotorrpt1404::ID = 0x404; void Steeringmotorrpt1404::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_steering_motor_rpt_1_404()->set_motor_current( - motor_current(bytes, length)); - chassis->mutable_steering_motor_rpt_1_404()->set_shaft_position( - shaft_position(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_steering_motor_rpt_1_404() + ->set_motor_current(motor_current(bytes, length)); + chassis->mutable_lexus() + ->mutable_steering_motor_rpt_1_404() + ->set_shaft_position(shaft_position(bytes, length)); } // config detail: {'name': 'motor_current', 'offset': 0.0, 'precision': 0.001, diff --git a/modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_1_404.h b/modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_1_404.h similarity index 90% rename from modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_1_404.h rename to modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_1_404.h index b2530f14b6f..0ef376a2759 100644 --- a/modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_1_404.h +++ b/modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_1_404.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Steeringmotorrpt1404 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Steeringmotorrpt1404(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'MOTOR_CURRENT', 'offset': 0.0, 'precision': 0.001, diff --git a/modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_2_405.cc b/modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_2_405.cc similarity index 85% rename from modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_2_405.cc rename to modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_2_405.cc index db187d7fb40..e9accee62e9 100644 --- a/modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_2_405.cc +++ b/modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_2_405.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_2_405.h" +#include "modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_2_405.h" #include "glog/logging.h" @@ -31,13 +31,16 @@ Steeringmotorrpt2405::Steeringmotorrpt2405() {} const int32_t Steeringmotorrpt2405::ID = 0x405; void Steeringmotorrpt2405::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_steering_motor_rpt_2_405()->set_encoder_temperature( - encoder_temperature(bytes, length)); - chassis->mutable_steering_motor_rpt_2_405()->set_motor_temperature( - motor_temperature(bytes, length)); - chassis->mutable_steering_motor_rpt_2_405()->set_angular_speed( - angular_speed(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_steering_motor_rpt_2_405() + ->set_encoder_temperature(encoder_temperature(bytes, length)); + chassis->mutable_lexus() + ->mutable_steering_motor_rpt_2_405() + ->set_motor_temperature(motor_temperature(bytes, length)); + chassis->mutable_lexus() + ->mutable_steering_motor_rpt_2_405() + ->set_angular_speed(angular_speed(bytes, length)); } // config detail: {'name': 'encoder_temperature', 'offset': -40.0, diff --git a/modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_2_405.h b/modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_2_405.h similarity index 92% rename from modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_2_405.h rename to modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_2_405.h index 1aaa57ad3c8..f8bcfa94c00 100644 --- a/modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_2_405.h +++ b/modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_2_405.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Steeringmotorrpt2405 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Steeringmotorrpt2405(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'ENCODER_TEMPERATURE', 'offset': -40.0, diff --git a/modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_3_406.cc b/modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_3_406.cc similarity index 87% rename from modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_3_406.cc rename to modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_3_406.cc index c3cd20fa811..3938d0428c5 100644 --- a/modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_3_406.cc +++ b/modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_3_406.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_3_406.h" +#include "modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_3_406.h" #include "glog/logging.h" @@ -31,11 +31,13 @@ Steeringmotorrpt3406::Steeringmotorrpt3406() {} const int32_t Steeringmotorrpt3406::ID = 0x406; void Steeringmotorrpt3406::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_steering_motor_rpt_3_406()->set_torque_output( - torque_output(bytes, length)); - chassis->mutable_steering_motor_rpt_3_406()->set_torque_input( - torque_input(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_steering_motor_rpt_3_406() + ->set_torque_output(torque_output(bytes, length)); + chassis->mutable_lexus() + ->mutable_steering_motor_rpt_3_406() + ->set_torque_input(torque_input(bytes, length)); } // config detail: {'name': 'torque_output', 'offset': 0.0, 'precision': 0.001, diff --git a/modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_3_406.h b/modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_3_406.h similarity index 90% rename from modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_3_406.h rename to modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_3_406.h index cb73ee181bb..4251c6a1b52 100644 --- a/modules/canbus_vehicle/lexus/protocol/steering_motor_rpt_3_406.h +++ b/modules/canbus/vehicle/lexus/protocol/steering_motor_rpt_3_406.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Steeringmotorrpt3406 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Steeringmotorrpt3406(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'TORQUE_OUTPUT', 'offset': 0.0, 'precision': 0.001, diff --git a/modules/canbus_vehicle/lexus/protocol/steering_rpt_22c.cc b/modules/canbus/vehicle/lexus/protocol/steering_rpt_22c.cc similarity index 86% rename from modules/canbus_vehicle/lexus/protocol/steering_rpt_22c.cc rename to modules/canbus/vehicle/lexus/protocol/steering_rpt_22c.cc index 70fc688e962..9025513e057 100644 --- a/modules/canbus_vehicle/lexus/protocol/steering_rpt_22c.cc +++ b/modules/canbus/vehicle/lexus/protocol/steering_rpt_22c.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/steering_rpt_22c.h" +#include "modules/canbus/vehicle/lexus/protocol/steering_rpt_22c.h" #include "glog/logging.h" @@ -31,26 +31,28 @@ Steeringrpt22c::Steeringrpt22c() {} const int32_t Steeringrpt22c::ID = 0x22C; void Steeringrpt22c::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_steering_rpt_22c()->set_vehicle_fault( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_steering_rpt_22c()->set_vehicle_fault( vehicle_fault(bytes, length)); - chassis->mutable_steering_rpt_22c()->set_pacmod_fault( + chassis->mutable_lexus()->mutable_steering_rpt_22c()->set_pacmod_fault( pacmod_fault(bytes, length)); - chassis->mutable_steering_rpt_22c()->set_override_active( + chassis->mutable_lexus()->mutable_steering_rpt_22c()->set_override_active( override_active(bytes, length)); - chassis->mutable_steering_rpt_22c()->set_output_reported_fault( - output_reported_fault(bytes, length)); - chassis->mutable_steering_rpt_22c()->set_input_output_fault( + chassis->mutable_lexus() + ->mutable_steering_rpt_22c() + ->set_output_reported_fault(output_reported_fault(bytes, length)); + chassis->mutable_lexus()->mutable_steering_rpt_22c()->set_input_output_fault( input_output_fault(bytes, length)); - chassis->mutable_steering_rpt_22c()->set_enabled( + chassis->mutable_lexus()->mutable_steering_rpt_22c()->set_enabled( enabled(bytes, length)); - chassis->mutable_steering_rpt_22c()->set_command_output_fault( - command_output_fault(bytes, length)); - chassis->mutable_steering_rpt_22c()->set_manual_input( + chassis->mutable_lexus() + ->mutable_steering_rpt_22c() + ->set_command_output_fault(command_output_fault(bytes, length)); + chassis->mutable_lexus()->mutable_steering_rpt_22c()->set_manual_input( manual_input(bytes, length)); - chassis->mutable_steering_rpt_22c()->set_commanded_value( + chassis->mutable_lexus()->mutable_steering_rpt_22c()->set_commanded_value( commanded_value(bytes, length)); - chassis->mutable_steering_rpt_22c()->set_output_value( + chassis->mutable_lexus()->mutable_steering_rpt_22c()->set_output_value( output_value(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/steering_rpt_22c.h b/modules/canbus/vehicle/lexus/protocol/steering_rpt_22c.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/steering_rpt_22c.h rename to modules/canbus/vehicle/lexus/protocol/steering_rpt_22c.h index ea8b10ddc50..bf55a4437cd 100644 --- a/modules/canbus_vehicle/lexus/protocol/steering_rpt_22c.h +++ b/modules/canbus/vehicle/lexus/protocol/steering_rpt_22c.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Steeringrpt22c : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Steeringrpt22c(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VEHICLE_FAULT', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/turn_aux_rpt_330.cc b/modules/canbus/vehicle/lexus/protocol/turn_aux_rpt_330.cc similarity index 80% rename from modules/canbus_vehicle/lexus/protocol/turn_aux_rpt_330.cc rename to modules/canbus/vehicle/lexus/protocol/turn_aux_rpt_330.cc index 7c150b87741..7b083739521 100644 --- a/modules/canbus_vehicle/lexus/protocol/turn_aux_rpt_330.cc +++ b/modules/canbus/vehicle/lexus/protocol/turn_aux_rpt_330.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/turn_aux_rpt_330.h" +#include "modules/canbus/vehicle/lexus/protocol/turn_aux_rpt_330.h" #include "glog/logging.h" @@ -31,15 +31,21 @@ Turnauxrpt330::Turnauxrpt330() {} const int32_t Turnauxrpt330::ID = 0x330; void Turnauxrpt330::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_turn_aux_rpt_330()->set_pass_blinker_bulb_on_is_valid( - pass_blinker_bulb_on_is_valid(bytes, length)); - chassis->mutable_turn_aux_rpt_330()->set_pass_blinker_bulb_on( - pass_blinker_bulb_on(bytes, length)); - chassis->mutable_turn_aux_rpt_330()->set_driver_blinker_bulb_on_is_valid( - driver_blinker_bulb_on_is_valid(bytes, length)); - chassis->mutable_turn_aux_rpt_330()->set_driver_blinker_bulb_on( - driver_blinker_bulb_on(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_turn_aux_rpt_330() + ->set_pass_blinker_bulb_on_is_valid( + pass_blinker_bulb_on_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_turn_aux_rpt_330() + ->set_pass_blinker_bulb_on(pass_blinker_bulb_on(bytes, length)); + chassis->mutable_lexus() + ->mutable_turn_aux_rpt_330() + ->set_driver_blinker_bulb_on_is_valid( + driver_blinker_bulb_on_is_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_turn_aux_rpt_330() + ->set_driver_blinker_bulb_on(driver_blinker_bulb_on(bytes, length)); } // config detail: {'name': 'pass_blinker_bulb_on_is_valid', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/turn_aux_rpt_330.h b/modules/canbus/vehicle/lexus/protocol/turn_aux_rpt_330.h similarity index 93% rename from modules/canbus_vehicle/lexus/protocol/turn_aux_rpt_330.h rename to modules/canbus/vehicle/lexus/protocol/turn_aux_rpt_330.h index 9aa11779b65..0164ac568d2 100644 --- a/modules/canbus_vehicle/lexus/protocol/turn_aux_rpt_330.h +++ b/modules/canbus/vehicle/lexus/protocol/turn_aux_rpt_330.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Turnauxrpt330 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Turnauxrpt330(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'PASS_BLINKER_BULB_ON_IS_VALID', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/turn_cmd_130.cc b/modules/canbus/vehicle/lexus/protocol/turn_cmd_130.cc similarity index 98% rename from modules/canbus_vehicle/lexus/protocol/turn_cmd_130.cc rename to modules/canbus/vehicle/lexus/protocol/turn_cmd_130.cc index d24ae95b5c1..ec7b113a1d7 100644 --- a/modules/canbus_vehicle/lexus/protocol/turn_cmd_130.cc +++ b/modules/canbus/vehicle/lexus/protocol/turn_cmd_130.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/turn_cmd_130.h" +#include "modules/canbus/vehicle/lexus/protocol/turn_cmd_130.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lexus/protocol/turn_cmd_130.h b/modules/canbus/vehicle/lexus/protocol/turn_cmd_130.h similarity index 97% rename from modules/canbus_vehicle/lexus/protocol/turn_cmd_130.h rename to modules/canbus/vehicle/lexus/protocol/turn_cmd_130.h index 95c58ac9fbf..6937f06df81 100644 --- a/modules/canbus_vehicle/lexus/protocol/turn_cmd_130.h +++ b/modules/canbus/vehicle/lexus/protocol/turn_cmd_130.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace lexus { class Turncmd130 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lexus/protocol/turn_rpt_230.cc b/modules/canbus/vehicle/lexus/protocol/turn_rpt_230.cc similarity index 88% rename from modules/canbus_vehicle/lexus/protocol/turn_rpt_230.cc rename to modules/canbus/vehicle/lexus/protocol/turn_rpt_230.cc index b6d4f72cbaf..009de085b94 100644 --- a/modules/canbus_vehicle/lexus/protocol/turn_rpt_230.cc +++ b/modules/canbus/vehicle/lexus/protocol/turn_rpt_230.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/turn_rpt_230.h" +#include "modules/canbus/vehicle/lexus/protocol/turn_rpt_230.h" #include "glog/logging.h" @@ -31,26 +31,26 @@ Turnrpt230::Turnrpt230() {} const int32_t Turnrpt230::ID = 0x230; void Turnrpt230::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_turn_rpt_230()->set_vehicle_fault( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_turn_rpt_230()->set_vehicle_fault( vehicle_fault(bytes, length)); - chassis->mutable_turn_rpt_230()->set_pacmod_fault( + chassis->mutable_lexus()->mutable_turn_rpt_230()->set_pacmod_fault( pacmod_fault(bytes, length)); - chassis->mutable_turn_rpt_230()->set_override_active( + chassis->mutable_lexus()->mutable_turn_rpt_230()->set_override_active( override_active(bytes, length)); - chassis->mutable_turn_rpt_230()->set_output_reported_fault( + chassis->mutable_lexus()->mutable_turn_rpt_230()->set_output_reported_fault( output_reported_fault(bytes, length)); - chassis->mutable_turn_rpt_230()->set_input_output_fault( + chassis->mutable_lexus()->mutable_turn_rpt_230()->set_input_output_fault( input_output_fault(bytes, length)); - chassis->mutable_turn_rpt_230()->set_enabled( + chassis->mutable_lexus()->mutable_turn_rpt_230()->set_enabled( enabled(bytes, length)); - chassis->mutable_turn_rpt_230()->set_command_output_fault( + chassis->mutable_lexus()->mutable_turn_rpt_230()->set_command_output_fault( command_output_fault(bytes, length)); - chassis->mutable_turn_rpt_230()->set_manual_input( + chassis->mutable_lexus()->mutable_turn_rpt_230()->set_manual_input( manual_input(bytes, length)); - chassis->mutable_turn_rpt_230()->set_commanded_value( + chassis->mutable_lexus()->mutable_turn_rpt_230()->set_commanded_value( commanded_value(bytes, length)); - chassis->mutable_turn_rpt_230()->set_output_value( + chassis->mutable_lexus()->mutable_turn_rpt_230()->set_output_value( output_value(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/turn_rpt_230.h b/modules/canbus/vehicle/lexus/protocol/turn_rpt_230.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/turn_rpt_230.h rename to modules/canbus/vehicle/lexus/protocol/turn_rpt_230.h index 0a5b1ab56d8..ecdf1cfb8dc 100644 --- a/modules/canbus_vehicle/lexus/protocol/turn_rpt_230.h +++ b/modules/canbus/vehicle/lexus/protocol/turn_rpt_230.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Turnrpt230 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Turnrpt230(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VEHICLE_FAULT', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/veh_dynamics_rpt_413.cc b/modules/canbus/vehicle/lexus/protocol/veh_dynamics_rpt_413.cc similarity index 89% rename from modules/canbus_vehicle/lexus/protocol/veh_dynamics_rpt_413.cc rename to modules/canbus/vehicle/lexus/protocol/veh_dynamics_rpt_413.cc index 384183a74ff..d4c8fc4bf48 100644 --- a/modules/canbus_vehicle/lexus/protocol/veh_dynamics_rpt_413.cc +++ b/modules/canbus/vehicle/lexus/protocol/veh_dynamics_rpt_413.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/veh_dynamics_rpt_413.h" +#include "modules/canbus/vehicle/lexus/protocol/veh_dynamics_rpt_413.h" #include "glog/logging.h" @@ -31,8 +31,8 @@ Vehdynamicsrpt413::Vehdynamicsrpt413() {} const int32_t Vehdynamicsrpt413::ID = 0x413; void Vehdynamicsrpt413::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_veh_dynamics_rpt_413()->set_veh_g_forces( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_veh_dynamics_rpt_413()->set_veh_g_forces( veh_g_forces(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/veh_dynamics_rpt_413.h b/modules/canbus/vehicle/lexus/protocol/veh_dynamics_rpt_413.h similarity index 89% rename from modules/canbus_vehicle/lexus/protocol/veh_dynamics_rpt_413.h rename to modules/canbus/vehicle/lexus/protocol/veh_dynamics_rpt_413.h index 0100a97b32d..e3c266e1501 100644 --- a/modules/canbus_vehicle/lexus/protocol/veh_dynamics_rpt_413.h +++ b/modules/canbus/vehicle/lexus/protocol/veh_dynamics_rpt_413.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Vehdynamicsrpt413 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vehdynamicsrpt413(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VEH_G_FORCES', 'offset': 0.0, 'precision': 0.001, diff --git a/modules/canbus_vehicle/lexus/protocol/veh_specific_rpt_1_412.cc b/modules/canbus/vehicle/lexus/protocol/veh_specific_rpt_1_412.cc similarity index 88% rename from modules/canbus_vehicle/lexus/protocol/veh_specific_rpt_1_412.cc rename to modules/canbus/vehicle/lexus/protocol/veh_specific_rpt_1_412.cc index f851efdf918..9146c010fbd 100644 --- a/modules/canbus_vehicle/lexus/protocol/veh_specific_rpt_1_412.cc +++ b/modules/canbus/vehicle/lexus/protocol/veh_specific_rpt_1_412.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/veh_specific_rpt_1_412.h" +#include "modules/canbus/vehicle/lexus/protocol/veh_specific_rpt_1_412.h" #include "glog/logging.h" @@ -31,10 +31,10 @@ Vehspecificrpt1412::Vehspecificrpt1412() {} const int32_t Vehspecificrpt1412::ID = 0x412; void Vehspecificrpt1412::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_veh_specific_rpt_1_412()->set_shift_pos_2( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_veh_specific_rpt_1_412()->set_shift_pos_2( shift_pos_2(bytes, length)); - chassis->mutable_veh_specific_rpt_1_412()->set_shift_pos_1( + chassis->mutable_lexus()->mutable_veh_specific_rpt_1_412()->set_shift_pos_1( shift_pos_1(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/veh_specific_rpt_1_412.h b/modules/canbus/vehicle/lexus/protocol/veh_specific_rpt_1_412.h similarity index 90% rename from modules/canbus_vehicle/lexus/protocol/veh_specific_rpt_1_412.h rename to modules/canbus/vehicle/lexus/protocol/veh_specific_rpt_1_412.h index 0ca6b15fa27..5345479e349 100644 --- a/modules/canbus_vehicle/lexus/protocol/veh_specific_rpt_1_412.h +++ b/modules/canbus/vehicle/lexus/protocol/veh_specific_rpt_1_412.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Vehspecificrpt1412 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vehspecificrpt1412(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'SHIFT_POS_2', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/vehicle_speed_rpt_400.cc b/modules/canbus/vehicle/lexus/protocol/vehicle_speed_rpt_400.cc similarity index 88% rename from modules/canbus_vehicle/lexus/protocol/vehicle_speed_rpt_400.cc rename to modules/canbus/vehicle/lexus/protocol/vehicle_speed_rpt_400.cc index b0c07e5dab3..3c42c850a02 100644 --- a/modules/canbus_vehicle/lexus/protocol/vehicle_speed_rpt_400.cc +++ b/modules/canbus/vehicle/lexus/protocol/vehicle_speed_rpt_400.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/vehicle_speed_rpt_400.h" +#include "modules/canbus/vehicle/lexus/protocol/vehicle_speed_rpt_400.h" #include "glog/logging.h" @@ -31,11 +31,12 @@ Vehiclespeedrpt400::Vehiclespeedrpt400() {} const int32_t Vehiclespeedrpt400::ID = 0x400; void Vehiclespeedrpt400::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_vehicle_speed_rpt_400()->set_vehicle_speed( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_vehicle_speed_rpt_400()->set_vehicle_speed( vehicle_speed(bytes, length)); - chassis->mutable_vehicle_speed_rpt_400()->set_vehicle_speed_valid( - vehicle_speed_valid(bytes, length)); + chassis->mutable_lexus() + ->mutable_vehicle_speed_rpt_400() + ->set_vehicle_speed_valid(vehicle_speed_valid(bytes, length)); } // config detail: {'name': 'vehicle_speed', 'offset': 0.0, 'precision': 0.01, diff --git a/modules/canbus_vehicle/lexus/protocol/vehicle_speed_rpt_400.h b/modules/canbus/vehicle/lexus/protocol/vehicle_speed_rpt_400.h similarity index 91% rename from modules/canbus_vehicle/lexus/protocol/vehicle_speed_rpt_400.h rename to modules/canbus/vehicle/lexus/protocol/vehicle_speed_rpt_400.h index 77c354d3260..97072fcb72a 100644 --- a/modules/canbus_vehicle/lexus/protocol/vehicle_speed_rpt_400.h +++ b/modules/canbus/vehicle/lexus/protocol/vehicle_speed_rpt_400.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Vehiclespeedrpt400 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vehiclespeedrpt400(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VEHICLE_SPEED', 'offset': 0.0, 'precision': 0.01, diff --git a/modules/canbus_vehicle/lexus/protocol/vin_rpt_414.cc b/modules/canbus/vehicle/lexus/protocol/vin_rpt_414.cc similarity index 89% rename from modules/canbus_vehicle/lexus/protocol/vin_rpt_414.cc rename to modules/canbus/vehicle/lexus/protocol/vin_rpt_414.cc index 78d9baacfe1..a9d1e568afb 100644 --- a/modules/canbus_vehicle/lexus/protocol/vin_rpt_414.cc +++ b/modules/canbus/vehicle/lexus/protocol/vin_rpt_414.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/vin_rpt_414.h" +#include "modules/canbus/vehicle/lexus/protocol/vin_rpt_414.h" #include "glog/logging.h" @@ -31,12 +31,12 @@ Vinrpt414::Vinrpt414() {} const int32_t Vinrpt414::ID = 0x414; void Vinrpt414::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_vin_rpt_414()->set_veh_serial( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_vin_rpt_414()->set_veh_serial( veh_serial(bytes, length)); - chassis->mutable_vin_rpt_414()->set_veh_my_code( + chassis->mutable_lexus()->mutable_vin_rpt_414()->set_veh_my_code( veh_my_code(bytes, length)); - chassis->mutable_vin_rpt_414()->set_veh_mfg_code( + chassis->mutable_lexus()->mutable_vin_rpt_414()->set_veh_mfg_code( veh_mfg_code(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/vin_rpt_414.h b/modules/canbus/vehicle/lexus/protocol/vin_rpt_414.h similarity index 92% rename from modules/canbus_vehicle/lexus/protocol/vin_rpt_414.h rename to modules/canbus/vehicle/lexus/protocol/vin_rpt_414.h index c24f1102be2..fcb57ce02f9 100644 --- a/modules/canbus_vehicle/lexus/protocol/vin_rpt_414.h +++ b/modules/canbus/vehicle/lexus/protocol/vin_rpt_414.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Vinrpt414 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vinrpt414(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VEH_SERIAL', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/wheel_speed_rpt_407.cc b/modules/canbus/vehicle/lexus/protocol/wheel_speed_rpt_407.cc similarity index 84% rename from modules/canbus_vehicle/lexus/protocol/wheel_speed_rpt_407.cc rename to modules/canbus/vehicle/lexus/protocol/wheel_speed_rpt_407.cc index 91202b9d2a7..2c155a10e1b 100644 --- a/modules/canbus_vehicle/lexus/protocol/wheel_speed_rpt_407.cc +++ b/modules/canbus/vehicle/lexus/protocol/wheel_speed_rpt_407.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/wheel_speed_rpt_407.h" +#include "modules/canbus/vehicle/lexus/protocol/wheel_speed_rpt_407.h" #include "glog/logging.h" @@ -31,15 +31,19 @@ Wheelspeedrpt407::Wheelspeedrpt407() {} const int32_t Wheelspeedrpt407::ID = 0x407; void Wheelspeedrpt407::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_wheel_speed_rpt_407()->set_wheel_spd_rear_right( - wheel_spd_rear_right(bytes, length)); - chassis->mutable_wheel_speed_rpt_407()->set_wheel_spd_rear_left( - wheel_spd_rear_left(bytes, length)); - chassis->mutable_wheel_speed_rpt_407()->set_wheel_spd_front_right( - wheel_spd_front_right(bytes, length)); - chassis->mutable_wheel_speed_rpt_407()->set_wheel_spd_front_left( - wheel_spd_front_left(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_wheel_speed_rpt_407() + ->set_wheel_spd_rear_right(wheel_spd_rear_right(bytes, length)); + chassis->mutable_lexus() + ->mutable_wheel_speed_rpt_407() + ->set_wheel_spd_rear_left(wheel_spd_rear_left(bytes, length)); + chassis->mutable_lexus() + ->mutable_wheel_speed_rpt_407() + ->set_wheel_spd_front_right(wheel_spd_front_right(bytes, length)); + chassis->mutable_lexus() + ->mutable_wheel_speed_rpt_407() + ->set_wheel_spd_front_left(wheel_spd_front_left(bytes, length)); } // config detail: {'name': 'wheel_spd_rear_right', 'offset': 0.0, 'precision': diff --git a/modules/canbus_vehicle/lexus/protocol/wheel_speed_rpt_407.h b/modules/canbus/vehicle/lexus/protocol/wheel_speed_rpt_407.h similarity index 93% rename from modules/canbus_vehicle/lexus/protocol/wheel_speed_rpt_407.h rename to modules/canbus/vehicle/lexus/protocol/wheel_speed_rpt_407.h index 9e35165d655..64d85781fd7 100644 --- a/modules/canbus_vehicle/lexus/protocol/wheel_speed_rpt_407.h +++ b/modules/canbus/vehicle/lexus/protocol/wheel_speed_rpt_407.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Wheelspeedrpt407 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Wheelspeedrpt407(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'WHEEL_SPD_REAR_RIGHT', 'offset': 0.0, 'precision': diff --git a/modules/canbus_vehicle/lexus/protocol/wiper_aux_rpt_334.cc b/modules/canbus/vehicle/lexus/protocol/wiper_aux_rpt_334.cc similarity index 82% rename from modules/canbus_vehicle/lexus/protocol/wiper_aux_rpt_334.cc rename to modules/canbus/vehicle/lexus/protocol/wiper_aux_rpt_334.cc index 21fbff8af1b..48799b7492b 100644 --- a/modules/canbus_vehicle/lexus/protocol/wiper_aux_rpt_334.cc +++ b/modules/canbus/vehicle/lexus/protocol/wiper_aux_rpt_334.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/wiper_aux_rpt_334.h" +#include "modules/canbus/vehicle/lexus/protocol/wiper_aux_rpt_334.h" #include "glog/logging.h" @@ -31,30 +31,36 @@ Wiperauxrpt334::Wiperauxrpt334() {} const int32_t Wiperauxrpt334::ID = 0x334; void Wiperauxrpt334::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_wiper_aux_rpt_334()->set_spray_empty_is_valid( - spray_empty_is_valid(bytes, length)); - chassis->mutable_wiper_aux_rpt_334()->set_spray_empty( + ChassisDetail* chassis) const { + chassis->mutable_lexus() + ->mutable_wiper_aux_rpt_334() + ->set_spray_empty_is_valid(spray_empty_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_wiper_aux_rpt_334()->set_spray_empty( spray_empty(bytes, length)); - chassis->mutable_wiper_aux_rpt_334()->set_spray_near_empty_is_valid( - spray_near_empty_is_valid(bytes, length)); - chassis->mutable_wiper_aux_rpt_334()->set_spray_near_empty( + chassis->mutable_lexus() + ->mutable_wiper_aux_rpt_334() + ->set_spray_near_empty_is_valid(spray_near_empty_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_wiper_aux_rpt_334()->set_spray_near_empty( spray_near_empty(bytes, length)); - chassis->mutable_wiper_aux_rpt_334()->set_rear_spraying_is_valid( - rear_spraying_is_valid(bytes, length)); - chassis->mutable_wiper_aux_rpt_334()->set_rear_spraying( + chassis->mutable_lexus() + ->mutable_wiper_aux_rpt_334() + ->set_rear_spraying_is_valid(rear_spraying_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_wiper_aux_rpt_334()->set_rear_spraying( rear_spraying(bytes, length)); - chassis->mutable_wiper_aux_rpt_334()->set_rear_wiping_is_valid( - rear_wiping_is_valid(bytes, length)); - chassis->mutable_wiper_aux_rpt_334()->set_rear_wiping( + chassis->mutable_lexus() + ->mutable_wiper_aux_rpt_334() + ->set_rear_wiping_is_valid(rear_wiping_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_wiper_aux_rpt_334()->set_rear_wiping( rear_wiping(bytes, length)); - chassis->mutable_wiper_aux_rpt_334()->set_front_spraying_is_valid( - front_spraying_is_valid(bytes, length)); - chassis->mutable_wiper_aux_rpt_334()->set_front_spraying( + chassis->mutable_lexus() + ->mutable_wiper_aux_rpt_334() + ->set_front_spraying_is_valid(front_spraying_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_wiper_aux_rpt_334()->set_front_spraying( front_spraying(bytes, length)); - chassis->mutable_wiper_aux_rpt_334()->set_front_wiping_is_valid( - front_wiping_is_valid(bytes, length)); - chassis->mutable_wiper_aux_rpt_334()->set_front_wiping( + chassis->mutable_lexus() + ->mutable_wiper_aux_rpt_334() + ->set_front_wiping_is_valid(front_wiping_is_valid(bytes, length)); + chassis->mutable_lexus()->mutable_wiper_aux_rpt_334()->set_front_wiping( front_wiping(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/wiper_aux_rpt_334.h b/modules/canbus/vehicle/lexus/protocol/wiper_aux_rpt_334.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/wiper_aux_rpt_334.h rename to modules/canbus/vehicle/lexus/protocol/wiper_aux_rpt_334.h index 975a3b076f5..6cd4032e88a 100644 --- a/modules/canbus_vehicle/lexus/protocol/wiper_aux_rpt_334.h +++ b/modules/canbus/vehicle/lexus/protocol/wiper_aux_rpt_334.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Wiperauxrpt334 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Wiperauxrpt334(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'SPRAY_EMPTY_IS_VALID', 'offset': 0.0, diff --git a/modules/canbus_vehicle/lexus/protocol/wiper_cmd_134.cc b/modules/canbus/vehicle/lexus/protocol/wiper_cmd_134.cc similarity index 98% rename from modules/canbus_vehicle/lexus/protocol/wiper_cmd_134.cc rename to modules/canbus/vehicle/lexus/protocol/wiper_cmd_134.cc index c53f57df143..06494f050e5 100644 --- a/modules/canbus_vehicle/lexus/protocol/wiper_cmd_134.cc +++ b/modules/canbus/vehicle/lexus/protocol/wiper_cmd_134.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/wiper_cmd_134.h" +#include "modules/canbus/vehicle/lexus/protocol/wiper_cmd_134.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lexus/protocol/wiper_cmd_134.h b/modules/canbus/vehicle/lexus/protocol/wiper_cmd_134.h similarity index 97% rename from modules/canbus_vehicle/lexus/protocol/wiper_cmd_134.h rename to modules/canbus/vehicle/lexus/protocol/wiper_cmd_134.h index db17c447fd2..b4c4d83aba5 100644 --- a/modules/canbus_vehicle/lexus/protocol/wiper_cmd_134.h +++ b/modules/canbus/vehicle/lexus/protocol/wiper_cmd_134.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace lexus { class Wipercmd134 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lexus/protocol/wiper_rpt_234.cc b/modules/canbus/vehicle/lexus/protocol/wiper_rpt_234.cc similarity index 88% rename from modules/canbus_vehicle/lexus/protocol/wiper_rpt_234.cc rename to modules/canbus/vehicle/lexus/protocol/wiper_rpt_234.cc index d3a99ebe18d..0fb2e885e42 100644 --- a/modules/canbus_vehicle/lexus/protocol/wiper_rpt_234.cc +++ b/modules/canbus/vehicle/lexus/protocol/wiper_rpt_234.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/wiper_rpt_234.h" +#include "modules/canbus/vehicle/lexus/protocol/wiper_rpt_234.h" #include "glog/logging.h" @@ -31,26 +31,26 @@ Wiperrpt234::Wiperrpt234() {} const int32_t Wiperrpt234::ID = 0x234; void Wiperrpt234::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_wiper_rpt_234()->set_vehicle_fault( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_wiper_rpt_234()->set_vehicle_fault( vehicle_fault(bytes, length)); - chassis->mutable_wiper_rpt_234()->set_pacmod_fault( + chassis->mutable_lexus()->mutable_wiper_rpt_234()->set_pacmod_fault( pacmod_fault(bytes, length)); - chassis->mutable_wiper_rpt_234()->set_override_active( + chassis->mutable_lexus()->mutable_wiper_rpt_234()->set_override_active( override_active(bytes, length)); - chassis->mutable_wiper_rpt_234()->set_output_reported_fault( + chassis->mutable_lexus()->mutable_wiper_rpt_234()->set_output_reported_fault( output_reported_fault(bytes, length)); - chassis->mutable_wiper_rpt_234()->set_input_output_fault( + chassis->mutable_lexus()->mutable_wiper_rpt_234()->set_input_output_fault( input_output_fault(bytes, length)); - chassis->mutable_wiper_rpt_234()->set_enabled( + chassis->mutable_lexus()->mutable_wiper_rpt_234()->set_enabled( enabled(bytes, length)); - chassis->mutable_wiper_rpt_234()->set_command_output_fault( + chassis->mutable_lexus()->mutable_wiper_rpt_234()->set_command_output_fault( command_output_fault(bytes, length)); - chassis->mutable_wiper_rpt_234()->set_output_value( + chassis->mutable_lexus()->mutable_wiper_rpt_234()->set_output_value( output_value(bytes, length)); - chassis->mutable_wiper_rpt_234()->set_commanded_value( + chassis->mutable_lexus()->mutable_wiper_rpt_234()->set_commanded_value( commanded_value(bytes, length)); - chassis->mutable_wiper_rpt_234()->set_manual_input( + chassis->mutable_lexus()->mutable_wiper_rpt_234()->set_manual_input( manual_input(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/wiper_rpt_234.h b/modules/canbus/vehicle/lexus/protocol/wiper_rpt_234.h similarity index 96% rename from modules/canbus_vehicle/lexus/protocol/wiper_rpt_234.h rename to modules/canbus/vehicle/lexus/protocol/wiper_rpt_234.h index b893ac93ad7..771b53d27f0 100644 --- a/modules/canbus_vehicle/lexus/protocol/wiper_rpt_234.h +++ b/modules/canbus/vehicle/lexus/protocol/wiper_rpt_234.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Wiperrpt234 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Wiperrpt234(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VEHICLE_FAULT', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/lexus/protocol/yaw_rate_rpt_40d.cc b/modules/canbus/vehicle/lexus/protocol/yaw_rate_rpt_40d.cc similarity index 90% rename from modules/canbus_vehicle/lexus/protocol/yaw_rate_rpt_40d.cc rename to modules/canbus/vehicle/lexus/protocol/yaw_rate_rpt_40d.cc index 139ccd67415..fbecefaacf3 100644 --- a/modules/canbus_vehicle/lexus/protocol/yaw_rate_rpt_40d.cc +++ b/modules/canbus/vehicle/lexus/protocol/yaw_rate_rpt_40d.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lexus/protocol/yaw_rate_rpt_40d.h" +#include "modules/canbus/vehicle/lexus/protocol/yaw_rate_rpt_40d.h" #include "glog/logging.h" @@ -31,8 +31,8 @@ Yawraterpt40d::Yawraterpt40d() {} const int32_t Yawraterpt40d::ID = 0x40D; void Yawraterpt40d::Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const { - chassis->mutable_yaw_rate_rpt_40d()->set_yaw_rate( + ChassisDetail* chassis) const { + chassis->mutable_lexus()->mutable_yaw_rate_rpt_40d()->set_yaw_rate( yaw_rate(bytes, length)); } diff --git a/modules/canbus_vehicle/lexus/protocol/yaw_rate_rpt_40d.h b/modules/canbus/vehicle/lexus/protocol/yaw_rate_rpt_40d.h similarity index 89% rename from modules/canbus_vehicle/lexus/protocol/yaw_rate_rpt_40d.h rename to modules/canbus/vehicle/lexus/protocol/yaw_rate_rpt_40d.h index 37026e4af83..c6a6bf895d3 100644 --- a/modules/canbus_vehicle/lexus/protocol/yaw_rate_rpt_40d.h +++ b/modules/canbus/vehicle/lexus/protocol/yaw_rate_rpt_40d.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace lexus { class Yawraterpt40d : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lexus> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Yawraterpt40d(); void Parse(const std::uint8_t* bytes, int32_t length, - Lexus* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'YAW_RATE', 'offset': 0.0, 'precision': 0.01, diff --git a/modules/canbus/vehicle/lincoln/BUILD b/modules/canbus/vehicle/lincoln/BUILD new file mode 100644 index 00000000000..3ba61af7aab --- /dev/null +++ b/modules/canbus/vehicle/lincoln/BUILD @@ -0,0 +1,82 @@ +load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") +load("//tools:cpplint.bzl", "cpplint") + +package(default_visibility = ["//visibility:public"]) + +CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] + +cc_library( + name = "lincoln_vehicle_factory", + srcs = ["lincoln_vehicle_factory.cc"], + hdrs = ["lincoln_vehicle_factory.h"], + copts = CANBUS_COPTS, + deps = [ + ":lincoln_controller", + ":lincoln_message_manager", + "//modules/canbus/vehicle:abstract_vehicle_factory", + ], +) + +cc_library( + name = "lincoln_message_manager", + srcs = ["lincoln_message_manager.cc"], + hdrs = ["lincoln_message_manager.h"], + copts = CANBUS_COPTS, + deps = [ + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_library( + name = "lincoln_controller", + srcs = ["lincoln_controller.cc"], + hdrs = ["lincoln_controller.h"], + copts = CANBUS_COPTS, + deps = [ + ":lincoln_message_manager", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle:vehicle_controller_base", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/common/kv_db", + "//modules/drivers/canbus/can_comm:can_sender", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + "@com_google_googletest//:gtest", + ], +) + +cc_test( + name = "lincoln_controller_test", + size = "small", + srcs = ["lincoln_controller_test.cc"], + data = ["//modules/canbus:test_data"], + deps = [ + "//modules/canbus/vehicle/lincoln:lincoln_controller", + "@com_google_googletest//:gtest_main", + ], +) + +cc_test( + name = "lincoln_message_manager_test", + size = "small", + srcs = ["lincoln_message_manager_test.cc"], + deps = [ + "//modules/canbus/vehicle/lincoln:lincoln_message_manager", + "@com_google_googletest//:gtest_main", + ], +) + +cc_test( + name = "lincoln_vehicle_factory_test", + size = "small", + srcs = ["lincoln_vehicle_factory_test.cc"], + deps = [ + ":lincoln_vehicle_factory", + "@com_google_googletest//:gtest_main", + ], +) + +cpplint() diff --git a/modules/canbus_vehicle/lincoln/lincoln_controller.cc b/modules/canbus/vehicle/lincoln/lincoln_controller.cc similarity index 96% rename from modules/canbus_vehicle/lincoln/lincoln_controller.cc rename to modules/canbus/vehicle/lincoln/lincoln_controller.cc index 59186cbb881..e1cb8a30f67 100644 --- a/modules/canbus_vehicle/lincoln/lincoln_controller.cc +++ b/modules/canbus/vehicle/lincoln/lincoln_controller.cc @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/lincoln_controller.h" +#include "modules/canbus/vehicle/lincoln/lincoln_controller.h" #include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "cyber/common/log.h" #include "cyber/time/time.h" -#include "modules/canbus_vehicle/lincoln/lincoln_message_manager.h" -#include "modules/canbus_vehicle/lincoln/protocol/brake_60.h" -#include "modules/canbus_vehicle/lincoln/protocol/gear_66.h" -#include "modules/canbus_vehicle/lincoln/protocol/steering_64.h" -#include "modules/canbus_vehicle/lincoln/protocol/throttle_62.h" -#include "modules/canbus_vehicle/lincoln/protocol/turnsignal_68.h" +#include "modules/canbus/vehicle/lincoln/lincoln_message_manager.h" +#include "modules/canbus/vehicle/lincoln/protocol/brake_60.h" +#include "modules/canbus/vehicle/lincoln/protocol/gear_66.h" +#include "modules/canbus/vehicle/lincoln/protocol/steering_64.h" +#include "modules/canbus/vehicle/lincoln/protocol/throttle_62.h" +#include "modules/canbus/vehicle/lincoln/protocol/turnsignal_68.h" #include "modules/canbus/vehicle/vehicle_controller.h" #include "modules/common/kv_db/kv_db.h" #include "modules/drivers/canbus/can_comm/can_sender.h" @@ -49,8 +49,8 @@ const int32_t CHECK_RESPONSE_SPEED_UNIT_FLAG = 2; ErrorCode LincolnController::Init( const VehicleParameter ¶ms, - CanSender<::apollo::canbus::Lincoln> *const can_sender, - MessageManager<::apollo::canbus::Lincoln> *const message_manager) { + CanSender<::apollo::canbus::ChassisDetail> *const can_sender, + MessageManager<::apollo::canbus::ChassisDetail> *const message_manager) { if (is_initialized_) { AINFO << "LincolnController has already been initiated."; return ErrorCode::CANBUS_ERROR; @@ -117,7 +117,7 @@ ErrorCode LincolnController::Init( can_sender_->AddMessage(Turnsignal68::ID, turnsignal_68_, false); // Need to sleep to ensure all messages received - AINFO << "LincolnController is initialized."; + AINFO << "Controller is initialized."; gear_tmp_ = Chassis::GEAR_INVALID; is_initialized_ = true; @@ -151,7 +151,7 @@ void LincolnController::Stop() { Chassis LincolnController::chassis() { chassis_.Clear(); - Lincoln chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); // 21, 22, previously 1, 2 @@ -381,8 +381,6 @@ Chassis LincolnController::chassis() { return chassis_; } -bool LincolnController::VerifyID() { return true; } - void LincolnController::Emergency() { set_driving_mode(Chassis::EMERGENCY_MODE); ResetProtocol(); @@ -477,7 +475,7 @@ void LincolnController::Gear(Chassis::GearPosition ref_gear_position) { return; } - Lincoln chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); const Chassis::GearPosition current_gear_position = chassis_detail.gear().gear_state(); @@ -596,7 +594,7 @@ void LincolnController::Steer(double angle, double angle_spd) { const double real_angle = vehicle_params_.max_steer_angle() / M_PI * 180 * angle / 100.0; const double real_angle_spd = - ProtocolData<::apollo::canbus::Lincoln>::BoundedValue( + ProtocolData<::apollo::canbus::ChassisDetail>::BoundedValue( vehicle_params_.min_steer_angle_rate() / M_PI * 180, vehicle_params_.max_steer_angle_rate() / M_PI * 180, vehicle_params_.max_steer_angle_rate() / M_PI * 180 * angle_spd / @@ -648,7 +646,7 @@ void LincolnController::ResetProtocol() { } bool LincolnController::CheckChassisError() { - Lincoln chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); int32_t error_cnt = 0; @@ -673,7 +671,7 @@ bool LincolnController::CheckChassisError() { ((chassis_detail.eps().connector_fault()) << (++error_cnt)); if (!chassis_detail.has_brake()) { - AERROR_EVERY(100) << "Lincoln has NO brake." + AERROR_EVERY(100) << "ChassisDetail has NO brake." << chassis_detail.DebugString(); return false; } @@ -695,7 +693,8 @@ bool LincolnController::CheckChassisError() { ((chassis_detail.brake().connector_fault()) << (++error_cnt)); if (!chassis_detail.has_gas()) { - AERROR_EVERY(100) << "Lincoln has NO gas." << chassis_detail.DebugString(); + AERROR_EVERY(100) << "ChassisDetail has NO gas." + << chassis_detail.DebugString(); return false; } // Throttle fault @@ -714,7 +713,8 @@ bool LincolnController::CheckChassisError() { ((chassis_detail.gas().connector_fault()) << (++error_cnt)); if (!chassis_detail.has_gear()) { - AERROR_EVERY(100) << "Lincoln has NO gear." << chassis_detail.DebugString(); + AERROR_EVERY(100) << "ChassisDetail has NO gear." + << chassis_detail.DebugString(); return false; } // Gear fault @@ -837,7 +837,7 @@ bool LincolnController::CheckResponse(const int32_t flags, bool need_wait) { // for Lincoln, CheckResponse commonly takes 300ms. We leave a 100ms buffer // for it. int32_t retry_num = 20; - Lincoln chassis_detail; + ChassisDetail chassis_detail; bool is_eps_online = false; bool is_vcu_online = false; bool is_esp_online = false; @@ -903,7 +903,7 @@ void LincolnController::set_chassis_error_code( } bool LincolnController::CheckSafetyError( - const ::apollo::canbus::Lincoln &chassis_detail) { + const ::apollo::canbus::ChassisDetail &chassis_detail) { bool safety_error = chassis_detail.safety().is_passenger_door_open() || chassis_detail.safety().is_rearleft_door_open() || diff --git a/modules/canbus_vehicle/lincoln/lincoln_controller.h b/modules/canbus/vehicle/lincoln/lincoln_controller.h similarity index 84% rename from modules/canbus_vehicle/lincoln/lincoln_controller.h rename to modules/canbus/vehicle/lincoln/lincoln_controller.h index 23f65230d21..3467b5c3354 100644 --- a/modules/canbus_vehicle/lincoln/lincoln_controller.h +++ b/modules/canbus/vehicle/lincoln/lincoln_controller.h @@ -26,19 +26,20 @@ #include "gtest/gtest_prod.h" +#include "cyber/common/macros.h" + #include "modules/canbus/proto/canbus_conf.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" #include "modules/common_msgs/basic_msgs/error_code.pb.h" -#include "modules/common_msgs/chassis_msgs/chassis.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" -#include "cyber/common/macros.h" -#include "modules/canbus_vehicle/lincoln/protocol/brake_60.h" -#include "modules/canbus_vehicle/lincoln/protocol/gear_66.h" -#include "modules/canbus_vehicle/lincoln/protocol/steering_64.h" -#include "modules/canbus_vehicle/lincoln/protocol/throttle_62.h" -#include "modules/canbus_vehicle/lincoln/protocol/turnsignal_68.h" +#include "modules/canbus/vehicle/lincoln/protocol/brake_60.h" +#include "modules/canbus/vehicle/lincoln/protocol/gear_66.h" +#include "modules/canbus/vehicle/lincoln/protocol/steering_64.h" +#include "modules/canbus/vehicle/lincoln/protocol/throttle_62.h" +#include "modules/canbus/vehicle/lincoln/protocol/turnsignal_68.h" #include "modules/canbus/vehicle/vehicle_controller.h" /** @@ -54,17 +55,17 @@ namespace lincoln { * * @brief this class implements the vehicle controller for lincoln vehicle. */ -class LincolnController final - : public VehicleController<::apollo::canbus::Lincoln> { +class LincolnController final : public VehicleController { public: /** * @brief initialize the lincoln vehicle controller. * @return init error_code */ - common::ErrorCode Init(const VehicleParameter ¶ms, - CanSender<::apollo::canbus::Lincoln> *const can_sender, - MessageManager<::apollo::canbus::Lincoln> - *const message_manager) override; + common::ErrorCode Init( + const VehicleParameter ¶ms, + CanSender<::apollo::canbus::ChassisDetail> *const can_sender, + MessageManager<::apollo::canbus::ChassisDetail> *const message_manager) + override; /** * @brief start the vehicle controller. @@ -126,10 +127,9 @@ class LincolnController final void SetHorn(const control::ControlCommand &command) override; void SetTurningSignal(const control::ControlCommand &command) override; - bool VerifyID() override; void ResetProtocol(); bool CheckChassisError(); - bool CheckSafetyError(const canbus::Lincoln &chassis); + bool CheckSafetyError(const canbus::ChassisDetail &chassis); private: void SecurityDogThreadFunc(); diff --git a/modules/canbus_vehicle/lincoln/lincoln_controller_test.cc b/modules/canbus/vehicle/lincoln/lincoln_controller_test.cc similarity index 93% rename from modules/canbus_vehicle/lincoln/lincoln_controller_test.cc rename to modules/canbus/vehicle/lincoln/lincoln_controller_test.cc index b2609a39ba0..13c224be10a 100644 --- a/modules/canbus_vehicle/lincoln/lincoln_controller_test.cc +++ b/modules/canbus/vehicle/lincoln/lincoln_controller_test.cc @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/lincoln_controller.h" +#include "modules/canbus/vehicle/lincoln/lincoln_controller.h" #include "cyber/common/file.h" #include "gtest/gtest.h" #include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" -#include "modules/canbus_vehicle/lincoln/lincoln_message_manager.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" +#include "modules/canbus/vehicle/lincoln/lincoln_message_manager.h" #include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" #include "modules/drivers/canbus/can_comm/can_sender.h" @@ -52,7 +52,7 @@ class LincolnControllerTest : public ::testing::Test { LincolnController controller_; ControlCommand control_cmd_; VehicleSignal vehicle_signal_; - CanSender<::apollo::canbus::Lincoln> sender_; + CanSender<::apollo::canbus::ChassisDetail> sender_; LincolnMessageManager msg_manager_; CanbusConf canbus_conf_; VehicleParameter params_; diff --git a/modules/canbus_vehicle/lincoln/lincoln_message_manager.cc b/modules/canbus/vehicle/lincoln/lincoln_message_manager.cc similarity index 57% rename from modules/canbus_vehicle/lincoln/lincoln_message_manager.cc rename to modules/canbus/vehicle/lincoln/lincoln_message_manager.cc index 09f41b648e6..4780871b0cf 100644 --- a/modules/canbus_vehicle/lincoln/lincoln_message_manager.cc +++ b/modules/canbus/vehicle/lincoln/lincoln_message_manager.cc @@ -14,31 +14,31 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/lincoln_message_manager.h" +#include "modules/canbus/vehicle/lincoln/lincoln_message_manager.h" -#include "modules/canbus_vehicle/lincoln/protocol/accel_6b.h" -#include "modules/canbus_vehicle/lincoln/protocol/brake_60.h" -#include "modules/canbus_vehicle/lincoln/protocol/brake_61.h" -#include "modules/canbus_vehicle/lincoln/protocol/brakeinfo_74.h" -#include "modules/canbus_vehicle/lincoln/protocol/fuellevel_72.h" -#include "modules/canbus_vehicle/lincoln/protocol/gear_66.h" -#include "modules/canbus_vehicle/lincoln/protocol/gear_67.h" -#include "modules/canbus_vehicle/lincoln/protocol/gps_6d.h" -#include "modules/canbus_vehicle/lincoln/protocol/gps_6e.h" -#include "modules/canbus_vehicle/lincoln/protocol/gps_6f.h" -#include "modules/canbus_vehicle/lincoln/protocol/gyro_6c.h" -#include "modules/canbus_vehicle/lincoln/protocol/license_7e.h" -#include "modules/canbus_vehicle/lincoln/protocol/misc_69.h" -#include "modules/canbus_vehicle/lincoln/protocol/steering_64.h" -#include "modules/canbus_vehicle/lincoln/protocol/steering_65.h" -#include "modules/canbus_vehicle/lincoln/protocol/surround_73.h" -#include "modules/canbus_vehicle/lincoln/protocol/throttle_62.h" -#include "modules/canbus_vehicle/lincoln/protocol/throttle_63.h" -#include "modules/canbus_vehicle/lincoln/protocol/throttleinfo_75.h" -#include "modules/canbus_vehicle/lincoln/protocol/tirepressure_71.h" -#include "modules/canbus_vehicle/lincoln/protocol/turnsignal_68.h" -#include "modules/canbus_vehicle/lincoln/protocol/version_7f.h" -#include "modules/canbus_vehicle/lincoln/protocol/wheelspeed_6a.h" +#include "modules/canbus/vehicle/lincoln/protocol/accel_6b.h" +#include "modules/canbus/vehicle/lincoln/protocol/brake_60.h" +#include "modules/canbus/vehicle/lincoln/protocol/brake_61.h" +#include "modules/canbus/vehicle/lincoln/protocol/brakeinfo_74.h" +#include "modules/canbus/vehicle/lincoln/protocol/fuellevel_72.h" +#include "modules/canbus/vehicle/lincoln/protocol/gear_66.h" +#include "modules/canbus/vehicle/lincoln/protocol/gear_67.h" +#include "modules/canbus/vehicle/lincoln/protocol/gps_6d.h" +#include "modules/canbus/vehicle/lincoln/protocol/gps_6e.h" +#include "modules/canbus/vehicle/lincoln/protocol/gps_6f.h" +#include "modules/canbus/vehicle/lincoln/protocol/gyro_6c.h" +#include "modules/canbus/vehicle/lincoln/protocol/license_7e.h" +#include "modules/canbus/vehicle/lincoln/protocol/misc_69.h" +#include "modules/canbus/vehicle/lincoln/protocol/steering_64.h" +#include "modules/canbus/vehicle/lincoln/protocol/steering_65.h" +#include "modules/canbus/vehicle/lincoln/protocol/surround_73.h" +#include "modules/canbus/vehicle/lincoln/protocol/throttle_62.h" +#include "modules/canbus/vehicle/lincoln/protocol/throttle_63.h" +#include "modules/canbus/vehicle/lincoln/protocol/throttleinfo_75.h" +#include "modules/canbus/vehicle/lincoln/protocol/tirepressure_71.h" +#include "modules/canbus/vehicle/lincoln/protocol/turnsignal_68.h" +#include "modules/canbus/vehicle/lincoln/protocol/version_7f.h" +#include "modules/canbus/vehicle/lincoln/protocol/wheelspeed_6a.h" namespace apollo { namespace canbus { diff --git a/modules/canbus_vehicle/lincoln/lincoln_message_manager.h b/modules/canbus/vehicle/lincoln/lincoln_message_manager.h similarity index 92% rename from modules/canbus_vehicle/lincoln/lincoln_message_manager.h rename to modules/canbus/vehicle/lincoln/lincoln_message_manager.h index 21f65c9b535..6228be65a35 100644 --- a/modules/canbus_vehicle/lincoln/lincoln_message_manager.h +++ b/modules/canbus/vehicle/lincoln/lincoln_message_manager.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/message_manager.h" /** @@ -40,7 +40,7 @@ using ::apollo::drivers::canbus::MessageManager; * @brief implementation of MessageManager for lincoln vehicle */ class LincolnMessageManager - : public MessageManager<::apollo::canbus::Lincoln> { + : public MessageManager<::apollo::canbus::ChassisDetail> { public: /** * @brief construct a lincoln message manager. protocol data for send and diff --git a/modules/canbus_vehicle/lincoln/lincoln_message_manager_test.cc b/modules/canbus/vehicle/lincoln/lincoln_message_manager_test.cc similarity index 72% rename from modules/canbus_vehicle/lincoln/lincoln_message_manager_test.cc rename to modules/canbus/vehicle/lincoln/lincoln_message_manager_test.cc index 6be8b558d6a..e9a647d81a9 100644 --- a/modules/canbus_vehicle/lincoln/lincoln_message_manager_test.cc +++ b/modules/canbus/vehicle/lincoln/lincoln_message_manager_test.cc @@ -14,37 +14,37 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/lincoln_message_manager.h" +#include "modules/canbus/vehicle/lincoln/lincoln_message_manager.h" #include "gtest/gtest.h" -#include "modules/canbus_vehicle/lincoln/protocol/accel_6b.h" -#include "modules/canbus_vehicle/lincoln/protocol/brake_60.h" -#include "modules/canbus_vehicle/lincoln/protocol/brake_61.h" -#include "modules/canbus_vehicle/lincoln/protocol/brakeinfo_74.h" -#include "modules/canbus_vehicle/lincoln/protocol/fuellevel_72.h" -#include "modules/canbus_vehicle/lincoln/protocol/gear_66.h" -#include "modules/canbus_vehicle/lincoln/protocol/gear_67.h" -#include "modules/canbus_vehicle/lincoln/protocol/gps_6d.h" -#include "modules/canbus_vehicle/lincoln/protocol/gps_6e.h" -#include "modules/canbus_vehicle/lincoln/protocol/gps_6f.h" -#include "modules/canbus_vehicle/lincoln/protocol/gyro_6c.h" -#include "modules/canbus_vehicle/lincoln/protocol/misc_69.h" -#include "modules/canbus_vehicle/lincoln/protocol/steering_64.h" -#include "modules/canbus_vehicle/lincoln/protocol/steering_65.h" -#include "modules/canbus_vehicle/lincoln/protocol/throttle_62.h" -#include "modules/canbus_vehicle/lincoln/protocol/throttle_63.h" -#include "modules/canbus_vehicle/lincoln/protocol/throttleinfo_75.h" -#include "modules/canbus_vehicle/lincoln/protocol/tirepressure_71.h" -#include "modules/canbus_vehicle/lincoln/protocol/turnsignal_68.h" -#include "modules/canbus_vehicle/lincoln/protocol/version_7f.h" -#include "modules/canbus_vehicle/lincoln/protocol/wheelspeed_6a.h" +#include "modules/canbus/vehicle/lincoln/protocol/accel_6b.h" +#include "modules/canbus/vehicle/lincoln/protocol/brake_60.h" +#include "modules/canbus/vehicle/lincoln/protocol/brake_61.h" +#include "modules/canbus/vehicle/lincoln/protocol/brakeinfo_74.h" +#include "modules/canbus/vehicle/lincoln/protocol/fuellevel_72.h" +#include "modules/canbus/vehicle/lincoln/protocol/gear_66.h" +#include "modules/canbus/vehicle/lincoln/protocol/gear_67.h" +#include "modules/canbus/vehicle/lincoln/protocol/gps_6d.h" +#include "modules/canbus/vehicle/lincoln/protocol/gps_6e.h" +#include "modules/canbus/vehicle/lincoln/protocol/gps_6f.h" +#include "modules/canbus/vehicle/lincoln/protocol/gyro_6c.h" +#include "modules/canbus/vehicle/lincoln/protocol/misc_69.h" +#include "modules/canbus/vehicle/lincoln/protocol/steering_64.h" +#include "modules/canbus/vehicle/lincoln/protocol/steering_65.h" +#include "modules/canbus/vehicle/lincoln/protocol/throttle_62.h" +#include "modules/canbus/vehicle/lincoln/protocol/throttle_63.h" +#include "modules/canbus/vehicle/lincoln/protocol/throttleinfo_75.h" +#include "modules/canbus/vehicle/lincoln/protocol/tirepressure_71.h" +#include "modules/canbus/vehicle/lincoln/protocol/turnsignal_68.h" +#include "modules/canbus/vehicle/lincoln/protocol/version_7f.h" +#include "modules/canbus/vehicle/lincoln/protocol/wheelspeed_6a.h" namespace apollo { namespace canbus { namespace lincoln { -using ::apollo::canbus::Lincoln; +using ::apollo::canbus::ChassisDetail; using ::apollo::drivers::canbus::ProtocolData; class LincolnMessageManagerTest : public ::testing::Test { @@ -54,7 +54,7 @@ class LincolnMessageManagerTest : public ::testing::Test { TEST_F(LincolnMessageManagerTest, Accel6b) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Accel6b::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Accel6b::ID); @@ -62,7 +62,7 @@ TEST_F(LincolnMessageManagerTest, Accel6b) { TEST_F(LincolnMessageManagerTest, Brake60) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Brake60::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Brake60::ID); @@ -70,7 +70,7 @@ TEST_F(LincolnMessageManagerTest, Brake60) { TEST_F(LincolnMessageManagerTest, Brake61) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Brake61::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Brake61::ID); @@ -78,7 +78,7 @@ TEST_F(LincolnMessageManagerTest, Brake61) { TEST_F(LincolnMessageManagerTest, Brakeinfo74) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Brakeinfo74::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Brakeinfo74::ID); @@ -86,7 +86,7 @@ TEST_F(LincolnMessageManagerTest, Brakeinfo74) { TEST_F(LincolnMessageManagerTest, Fuellevel72) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Fuellevel72::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Fuellevel72::ID); @@ -94,7 +94,7 @@ TEST_F(LincolnMessageManagerTest, Fuellevel72) { TEST_F(LincolnMessageManagerTest, Gear66) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Gear66::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Gear66::ID); @@ -102,7 +102,7 @@ TEST_F(LincolnMessageManagerTest, Gear66) { TEST_F(LincolnMessageManagerTest, Gear67) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Gear67::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Gear67::ID); @@ -110,7 +110,7 @@ TEST_F(LincolnMessageManagerTest, Gear67) { TEST_F(LincolnMessageManagerTest, Gps6d) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Gps6d::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Gps6d::ID); @@ -118,7 +118,7 @@ TEST_F(LincolnMessageManagerTest, Gps6d) { TEST_F(LincolnMessageManagerTest, Gps6e) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Gps6e::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Gps6e::ID); @@ -126,7 +126,7 @@ TEST_F(LincolnMessageManagerTest, Gps6e) { TEST_F(LincolnMessageManagerTest, Gps6f) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Gps6f::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Gps6f::ID); @@ -134,7 +134,7 @@ TEST_F(LincolnMessageManagerTest, Gps6f) { TEST_F(LincolnMessageManagerTest, Gyro6c) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Gyro6c::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Gyro6c::ID); @@ -142,7 +142,7 @@ TEST_F(LincolnMessageManagerTest, Gyro6c) { TEST_F(LincolnMessageManagerTest, Misc69) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Misc69::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Misc69::ID); @@ -150,7 +150,7 @@ TEST_F(LincolnMessageManagerTest, Misc69) { TEST_F(LincolnMessageManagerTest, Steering64) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Steering64::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Steering64::ID); @@ -158,7 +158,7 @@ TEST_F(LincolnMessageManagerTest, Steering64) { TEST_F(LincolnMessageManagerTest, Steering65) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Steering65::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Steering65::ID); @@ -166,7 +166,7 @@ TEST_F(LincolnMessageManagerTest, Steering65) { TEST_F(LincolnMessageManagerTest, Throttle62) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Throttle62::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Throttle62::ID); @@ -174,7 +174,7 @@ TEST_F(LincolnMessageManagerTest, Throttle62) { TEST_F(LincolnMessageManagerTest, Throttle63) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Throttle63::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Throttle63::ID); @@ -182,7 +182,7 @@ TEST_F(LincolnMessageManagerTest, Throttle63) { TEST_F(LincolnMessageManagerTest, Throttleinfo75) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Throttleinfo75::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Throttleinfo75::ID); @@ -190,7 +190,7 @@ TEST_F(LincolnMessageManagerTest, Throttleinfo75) { TEST_F(LincolnMessageManagerTest, Tirepressure71) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Tirepressure71::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Tirepressure71::ID); @@ -198,7 +198,7 @@ TEST_F(LincolnMessageManagerTest, Tirepressure71) { TEST_F(LincolnMessageManagerTest, Turnsignal68) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Turnsignal68::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Turnsignal68::ID); @@ -206,7 +206,7 @@ TEST_F(LincolnMessageManagerTest, Turnsignal68) { TEST_F(LincolnMessageManagerTest, Version7f) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Version7f::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Version7f::ID); @@ -214,7 +214,7 @@ TEST_F(LincolnMessageManagerTest, Version7f) { TEST_F(LincolnMessageManagerTest, Wheelspeed6a) { LincolnMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Wheelspeed6a::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Wheelspeed6a::ID); diff --git a/modules/third_party_perception/tools/filter.h b/modules/canbus/vehicle/lincoln/lincoln_vehicle_factory.cc similarity index 53% rename from modules/third_party_perception/tools/filter.h rename to modules/canbus/vehicle/lincoln/lincoln_vehicle_factory.cc index 09409a9663c..7f7ec5fbf6e 100644 --- a/modules/third_party_perception/tools/filter.h +++ b/modules/canbus/vehicle/lincoln/lincoln_vehicle_factory.cc @@ -14,25 +14,26 @@ * limitations under the License. *****************************************************************************/ -/** - * @file - */ +#include "modules/canbus/vehicle/lincoln/lincoln_vehicle_factory.h" -#pragma once +#include "cyber/common/log.h" +#include "modules/canbus/vehicle/lincoln/lincoln_controller.h" +#include "modules/canbus/vehicle/lincoln/lincoln_message_manager.h" +#include "modules/common/util/util.h" -#include "modules/third_party_perception/proto/radar_obstacle.pb.h" - -/** - * @namespace apollo::third_party_perception::filter - * @brief apollo::third_party_perception - */ namespace apollo { -namespace third_party_perception { -namespace filter { +namespace canbus { + +std::unique_ptr +LincolnVehicleFactory::CreateVehicleController() { + return std::unique_ptr(new lincoln::LincolnController()); +} -RadarObstacles FilterRadarObstacles(const RadarObstacles& radar_obstacles); -bool IsPreserved(const RadarObstacle& radar_obstacle); +std::unique_ptr> +LincolnVehicleFactory::CreateMessageManager() { + return std::unique_ptr>( + new lincoln::LincolnMessageManager()); +} -} // namespace filter -} // namespace third_party_perception +} // namespace canbus } // namespace apollo diff --git a/modules/canbus/vehicle/lincoln/lincoln_vehicle_factory.h b/modules/canbus/vehicle/lincoln/lincoln_vehicle_factory.h new file mode 100644 index 00000000000..37cf6679012 --- /dev/null +++ b/modules/canbus/vehicle/lincoln/lincoln_vehicle_factory.h @@ -0,0 +1,65 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file lincoln_vehicle_factory.h + */ + +#pragma once + +#include + +#include "modules/canbus/proto/vehicle_parameter.pb.h" +#include "modules/canbus/vehicle/abstract_vehicle_factory.h" +#include "modules/canbus/vehicle/vehicle_controller.h" +#include "modules/drivers/canbus/can_comm/message_manager.h" + +/** + * @namespace apollo::canbus + * @brief apollo::canbus + */ +namespace apollo { +namespace canbus { + +/** + * @class LincolnVehicleFactory + * + * @brief this class is inherited from AbstractVehicleFactory. It can be used to + * create controller and message manager for lincoln vehicle. + */ +class LincolnVehicleFactory : public AbstractVehicleFactory { + public: + /** + * @brief destructor + */ + virtual ~LincolnVehicleFactory() = default; + + /** + * @brief create lincoln vehicle controller + * @returns a unique_ptr that points to the created controller + */ + std::unique_ptr CreateVehicleController() override; + + /** + * @brief create lincoln message manager + * @returns a unique_ptr that points to the created message manager + */ + std::unique_ptr> + CreateMessageManager() override; +}; + +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/lincoln/lincoln_vehicle_factory_test.cc b/modules/canbus/vehicle/lincoln/lincoln_vehicle_factory_test.cc similarity index 64% rename from modules/canbus_vehicle/lincoln/lincoln_vehicle_factory_test.cc rename to modules/canbus/vehicle/lincoln/lincoln_vehicle_factory_test.cc index 793f37386fc..979c8f461fd 100644 --- a/modules/canbus_vehicle/lincoln/lincoln_vehicle_factory_test.cc +++ b/modules/canbus/vehicle/lincoln/lincoln_vehicle_factory_test.cc @@ -14,40 +14,34 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/lincoln_vehicle_factory.h" +#include "modules/canbus/vehicle/lincoln/lincoln_vehicle_factory.h" #include "gtest/gtest.h" -#include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "cyber/common/file.h" - namespace apollo { namespace canbus { class LincolnVehicleFactoryTest : public ::testing::Test { public: virtual void SetUp() { - std::string canbus_conf_file = - "/apollo/modules/canbus_vehicle/lincoln/testdata/" - "mkz_canbus_conf_test.pb.txt"; - cyber::common::GetProtoFromFile(canbus_conf_file, &canbus_conf_); - params_ = canbus_conf_.vehicle_parameter(); - params_.set_brand(apollo::common::LINCOLN_MKZ); - lincoln_factory_.SetVehicleParameter(params_); + VehicleParameter parameter; + parameter.set_brand(apollo::common::LINCOLN_MKZ); + lincoln_factory_.SetVehicleParameter(parameter); } virtual void TearDown() {} protected: LincolnVehicleFactory lincoln_factory_; - CanbusConf canbus_conf_; - VehicleParameter params_; }; TEST_F(LincolnVehicleFactoryTest, InitVehicleController) { - apollo::cyber::Init("vehicle_factory_test"); - EXPECT_EQ(lincoln_factory_.Init(&canbus_conf_), true); + EXPECT_NE(lincoln_factory_.CreateVehicleController(), nullptr); +} + +TEST_F(LincolnVehicleFactoryTest, InitMessageManager) { + EXPECT_NE(lincoln_factory_.CreateMessageManager(), nullptr); } } // namespace canbus diff --git a/modules/canbus_vehicle/lincoln/protocol/BUILD b/modules/canbus/vehicle/lincoln/protocol/BUILD similarity index 72% rename from modules/canbus_vehicle/lincoln/protocol/BUILD rename to modules/canbus/vehicle/lincoln/protocol/BUILD index 8e9501b0530..6a34e1fb001 100644 --- a/modules/canbus_vehicle/lincoln/protocol/BUILD +++ b/modules/canbus/vehicle/lincoln/protocol/BUILD @@ -3,8 +3,6 @@ load("//tools:cpplint.bzl", "cpplint") package(default_visibility = ["//visibility:public"]) -CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] - cc_library( name = "canbus_lincoln_protocol", srcs = [ @@ -57,9 +55,9 @@ cc_library( "version_7f.h", "wheelspeed_6a.h", ], - copts = CANBUS_COPTS, + copts = ["-DMODULE_NAME=\\\"canbus\\\""], deps = [ - "//modules/canbus_vehicle/lincoln/proto:lincoln_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -70,10 +68,9 @@ cc_test( size = "small", srcs = ["accel_6b_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -81,10 +78,9 @@ cc_test( size = "small", srcs = ["brake_60_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -92,10 +88,9 @@ cc_test( size = "small", srcs = ["brake_61_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -103,10 +98,9 @@ cc_test( size = "small", srcs = ["brakeinfo_74_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -114,10 +108,9 @@ cc_test( size = "small", srcs = ["fuellevel_72_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -125,10 +118,9 @@ cc_test( size = "small", srcs = ["gear_66_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -136,10 +128,9 @@ cc_test( size = "small", srcs = ["gear_67_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -147,10 +138,9 @@ cc_test( size = "small", srcs = ["gps_6d_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -158,10 +148,9 @@ cc_test( size = "small", srcs = ["gps_6e_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -169,10 +158,9 @@ cc_test( size = "small", srcs = ["gps_6f_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -180,10 +168,9 @@ cc_test( size = "small", srcs = ["gyro_6c_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -191,10 +178,9 @@ cc_test( size = "small", srcs = ["misc_69_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -202,10 +188,9 @@ cc_test( size = "small", srcs = ["steering_64_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -213,10 +198,9 @@ cc_test( size = "small", srcs = ["steering_65_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -224,10 +208,9 @@ cc_test( size = "small", srcs = ["throttle_62_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -235,10 +218,9 @@ cc_test( size = "small", srcs = ["throttle_63_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -246,10 +228,9 @@ cc_test( size = "small", srcs = ["throttleinfo_75_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -257,10 +238,9 @@ cc_test( size = "small", srcs = ["tirepressure_71_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -268,10 +248,9 @@ cc_test( size = "small", srcs = ["turnsignal_68_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -279,10 +258,9 @@ cc_test( size = "small", srcs = ["version_7f_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -290,10 +268,9 @@ cc_test( size = "small", srcs = ["wheelspeed_6a_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -301,10 +278,9 @@ cc_test( size = "small", srcs = ["surround_73_test.cc"], deps = [ - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", + "//modules/canbus/vehicle/lincoln/protocol:canbus_lincoln_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cpplint() diff --git a/modules/canbus_vehicle/lincoln/protocol/accel_6b.cc b/modules/canbus/vehicle/lincoln/protocol/accel_6b.cc similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/accel_6b.cc rename to modules/canbus/vehicle/lincoln/protocol/accel_6b.cc index 8f623972621..db7ece5af0e 100644 --- a/modules/canbus_vehicle/lincoln/protocol/accel_6b.cc +++ b/modules/canbus/vehicle/lincoln/protocol/accel_6b.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/accel_6b.h" +#include "modules/canbus/vehicle/lincoln/protocol/accel_6b.h" #include "glog/logging.h" @@ -30,7 +30,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Accel6b::ID = 0x6B; void Accel6b::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { chassis_detail->mutable_vehicle_spd()->set_lat_acc( lateral_acceleration(bytes, length)); chassis_detail->mutable_vehicle_spd()->set_long_acc( diff --git a/modules/canbus_vehicle/lincoln/protocol/accel_6b.h b/modules/canbus/vehicle/lincoln/protocol/accel_6b.h similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/accel_6b.h rename to modules/canbus/vehicle/lincoln/protocol/accel_6b.h index 61e31cadc1b..d6d190294b6 100644 --- a/modules/canbus_vehicle/lincoln/protocol/accel_6b.h +++ b/modules/canbus/vehicle/lincoln/protocol/accel_6b.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Accel6b : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -49,7 +49,7 @@ class Accel6b : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; private: /** diff --git a/modules/canbus_vehicle/lincoln/protocol/accel_6b_test.cc b/modules/canbus/vehicle/lincoln/protocol/accel_6b_test.cc similarity index 94% rename from modules/canbus_vehicle/lincoln/protocol/accel_6b_test.cc rename to modules/canbus/vehicle/lincoln/protocol/accel_6b_test.cc index 31719001288..2b074e67a75 100644 --- a/modules/canbus_vehicle/lincoln/protocol/accel_6b_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/accel_6b_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/accel_6b.h" +#include "modules/canbus/vehicle/lincoln/protocol/accel_6b.h" #include "gtest/gtest.h" @@ -30,7 +30,7 @@ class Accel6bTest : public ::testing::Test { TEST_F(Accel6bTest, Parse) { Accel6b acc; int32_t length = 8; - Lincoln chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0, 0}; bytes[0] = 0b11111100; diff --git a/modules/canbus_vehicle/lincoln/protocol/brake_60.cc b/modules/canbus/vehicle/lincoln/protocol/brake_60.cc similarity index 98% rename from modules/canbus_vehicle/lincoln/protocol/brake_60.cc rename to modules/canbus/vehicle/lincoln/protocol/brake_60.cc index 3cf14d7bb72..656c8cf9184 100644 --- a/modules/canbus_vehicle/lincoln/protocol/brake_60.cc +++ b/modules/canbus/vehicle/lincoln/protocol/brake_60.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/brake_60.h" +#include "modules/canbus/vehicle/lincoln/protocol/brake_60.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lincoln/protocol/brake_60.h b/modules/canbus/vehicle/lincoln/protocol/brake_60.h similarity index 97% rename from modules/canbus_vehicle/lincoln/protocol/brake_60.h rename to modules/canbus/vehicle/lincoln/protocol/brake_60.h index cb3798d00bc..5a59e291a9c 100644 --- a/modules/canbus_vehicle/lincoln/protocol/brake_60.h +++ b/modules/canbus/vehicle/lincoln/protocol/brake_60.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Brake60 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; /** diff --git a/modules/canbus_vehicle/lincoln/protocol/brake_60_test.cc b/modules/canbus/vehicle/lincoln/protocol/brake_60_test.cc similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/brake_60_test.cc rename to modules/canbus/vehicle/lincoln/protocol/brake_60_test.cc index dcc0ed7a455..161f32df496 100644 --- a/modules/canbus_vehicle/lincoln/protocol/brake_60_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/brake_60_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/brake_60.h" +#include "modules/canbus/vehicle/lincoln/protocol/brake_60.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/lincoln/protocol/brake_61.cc b/modules/canbus/vehicle/lincoln/protocol/brake_61.cc similarity index 98% rename from modules/canbus_vehicle/lincoln/protocol/brake_61.cc rename to modules/canbus/vehicle/lincoln/protocol/brake_61.cc index 816af942134..4d75aac5fcb 100644 --- a/modules/canbus_vehicle/lincoln/protocol/brake_61.cc +++ b/modules/canbus/vehicle/lincoln/protocol/brake_61.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/brake_61.h" +#include "modules/canbus/vehicle/lincoln/protocol/brake_61.h" #include "glog/logging.h" @@ -30,7 +30,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Brake61::ID = 0x61; void Brake61::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { chassis_detail->mutable_brake()->set_brake_input(pedal_input(bytes, length)); chassis_detail->mutable_brake()->set_brake_cmd(pedal_cmd(bytes, length)); chassis_detail->mutable_brake()->set_brake_output( diff --git a/modules/canbus_vehicle/lincoln/protocol/brake_61.h b/modules/canbus/vehicle/lincoln/protocol/brake_61.h similarity index 98% rename from modules/canbus_vehicle/lincoln/protocol/brake_61.h rename to modules/canbus/vehicle/lincoln/protocol/brake_61.h index 08b9c282afb..3680dd78c72 100644 --- a/modules/canbus_vehicle/lincoln/protocol/brake_61.h +++ b/modules/canbus/vehicle/lincoln/protocol/brake_61.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Brake61 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -50,7 +50,7 @@ class Brake61 : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; private: /** diff --git a/modules/canbus_vehicle/lincoln/protocol/brake_61_test.cc b/modules/canbus/vehicle/lincoln/protocol/brake_61_test.cc similarity index 96% rename from modules/canbus_vehicle/lincoln/protocol/brake_61_test.cc rename to modules/canbus/vehicle/lincoln/protocol/brake_61_test.cc index c654d35c8dd..dbcd573b42d 100644 --- a/modules/canbus_vehicle/lincoln/protocol/brake_61_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/brake_61_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/brake_61.h" +#include "modules/canbus/vehicle/lincoln/protocol/brake_61.h" #include "gtest/gtest.h" @@ -25,7 +25,7 @@ namespace lincoln { TEST(Brake61Test, General) { uint8_t data[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; int32_t length = 8; - Lincoln cd; + ChassisDetail cd; Brake61 brake; brake.Parse(data, length, &cd); diff --git a/modules/canbus_vehicle/lincoln/protocol/brakeinfo_74.cc b/modules/canbus/vehicle/lincoln/protocol/brakeinfo_74.cc similarity index 98% rename from modules/canbus_vehicle/lincoln/protocol/brakeinfo_74.cc rename to modules/canbus/vehicle/lincoln/protocol/brakeinfo_74.cc index 427aaa5887a..99237ec244f 100644 --- a/modules/canbus_vehicle/lincoln/protocol/brakeinfo_74.cc +++ b/modules/canbus/vehicle/lincoln/protocol/brakeinfo_74.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/brakeinfo_74.h" +#include "modules/canbus/vehicle/lincoln/protocol/brakeinfo_74.h" #include "modules/drivers/canbus/common/byte.h" @@ -27,7 +27,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Brakeinfo74::ID = 0x74; void Brakeinfo74::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { chassis_detail->mutable_brake()->set_brake_torque_req( braking_torque_request(bytes, length)); switch (hill_start_assist_status(bytes, length)) { diff --git a/modules/canbus_vehicle/lincoln/protocol/brakeinfo_74.h b/modules/canbus/vehicle/lincoln/protocol/brakeinfo_74.h similarity index 98% rename from modules/canbus_vehicle/lincoln/protocol/brakeinfo_74.h rename to modules/canbus/vehicle/lincoln/protocol/brakeinfo_74.h index 9737f90483c..f115f28120c 100644 --- a/modules/canbus_vehicle/lincoln/protocol/brakeinfo_74.h +++ b/modules/canbus/vehicle/lincoln/protocol/brakeinfo_74.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Brakeinfo74 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -50,7 +50,7 @@ class Brakeinfo74 : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const override; + ChassisDetail *chassis_detail) const override; private: /* diff --git a/modules/canbus_vehicle/lincoln/protocol/brakeinfo_74_test.cc b/modules/canbus/vehicle/lincoln/protocol/brakeinfo_74_test.cc similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/brakeinfo_74_test.cc rename to modules/canbus/vehicle/lincoln/protocol/brakeinfo_74_test.cc index 52ce03bfc74..db8efed0c9c 100644 --- a/modules/canbus_vehicle/lincoln/protocol/brakeinfo_74_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/brakeinfo_74_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/brakeinfo_74.h" +#include "modules/canbus/vehicle/lincoln/protocol/brakeinfo_74.h" #include "gtest/gtest.h" @@ -31,7 +31,7 @@ TEST_F(Brakeinfo74Test, simple) { Brakeinfo74 brakeinfo; uint8_t data[8] = {0x64U, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; int32_t length = 8; - Lincoln cd; + ChassisDetail cd; brakeinfo.Parse(data, length, &cd); EXPECT_TRUE(cd.esp().is_abs_active()); diff --git a/modules/canbus_vehicle/lincoln/protocol/fuellevel_72.cc b/modules/canbus/vehicle/lincoln/protocol/fuellevel_72.cc similarity index 92% rename from modules/canbus_vehicle/lincoln/protocol/fuellevel_72.cc rename to modules/canbus/vehicle/lincoln/protocol/fuellevel_72.cc index 953f5c112d2..f417bf9bfff 100644 --- a/modules/canbus_vehicle/lincoln/protocol/fuellevel_72.cc +++ b/modules/canbus/vehicle/lincoln/protocol/fuellevel_72.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/fuellevel_72.h" +#include "modules/canbus/vehicle/lincoln/protocol/fuellevel_72.h" #include "modules/drivers/canbus/common/byte.h" @@ -27,7 +27,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Fuellevel72::ID = 0x72; void Fuellevel72::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { chassis_detail->mutable_battery()->set_fuel_level(fuel_level(bytes, length)); } diff --git a/modules/canbus_vehicle/lincoln/protocol/fuellevel_72.h b/modules/canbus/vehicle/lincoln/protocol/fuellevel_72.h similarity index 92% rename from modules/canbus_vehicle/lincoln/protocol/fuellevel_72.h rename to modules/canbus/vehicle/lincoln/protocol/fuellevel_72.h index 612f6099ee2..6c2da8069e1 100644 --- a/modules/canbus_vehicle/lincoln/protocol/fuellevel_72.h +++ b/modules/canbus/vehicle/lincoln/protocol/fuellevel_72.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Fuellevel72 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -50,7 +50,7 @@ class Fuellevel72 : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; private: /** diff --git a/modules/canbus_vehicle/lincoln/protocol/fuellevel_72_test.cc b/modules/canbus/vehicle/lincoln/protocol/fuellevel_72_test.cc similarity index 93% rename from modules/canbus_vehicle/lincoln/protocol/fuellevel_72_test.cc rename to modules/canbus/vehicle/lincoln/protocol/fuellevel_72_test.cc index 6e202c81cb0..d08ff5b57ba 100644 --- a/modules/canbus_vehicle/lincoln/protocol/fuellevel_72_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/fuellevel_72_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/fuellevel_72.h" +#include "modules/canbus/vehicle/lincoln/protocol/fuellevel_72.h" #include "gtest/gtest.h" @@ -31,7 +31,7 @@ TEST_F(Accel6bTest, Parse) { Fuellevel72 fuel; uint8_t data[8] = {0x61, 0x62, 0x63, 0x64, 0xF1, 0xF2, 0xF3, 0xF4}; int32_t length = 8; - Lincoln chassis_detail; + ChassisDetail chassis_detail; fuel.Parse(data, length, &chassis_detail); EXPECT_DOUBLE_EQ(chassis_detail.battery().fuel_level(), 2737.50876); EXPECT_EQ(data[0], 0x61); diff --git a/modules/canbus_vehicle/lincoln/protocol/gear_66.cc b/modules/canbus/vehicle/lincoln/protocol/gear_66.cc similarity index 97% rename from modules/canbus_vehicle/lincoln/protocol/gear_66.cc rename to modules/canbus/vehicle/lincoln/protocol/gear_66.cc index f6e82616b23..f3dbd406be7 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gear_66.cc +++ b/modules/canbus/vehicle/lincoln/protocol/gear_66.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/gear_66.h" +#include "modules/canbus/vehicle/lincoln/protocol/gear_66.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lincoln/protocol/gear_66.h b/modules/canbus/vehicle/lincoln/protocol/gear_66.h similarity index 96% rename from modules/canbus_vehicle/lincoln/protocol/gear_66.h rename to modules/canbus/vehicle/lincoln/protocol/gear_66.h index 43b8f693595..4338dca06fd 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gear_66.h +++ b/modules/canbus/vehicle/lincoln/protocol/gear_66.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Gear66 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lincoln/protocol/gear_66_test.cc b/modules/canbus/vehicle/lincoln/protocol/gear_66_test.cc similarity index 96% rename from modules/canbus_vehicle/lincoln/protocol/gear_66_test.cc rename to modules/canbus/vehicle/lincoln/protocol/gear_66_test.cc index 606792ee108..285c7e5b0c0 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gear_66_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/gear_66_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/gear_66.h" +#include "modules/canbus/vehicle/lincoln/protocol/gear_66.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/lincoln/protocol/gear_67.cc b/modules/canbus/vehicle/lincoln/protocol/gear_67.cc similarity index 96% rename from modules/canbus_vehicle/lincoln/protocol/gear_67.cc rename to modules/canbus/vehicle/lincoln/protocol/gear_67.cc index 42a66fe45ae..83e3aed13c2 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gear_67.cc +++ b/modules/canbus/vehicle/lincoln/protocol/gear_67.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/gear_67.h" +#include "modules/canbus/vehicle/lincoln/protocol/gear_67.h" #include "modules/drivers/canbus/common/byte.h" @@ -27,7 +27,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Gear67::ID = 0x67; void Gear67::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { int32_t gear = gear_state(bytes, length); switch (gear) { case 0x01: diff --git a/modules/canbus_vehicle/lincoln/protocol/gear_67.h b/modules/canbus/vehicle/lincoln/protocol/gear_67.h similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/gear_67.h rename to modules/canbus/vehicle/lincoln/protocol/gear_67.h index 419f942650a..92d08fbe3fa 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gear_67.h +++ b/modules/canbus/vehicle/lincoln/protocol/gear_67.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Gear67 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -50,7 +50,7 @@ class Gear67 : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; /** * @brief get the gear state from byte array diff --git a/modules/canbus_vehicle/lincoln/protocol/gear_67_test.cc b/modules/canbus/vehicle/lincoln/protocol/gear_67_test.cc similarity index 94% rename from modules/canbus_vehicle/lincoln/protocol/gear_67_test.cc rename to modules/canbus/vehicle/lincoln/protocol/gear_67_test.cc index 59a2459e74b..3b8d52d7ac2 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gear_67_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/gear_67_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/gear_67.h" +#include "modules/canbus/vehicle/lincoln/protocol/gear_67.h" #include "gtest/gtest.h" @@ -25,7 +25,7 @@ namespace lincoln { TEST(Gear67Test, General) { uint8_t data[8] = {0x56, 0x52, 0x53, 0x54, 0xF1, 0xF2, 0xF3, 0xF4}; int32_t length = 8; - Lincoln cd; + ChassisDetail cd; Gear67 gear; int32_t state = gear.gear_state(data, 8); EXPECT_EQ(state, (data[0] & 0b00000111)); diff --git a/modules/canbus_vehicle/lincoln/protocol/gps_6d.cc b/modules/canbus/vehicle/lincoln/protocol/gps_6d.cc similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/gps_6d.cc rename to modules/canbus/vehicle/lincoln/protocol/gps_6d.cc index 9819b26fdd3..89080154ac6 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gps_6d.cc +++ b/modules/canbus/vehicle/lincoln/protocol/gps_6d.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/gps_6d.h" +#include "modules/canbus/vehicle/lincoln/protocol/gps_6d.h" #include "modules/drivers/canbus/common/byte.h" @@ -27,7 +27,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Gps6d::ID = 0x6D; void Gps6d::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { chassis_detail->mutable_basic()->set_latitude(latitude(bytes, length)); chassis_detail->mutable_basic()->set_longitude(longitude(bytes, length)); chassis_detail->mutable_basic()->set_gps_valid(is_valid(bytes, length)); diff --git a/modules/canbus_vehicle/lincoln/protocol/gps_6d.h b/modules/canbus/vehicle/lincoln/protocol/gps_6d.h similarity index 94% rename from modules/canbus_vehicle/lincoln/protocol/gps_6d.h rename to modules/canbus/vehicle/lincoln/protocol/gps_6d.h index d1136450e7a..0baf649e16e 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gps_6d.h +++ b/modules/canbus/vehicle/lincoln/protocol/gps_6d.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Gps6d : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -50,7 +50,7 @@ class Gps6d : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; /** * @brief get latitude from byte array diff --git a/modules/canbus_vehicle/lincoln/protocol/gps_6d_test.cc b/modules/canbus/vehicle/lincoln/protocol/gps_6d_test.cc similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/gps_6d_test.cc rename to modules/canbus/vehicle/lincoln/protocol/gps_6d_test.cc index 4337c541fb0..24ccfcc69d8 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gps_6d_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/gps_6d_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/gps_6d.h" +#include "modules/canbus/vehicle/lincoln/protocol/gps_6d.h" #include "gtest/gtest.h" @@ -25,7 +25,7 @@ namespace lincoln { TEST(Gps6dTest, General) { uint8_t data[8] = {0x56, 0x52, 0x53, 0x54, 0xF1, 0xF2, 0xF3, 0xF4}; int32_t length = 8; - Lincoln cd; + ChassisDetail cd; Gps6d gps; gps.Parse(data, length, &cd); diff --git a/modules/canbus_vehicle/lincoln/protocol/gps_6e.cc b/modules/canbus/vehicle/lincoln/protocol/gps_6e.cc similarity index 96% rename from modules/canbus_vehicle/lincoln/protocol/gps_6e.cc rename to modules/canbus/vehicle/lincoln/protocol/gps_6e.cc index 227137bc75f..39e25adaf17 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gps_6e.cc +++ b/modules/canbus/vehicle/lincoln/protocol/gps_6e.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/gps_6e.h" +#include "modules/canbus/vehicle/lincoln/protocol/gps_6e.h" #include "modules/drivers/canbus/common/byte.h" @@ -27,7 +27,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Gps6e::ID = 0x6E; void Gps6e::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { chassis_detail->mutable_basic()->set_year(year(bytes, length)); chassis_detail->mutable_basic()->set_month(month(bytes, length)); chassis_detail->mutable_basic()->set_day(day(bytes, length)); diff --git a/modules/canbus_vehicle/lincoln/protocol/gps_6e.h b/modules/canbus/vehicle/lincoln/protocol/gps_6e.h similarity index 97% rename from modules/canbus_vehicle/lincoln/protocol/gps_6e.h rename to modules/canbus/vehicle/lincoln/protocol/gps_6e.h index bd5f2e3e60c..f84cc7847a5 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gps_6e.h +++ b/modules/canbus/vehicle/lincoln/protocol/gps_6e.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Gps6e : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -50,7 +50,7 @@ class Gps6e : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; /** * @brief get year from byte array diff --git a/modules/canbus_vehicle/lincoln/protocol/gps_6e_test.cc b/modules/canbus/vehicle/lincoln/protocol/gps_6e_test.cc similarity index 94% rename from modules/canbus_vehicle/lincoln/protocol/gps_6e_test.cc rename to modules/canbus/vehicle/lincoln/protocol/gps_6e_test.cc index 3207873d760..e65b251bd3c 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gps_6e_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/gps_6e_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/gps_6e.h" +#include "modules/canbus/vehicle/lincoln/protocol/gps_6e.h" #include "gtest/gtest.h" @@ -25,7 +25,7 @@ namespace lincoln { TEST(Gps6eTest, General) { uint8_t data[8] = {0x56, 0x52, 0x53, 0x54, 0xF1, 0xF2, 0xF3, 0xF4}; int32_t length = 8; - Lincoln cd; + ChassisDetail cd; Gps6e gps; gps.Parse(data, length, &cd); diff --git a/modules/canbus_vehicle/lincoln/protocol/gps_6f.cc b/modules/canbus/vehicle/lincoln/protocol/gps_6f.cc similarity index 96% rename from modules/canbus_vehicle/lincoln/protocol/gps_6f.cc rename to modules/canbus/vehicle/lincoln/protocol/gps_6f.cc index b2e2f9b924f..d06a413e782 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gps_6f.cc +++ b/modules/canbus/vehicle/lincoln/protocol/gps_6f.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/gps_6f.h" +#include "modules/canbus/vehicle/lincoln/protocol/gps_6f.h" #include "modules/drivers/canbus/common/byte.h" @@ -27,7 +27,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Gps6f::ID = 0x6F; void Gps6f::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { chassis_detail->mutable_basic()->set_altitude(altitude(bytes, length)); chassis_detail->mutable_basic()->set_heading(heading(bytes, length)); // speed mph -> mps diff --git a/modules/canbus_vehicle/lincoln/protocol/gps_6f.h b/modules/canbus/vehicle/lincoln/protocol/gps_6f.h similarity index 96% rename from modules/canbus_vehicle/lincoln/protocol/gps_6f.h rename to modules/canbus/vehicle/lincoln/protocol/gps_6f.h index 70452acb278..f7be339bcef 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gps_6f.h +++ b/modules/canbus/vehicle/lincoln/protocol/gps_6f.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Gps6f : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -50,7 +50,7 @@ class Gps6f : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; /** * @brief get altitude from byte array diff --git a/modules/canbus_vehicle/lincoln/protocol/gps_6f_test.cc b/modules/canbus/vehicle/lincoln/protocol/gps_6f_test.cc similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/gps_6f_test.cc rename to modules/canbus/vehicle/lincoln/protocol/gps_6f_test.cc index 72bf439e9dd..aa1bd564e82 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gps_6f_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/gps_6f_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/gps_6f.h" +#include "modules/canbus/vehicle/lincoln/protocol/gps_6f.h" #include "gtest/gtest.h" @@ -25,7 +25,7 @@ namespace lincoln { TEST(Gps6fTest, General) { uint8_t data[8] = {0x56, 0x52, 0x53, 0x54, 0xF1, 0xF2, 0xF3, 0xF4}; int32_t length = 8; - Lincoln cd; + ChassisDetail cd; Gps6f gps; gps.Parse(data, length, &cd); diff --git a/modules/canbus_vehicle/lincoln/protocol/gyro_6c.cc b/modules/canbus/vehicle/lincoln/protocol/gyro_6c.cc similarity index 94% rename from modules/canbus_vehicle/lincoln/protocol/gyro_6c.cc rename to modules/canbus/vehicle/lincoln/protocol/gyro_6c.cc index b1b334b4418..18a5c778e21 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gyro_6c.cc +++ b/modules/canbus/vehicle/lincoln/protocol/gyro_6c.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/gyro_6c.h" +#include "modules/canbus/vehicle/lincoln/protocol/gyro_6c.h" #include "modules/drivers/canbus/common/byte.h" @@ -27,7 +27,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Gyro6c::ID = 0x6C; void Gyro6c::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { chassis_detail->mutable_vehicle_spd()->set_roll_rate( roll_rate(bytes, length)); chassis_detail->mutable_vehicle_spd()->set_yaw_rate(yaw_rate(bytes, length)); diff --git a/modules/canbus_vehicle/lincoln/protocol/gyro_6c.h b/modules/canbus/vehicle/lincoln/protocol/gyro_6c.h similarity index 93% rename from modules/canbus_vehicle/lincoln/protocol/gyro_6c.h rename to modules/canbus/vehicle/lincoln/protocol/gyro_6c.h index 6d32b0af62f..11325a18b13 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gyro_6c.h +++ b/modules/canbus/vehicle/lincoln/protocol/gyro_6c.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Gyro6c : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -50,7 +50,7 @@ class Gyro6c : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; /** * @brief calculate the roll rate based on byte array. diff --git a/modules/canbus_vehicle/lincoln/protocol/gyro_6c_test.cc b/modules/canbus/vehicle/lincoln/protocol/gyro_6c_test.cc similarity index 94% rename from modules/canbus_vehicle/lincoln/protocol/gyro_6c_test.cc rename to modules/canbus/vehicle/lincoln/protocol/gyro_6c_test.cc index e2f06bb4a94..8cab13c4865 100644 --- a/modules/canbus_vehicle/lincoln/protocol/gyro_6c_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/gyro_6c_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/gyro_6c.h" +#include "modules/canbus/vehicle/lincoln/protocol/gyro_6c.h" #include "gtest/gtest.h" @@ -25,7 +25,7 @@ namespace lincoln { TEST(Gyro6cTest, General) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Lincoln cd; + ChassisDetail cd; Gyro6c gyro; gyro.Parse(data, length, &cd); diff --git a/modules/canbus_vehicle/lincoln/protocol/license_7e.cc b/modules/canbus/vehicle/lincoln/protocol/license_7e.cc similarity index 99% rename from modules/canbus_vehicle/lincoln/protocol/license_7e.cc rename to modules/canbus/vehicle/lincoln/protocol/license_7e.cc index 9a41b4c437c..14ce03474e8 100644 --- a/modules/canbus_vehicle/lincoln/protocol/license_7e.cc +++ b/modules/canbus/vehicle/lincoln/protocol/license_7e.cc @@ -12,7 +12,7 @@ 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/canbus_vehicle/lincoln/protocol/license_7e.h" +#include "modules/canbus/vehicle/lincoln/protocol/license_7e.h" #include "modules/drivers/canbus/common/byte.h" @@ -46,7 +46,7 @@ License7e::License7e() parse_success_(false) {} void License7e::Parse(const std::uint8_t* bytes, int length, - Lincoln* chassis_detail) const { + ChassisDetail* chassis_detail) const { if (!parse_success_) { switch (mux(bytes, length)) { case 0x83: diff --git a/modules/canbus_vehicle/lincoln/protocol/license_7e.h b/modules/canbus/vehicle/lincoln/protocol/license_7e.h similarity index 98% rename from modules/canbus_vehicle/lincoln/protocol/license_7e.h rename to modules/canbus/vehicle/lincoln/protocol/license_7e.h index 40a5afa5763..a4a9be83cf9 100644 --- a/modules/canbus_vehicle/lincoln/protocol/license_7e.h +++ b/modules/canbus/vehicle/lincoln/protocol/license_7e.h @@ -17,7 +17,7 @@ #include -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -29,7 +29,7 @@ namespace canbus { namespace lincoln { class License7e : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { private: mutable std::string vin_part0_; mutable std::string vin_part1_; @@ -43,7 +43,7 @@ class License7e : public ::apollo::drivers::canbus::ProtocolData< static const int32_t ID; License7e(); virtual void Parse(const std::uint8_t* bytes, int32_t length, - Lincoln* chassis_detail) const; + ChassisDetail* chassis_detail) const; // config detail: {'name': 'mux', 'offset': 0.0, 'precision': 1.0, 'len': 8, // 'f_type': 'value', 'is_signed_var': False, 'physical_range': '[0|0]', // 'bit': 0, 'type': 'int', 'order': 'intel', 'physical_unit': '""'} diff --git a/modules/canbus_vehicle/lincoln/protocol/misc_69.cc b/modules/canbus/vehicle/lincoln/protocol/misc_69.cc similarity index 99% rename from modules/canbus_vehicle/lincoln/protocol/misc_69.cc rename to modules/canbus/vehicle/lincoln/protocol/misc_69.cc index 141b11d26f8..3b0d92a4cd5 100644 --- a/modules/canbus_vehicle/lincoln/protocol/misc_69.cc +++ b/modules/canbus/vehicle/lincoln/protocol/misc_69.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/misc_69.h" +#include "modules/canbus/vehicle/lincoln/protocol/misc_69.h" #include "modules/drivers/canbus/common/byte.h" @@ -27,7 +27,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Misc69::ID = 0x69; void Misc69::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { int32_t turn_light_type = turn_signal_status(bytes, length); switch (turn_light_type) { case 0: diff --git a/modules/canbus_vehicle/lincoln/protocol/misc_69.h b/modules/canbus/vehicle/lincoln/protocol/misc_69.h similarity index 98% rename from modules/canbus_vehicle/lincoln/protocol/misc_69.h rename to modules/canbus/vehicle/lincoln/protocol/misc_69.h index 8e62243c8b1..a2b2fb1fb90 100644 --- a/modules/canbus_vehicle/lincoln/protocol/misc_69.h +++ b/modules/canbus/vehicle/lincoln/protocol/misc_69.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Misc69 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -50,7 +50,7 @@ class Misc69 : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; /** * @brief calculate the turn signal status based on byte array. diff --git a/modules/canbus_vehicle/lincoln/protocol/misc_69_test.cc b/modules/canbus/vehicle/lincoln/protocol/misc_69_test.cc similarity index 96% rename from modules/canbus_vehicle/lincoln/protocol/misc_69_test.cc rename to modules/canbus/vehicle/lincoln/protocol/misc_69_test.cc index 906bc06230a..1176e1fbe0f 100644 --- a/modules/canbus_vehicle/lincoln/protocol/misc_69_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/misc_69_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/misc_69.h" +#include "modules/canbus/vehicle/lincoln/protocol/misc_69.h" #include "gtest/gtest.h" @@ -25,7 +25,7 @@ namespace lincoln { TEST(Misc69Test, General) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Lincoln cd; + ChassisDetail cd; Misc69 misc; misc.Parse(data, length, &cd); diff --git a/modules/canbus_vehicle/lincoln/protocol/steering_64.cc b/modules/canbus/vehicle/lincoln/protocol/steering_64.cc similarity index 98% rename from modules/canbus_vehicle/lincoln/protocol/steering_64.cc rename to modules/canbus/vehicle/lincoln/protocol/steering_64.cc index 8fb89a54253..5b0c8767022 100644 --- a/modules/canbus_vehicle/lincoln/protocol/steering_64.cc +++ b/modules/canbus/vehicle/lincoln/protocol/steering_64.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/steering_64.h" +#include "modules/canbus/vehicle/lincoln/protocol/steering_64.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lincoln/protocol/steering_64.h b/modules/canbus/vehicle/lincoln/protocol/steering_64.h similarity index 97% rename from modules/canbus_vehicle/lincoln/protocol/steering_64.h rename to modules/canbus/vehicle/lincoln/protocol/steering_64.h index 989f2cb6c73..b8c75154745 100644 --- a/modules/canbus_vehicle/lincoln/protocol/steering_64.h +++ b/modules/canbus/vehicle/lincoln/protocol/steering_64.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Steering64 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lincoln/protocol/steering_64_test.cc b/modules/canbus/vehicle/lincoln/protocol/steering_64_test.cc similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/steering_64_test.cc rename to modules/canbus/vehicle/lincoln/protocol/steering_64_test.cc index 986f99c1165..f216585acb3 100644 --- a/modules/canbus_vehicle/lincoln/protocol/steering_64_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/steering_64_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/steering_64.h" +#include "modules/canbus/vehicle/lincoln/protocol/steering_64.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/lincoln/protocol/steering_65.cc b/modules/canbus/vehicle/lincoln/protocol/steering_65.cc similarity index 96% rename from modules/canbus_vehicle/lincoln/protocol/steering_65.cc rename to modules/canbus/vehicle/lincoln/protocol/steering_65.cc index 6c25a1ea03b..1468dbc5a7d 100644 --- a/modules/canbus_vehicle/lincoln/protocol/steering_65.cc +++ b/modules/canbus/vehicle/lincoln/protocol/steering_65.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/steering_65.h" +#include "modules/canbus/vehicle/lincoln/protocol/steering_65.h" #include "modules/drivers/canbus/common/byte.h" @@ -27,7 +27,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Steering65::ID = 0x65; void Steering65::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { chassis_detail->mutable_eps()->set_steering_angle( steering_angle(bytes, length)); // no steering angle speed @@ -69,7 +69,7 @@ void Steering65::Parse(const std::uint8_t *bytes, int32_t length, void Steering65::Parse(const std::uint8_t *bytes, int32_t length, const struct timeval ×tamp, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { chassis_detail->mutable_eps()->set_timestamp_65( static_cast(timestamp.tv_sec) + static_cast(timestamp.tv_usec) / 1000000.0); diff --git a/modules/canbus_vehicle/lincoln/protocol/steering_65.h b/modules/canbus/vehicle/lincoln/protocol/steering_65.h similarity index 97% rename from modules/canbus_vehicle/lincoln/protocol/steering_65.h rename to modules/canbus/vehicle/lincoln/protocol/steering_65.h index 7d586d292e6..5f21f1f5107 100644 --- a/modules/canbus_vehicle/lincoln/protocol/steering_65.h +++ b/modules/canbus/vehicle/lincoln/protocol/steering_65.h @@ -23,7 +23,7 @@ #include -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -40,7 +40,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Steering65 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -51,7 +51,7 @@ class Steering65 : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; /* * @brief parse received data @@ -62,7 +62,7 @@ class Steering65 : public ::apollo::drivers::canbus::ProtocolData< */ virtual void Parse(const std::uint8_t *bytes, int32_t length, const struct timeval ×tamp, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; /** * @brief calculate steering angle based on byte array. diff --git a/modules/canbus_vehicle/lincoln/protocol/steering_65_test.cc b/modules/canbus/vehicle/lincoln/protocol/steering_65_test.cc similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/steering_65_test.cc rename to modules/canbus/vehicle/lincoln/protocol/steering_65_test.cc index 451b8841871..7eefc6c2c6e 100644 --- a/modules/canbus_vehicle/lincoln/protocol/steering_65_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/steering_65_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/steering_65.h" +#include "modules/canbus/vehicle/lincoln/protocol/steering_65.h" #include "gtest/gtest.h" @@ -25,7 +25,7 @@ namespace lincoln { TEST(Steering65Test, General) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Lincoln cd; + ChassisDetail cd; Steering65 steering; steering.Parse(data, length, &cd); diff --git a/modules/canbus_vehicle/lincoln/protocol/surround_73.cc b/modules/canbus/vehicle/lincoln/protocol/surround_73.cc similarity index 98% rename from modules/canbus_vehicle/lincoln/protocol/surround_73.cc rename to modules/canbus/vehicle/lincoln/protocol/surround_73.cc index 24d665af4b7..c977f45fff0 100644 --- a/modules/canbus_vehicle/lincoln/protocol/surround_73.cc +++ b/modules/canbus/vehicle/lincoln/protocol/surround_73.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/surround_73.h" +#include "modules/canbus/vehicle/lincoln/protocol/surround_73.h" #include "modules/drivers/canbus/common/byte.h" @@ -27,7 +27,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Surround73::ID = 0x73; void Surround73::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { // sonar left chassis_detail->mutable_surround()->set_cross_traffic_alert_left( is_cross_traffic_alert_left(bytes, length)); diff --git a/modules/canbus_vehicle/lincoln/protocol/surround_73.h b/modules/canbus/vehicle/lincoln/protocol/surround_73.h similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/surround_73.h rename to modules/canbus/vehicle/lincoln/protocol/surround_73.h index a5e413c2d4f..3fd85334b15 100644 --- a/modules/canbus_vehicle/lincoln/protocol/surround_73.h +++ b/modules/canbus/vehicle/lincoln/protocol/surround_73.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Surround73 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -49,7 +49,7 @@ class Surround73 : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; private: bool is_cross_traffic_alert_left(const std::uint8_t *bytes, diff --git a/modules/canbus_vehicle/lincoln/protocol/surround_73_test.cc b/modules/canbus/vehicle/lincoln/protocol/surround_73_test.cc similarity index 97% rename from modules/canbus_vehicle/lincoln/protocol/surround_73_test.cc rename to modules/canbus/vehicle/lincoln/protocol/surround_73_test.cc index 4759152188a..617b250bd57 100644 --- a/modules/canbus_vehicle/lincoln/protocol/surround_73_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/surround_73_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/surround_73.h" +#include "modules/canbus/vehicle/lincoln/protocol/surround_73.h" #include "gtest/gtest.h" @@ -25,7 +25,7 @@ namespace lincoln { TEST(Surround73Test, General) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x00, 0x53, 0x54}; int32_t length = 8; - Lincoln cd; + ChassisDetail cd; Surround73 surround; surround.Parse(data, length, &cd); diff --git a/modules/canbus_vehicle/lincoln/protocol/throttle_62.cc b/modules/canbus/vehicle/lincoln/protocol/throttle_62.cc similarity index 97% rename from modules/canbus_vehicle/lincoln/protocol/throttle_62.cc rename to modules/canbus/vehicle/lincoln/protocol/throttle_62.cc index 9a4e93ab6d3..da5a086eba8 100644 --- a/modules/canbus_vehicle/lincoln/protocol/throttle_62.cc +++ b/modules/canbus/vehicle/lincoln/protocol/throttle_62.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/throttle_62.h" +#include "modules/canbus/vehicle/lincoln/protocol/throttle_62.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lincoln/protocol/throttle_62.h b/modules/canbus/vehicle/lincoln/protocol/throttle_62.h similarity index 96% rename from modules/canbus_vehicle/lincoln/protocol/throttle_62.h rename to modules/canbus/vehicle/lincoln/protocol/throttle_62.h index af30c0e527d..b196fb79452 100644 --- a/modules/canbus_vehicle/lincoln/protocol/throttle_62.h +++ b/modules/canbus/vehicle/lincoln/protocol/throttle_62.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Throttle62 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lincoln/protocol/throttle_62_test.cc b/modules/canbus/vehicle/lincoln/protocol/throttle_62_test.cc similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/throttle_62_test.cc rename to modules/canbus/vehicle/lincoln/protocol/throttle_62_test.cc index 2cb0397d0b0..ba5ee0017b0 100644 --- a/modules/canbus_vehicle/lincoln/protocol/throttle_62_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/throttle_62_test.cc @@ -13,7 +13,7 @@ See the License for the specific language governing permissions and limitations under the License. =============================================================================*/ -#include "modules/canbus_vehicle/lincoln/protocol/throttle_62.h" +#include "modules/canbus/vehicle/lincoln/protocol/throttle_62.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/lincoln/protocol/throttle_63.cc b/modules/canbus/vehicle/lincoln/protocol/throttle_63.cc similarity index 97% rename from modules/canbus_vehicle/lincoln/protocol/throttle_63.cc rename to modules/canbus/vehicle/lincoln/protocol/throttle_63.cc index cecb6122694..db14c074b27 100644 --- a/modules/canbus_vehicle/lincoln/protocol/throttle_63.cc +++ b/modules/canbus/vehicle/lincoln/protocol/throttle_63.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/throttle_63.h" +#include "modules/canbus/vehicle/lincoln/protocol/throttle_63.h" #include "modules/drivers/canbus/common/byte.h" @@ -27,7 +27,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Throttle63::ID = 0x63; void Throttle63::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { chassis_detail->mutable_gas()->set_throttle_input(pedal_input(bytes, length)); chassis_detail->mutable_gas()->set_throttle_cmd(pedal_cmd(bytes, length)); chassis_detail->mutable_gas()->set_throttle_output( diff --git a/modules/canbus_vehicle/lincoln/protocol/throttle_63.h b/modules/canbus/vehicle/lincoln/protocol/throttle_63.h similarity index 97% rename from modules/canbus_vehicle/lincoln/protocol/throttle_63.h rename to modules/canbus/vehicle/lincoln/protocol/throttle_63.h index e043bdfe11c..aff18407a94 100644 --- a/modules/canbus_vehicle/lincoln/protocol/throttle_63.h +++ b/modules/canbus/vehicle/lincoln/protocol/throttle_63.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Throttle63 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -49,7 +49,7 @@ class Throttle63 : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; /** * @brief calculate pedal input based on byte array. diff --git a/modules/canbus_vehicle/lincoln/protocol/throttle_63_test.cc b/modules/canbus/vehicle/lincoln/protocol/throttle_63_test.cc similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/throttle_63_test.cc rename to modules/canbus/vehicle/lincoln/protocol/throttle_63_test.cc index d90dccfefb1..96fefc21d81 100644 --- a/modules/canbus_vehicle/lincoln/protocol/throttle_63_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/throttle_63_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/throttle_63.h" +#include "modules/canbus/vehicle/lincoln/protocol/throttle_63.h" #include "gtest/gtest.h" @@ -25,7 +25,7 @@ namespace lincoln { TEST(Throttle63Test, General) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Lincoln cd; + ChassisDetail cd; Throttle63 throttle; throttle.Parse(data, length, &cd); diff --git a/modules/canbus_vehicle/lincoln/protocol/throttleinfo_75.cc b/modules/canbus/vehicle/lincoln/protocol/throttleinfo_75.cc similarity index 94% rename from modules/canbus_vehicle/lincoln/protocol/throttleinfo_75.cc rename to modules/canbus/vehicle/lincoln/protocol/throttleinfo_75.cc index 0e80aa24cc7..c0b88309c1a 100644 --- a/modules/canbus_vehicle/lincoln/protocol/throttleinfo_75.cc +++ b/modules/canbus/vehicle/lincoln/protocol/throttleinfo_75.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/throttleinfo_75.h" +#include "modules/canbus/vehicle/lincoln/protocol/throttleinfo_75.h" #include "modules/drivers/canbus/common/byte.h" @@ -27,7 +27,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Throttleinfo75::ID = 0x75; void Throttleinfo75::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { chassis_detail->mutable_ems()->set_engine_rpm(engine_rpm(bytes, length)); chassis_detail->mutable_gas()->set_accelerator_pedal( acc_pedal_percent(bytes, length)); diff --git a/modules/canbus_vehicle/lincoln/protocol/throttleinfo_75.h b/modules/canbus/vehicle/lincoln/protocol/throttleinfo_75.h similarity index 93% rename from modules/canbus_vehicle/lincoln/protocol/throttleinfo_75.h rename to modules/canbus/vehicle/lincoln/protocol/throttleinfo_75.h index 9a5053d8090..23d587ae000 100644 --- a/modules/canbus_vehicle/lincoln/protocol/throttleinfo_75.h +++ b/modules/canbus/vehicle/lincoln/protocol/throttleinfo_75.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Throttleinfo75 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -49,7 +49,7 @@ class Throttleinfo75 : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; /** * @brief calculate engine rpm based on byte array. diff --git a/modules/canbus_vehicle/lincoln/protocol/throttleinfo_75_test.cc b/modules/canbus/vehicle/lincoln/protocol/throttleinfo_75_test.cc similarity index 94% rename from modules/canbus_vehicle/lincoln/protocol/throttleinfo_75_test.cc rename to modules/canbus/vehicle/lincoln/protocol/throttleinfo_75_test.cc index dec98e98936..a978cfa4224 100644 --- a/modules/canbus_vehicle/lincoln/protocol/throttleinfo_75_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/throttleinfo_75_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/throttleinfo_75.h" +#include "modules/canbus/vehicle/lincoln/protocol/throttleinfo_75.h" #include "gtest/gtest.h" @@ -25,7 +25,7 @@ namespace lincoln { TEST(Throttleinfo75Test, General) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Lincoln cd; + ChassisDetail cd; Throttleinfo75 throttle_info; throttle_info.Parse(data, length, &cd); diff --git a/modules/canbus_vehicle/lincoln/protocol/tirepressure_71.cc b/modules/canbus/vehicle/lincoln/protocol/tirepressure_71.cc similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/tirepressure_71.cc rename to modules/canbus/vehicle/lincoln/protocol/tirepressure_71.cc index 61966735483..dd024da670d 100644 --- a/modules/canbus_vehicle/lincoln/protocol/tirepressure_71.cc +++ b/modules/canbus/vehicle/lincoln/protocol/tirepressure_71.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/tirepressure_71.h" +#include "modules/canbus/vehicle/lincoln/protocol/tirepressure_71.h" #include "modules/drivers/canbus/common/byte.h" @@ -27,7 +27,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Tirepressure71::ID = 0x71; void Tirepressure71::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { chassis_detail->mutable_safety()->set_front_left_tire_press( front_left_tire(bytes, length)); chassis_detail->mutable_safety()->set_front_right_tire_press( diff --git a/modules/canbus_vehicle/lincoln/protocol/tirepressure_71.h b/modules/canbus/vehicle/lincoln/protocol/tirepressure_71.h similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/tirepressure_71.h rename to modules/canbus/vehicle/lincoln/protocol/tirepressure_71.h index 05db7a77185..d403ce0e068 100644 --- a/modules/canbus_vehicle/lincoln/protocol/tirepressure_71.h +++ b/modules/canbus/vehicle/lincoln/protocol/tirepressure_71.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Tirepressure71 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -49,7 +49,7 @@ class Tirepressure71 : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; private: /** diff --git a/modules/canbus_vehicle/lincoln/protocol/tirepressure_71_test.cc b/modules/canbus/vehicle/lincoln/protocol/tirepressure_71_test.cc similarity index 94% rename from modules/canbus_vehicle/lincoln/protocol/tirepressure_71_test.cc rename to modules/canbus/vehicle/lincoln/protocol/tirepressure_71_test.cc index 7d21485f270..8a30703d670 100644 --- a/modules/canbus_vehicle/lincoln/protocol/tirepressure_71_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/tirepressure_71_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/tirepressure_71.h" +#include "modules/canbus/vehicle/lincoln/protocol/tirepressure_71.h" #include "gtest/gtest.h" @@ -27,7 +27,7 @@ TEST(Tirepressure71Test, General) { int32_t length = 8; Tirepressure71 tire_pressure; - Lincoln cd; + ChassisDetail cd; tire_pressure.Parse(data, length, &cd); EXPECT_EQ(cd.safety().front_left_tire_press(), 25191); diff --git a/modules/canbus_vehicle/lincoln/protocol/turnsignal_68.cc b/modules/canbus/vehicle/lincoln/protocol/turnsignal_68.cc similarity index 96% rename from modules/canbus_vehicle/lincoln/protocol/turnsignal_68.cc rename to modules/canbus/vehicle/lincoln/protocol/turnsignal_68.cc index 8179cc862aa..a1c8700b3a1 100644 --- a/modules/canbus_vehicle/lincoln/protocol/turnsignal_68.cc +++ b/modules/canbus/vehicle/lincoln/protocol/turnsignal_68.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/turnsignal_68.h" +#include "modules/canbus/vehicle/lincoln/protocol/turnsignal_68.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/lincoln/protocol/turnsignal_68.h b/modules/canbus/vehicle/lincoln/protocol/turnsignal_68.h similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/turnsignal_68.h rename to modules/canbus/vehicle/lincoln/protocol/turnsignal_68.h index 8ba95a61ddd..036a402ff05 100644 --- a/modules/canbus_vehicle/lincoln/protocol/turnsignal_68.h +++ b/modules/canbus/vehicle/lincoln/protocol/turnsignal_68.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Turnsignal68 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/lincoln/protocol/turnsignal_68_test.cc b/modules/canbus/vehicle/lincoln/protocol/turnsignal_68_test.cc similarity index 96% rename from modules/canbus_vehicle/lincoln/protocol/turnsignal_68_test.cc rename to modules/canbus/vehicle/lincoln/protocol/turnsignal_68_test.cc index b91a4fb78f3..cfeff5d2a1b 100644 --- a/modules/canbus_vehicle/lincoln/protocol/turnsignal_68_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/turnsignal_68_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/turnsignal_68.h" +#include "modules/canbus/vehicle/lincoln/protocol/turnsignal_68.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/lincoln/protocol/version_7f.cc b/modules/canbus/vehicle/lincoln/protocol/version_7f.cc similarity index 96% rename from modules/canbus_vehicle/lincoln/protocol/version_7f.cc rename to modules/canbus/vehicle/lincoln/protocol/version_7f.cc index 00b1b26015a..e6be510dd6c 100644 --- a/modules/canbus_vehicle/lincoln/protocol/version_7f.cc +++ b/modules/canbus/vehicle/lincoln/protocol/version_7f.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/version_7f.h" +#include "modules/canbus/vehicle/lincoln/protocol/version_7f.h" #include "modules/drivers/canbus/common/byte.h" @@ -27,7 +27,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Version7f::ID = 0x7f; void Version7f::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { switch (module_name(bytes, length)) { case 0x01: chassis_detail->mutable_brake()->set_major_version( diff --git a/modules/canbus_vehicle/lincoln/protocol/version_7f.h b/modules/canbus/vehicle/lincoln/protocol/version_7f.h similarity index 93% rename from modules/canbus_vehicle/lincoln/protocol/version_7f.h rename to modules/canbus/vehicle/lincoln/protocol/version_7f.h index c47d1be98b8..c84934acc17 100644 --- a/modules/canbus_vehicle/lincoln/protocol/version_7f.h +++ b/modules/canbus/vehicle/lincoln/protocol/version_7f.h @@ -21,7 +21,7 @@ #pragma once -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -38,7 +38,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Version7f : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -49,7 +49,7 @@ class Version7f : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; /** * @brief get module name based on byte array. diff --git a/modules/canbus_vehicle/lincoln/protocol/version_7f_test.cc b/modules/canbus/vehicle/lincoln/protocol/version_7f_test.cc similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/version_7f_test.cc rename to modules/canbus/vehicle/lincoln/protocol/version_7f_test.cc index fb76ed9a45f..7a9058fac17 100644 --- a/modules/canbus_vehicle/lincoln/protocol/version_7f_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/version_7f_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/version_7f.h" +#include "modules/canbus/vehicle/lincoln/protocol/version_7f.h" #include "gtest/gtest.h" @@ -24,7 +24,7 @@ namespace lincoln { TEST(Version7fTest, General) { int32_t length = 8; - Lincoln cd; + ChassisDetail cd; Version7f version; uint8_t data[8] = {0x01, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; diff --git a/modules/canbus_vehicle/lincoln/protocol/wheelspeed_6a.cc b/modules/canbus/vehicle/lincoln/protocol/wheelspeed_6a.cc similarity index 96% rename from modules/canbus_vehicle/lincoln/protocol/wheelspeed_6a.cc rename to modules/canbus/vehicle/lincoln/protocol/wheelspeed_6a.cc index 24e0774da63..57656181f2c 100644 --- a/modules/canbus_vehicle/lincoln/protocol/wheelspeed_6a.cc +++ b/modules/canbus/vehicle/lincoln/protocol/wheelspeed_6a.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/wheelspeed_6a.h" +#include "modules/canbus/vehicle/lincoln/protocol/wheelspeed_6a.h" #include "glog/logging.h" @@ -29,7 +29,7 @@ using ::apollo::drivers::canbus::Byte; const int32_t Wheelspeed6a::ID = 0x6A; void Wheelspeed6a::Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { // how to set direction // what is "valid" // front left @@ -65,7 +65,7 @@ void Wheelspeed6a::Parse(const std::uint8_t *bytes, int32_t length, void Wheelspeed6a::Parse(const std::uint8_t *bytes, int32_t length, const struct timeval ×tamp, - Lincoln *chassis_detail) const { + ChassisDetail *chassis_detail) const { chassis_detail->mutable_vehicle_spd()->set_timestamp_sec( static_cast(timestamp.tv_sec) + static_cast(timestamp.tv_usec) / 1000000.0); diff --git a/modules/canbus_vehicle/lincoln/protocol/wheelspeed_6a.h b/modules/canbus/vehicle/lincoln/protocol/wheelspeed_6a.h similarity index 93% rename from modules/canbus_vehicle/lincoln/protocol/wheelspeed_6a.h rename to modules/canbus/vehicle/lincoln/protocol/wheelspeed_6a.h index 22dbbdba982..83d14a3c493 100644 --- a/modules/canbus_vehicle/lincoln/protocol/wheelspeed_6a.h +++ b/modules/canbus/vehicle/lincoln/protocol/wheelspeed_6a.h @@ -23,8 +23,9 @@ #include -// #include "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" + #include "modules/drivers/canbus/can_comm/protocol_data.h" /** @@ -41,7 +42,7 @@ namespace lincoln { * @brief one of the protocol data of lincoln vehicle */ class Wheelspeed6a : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Lincoln> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; @@ -52,7 +53,7 @@ class Wheelspeed6a : public ::apollo::drivers::canbus::ProtocolData< * @param chassis_detail the parsed chassis_detail */ virtual void Parse(const std::uint8_t *bytes, int32_t length, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; /* * @brief parse received data @@ -63,7 +64,7 @@ class Wheelspeed6a : public ::apollo::drivers::canbus::ProtocolData< */ virtual void Parse(const std::uint8_t *bytes, int32_t length, const struct timeval ×tamp, - Lincoln *chassis_detail) const; + ChassisDetail *chassis_detail) const; private: /** diff --git a/modules/canbus_vehicle/lincoln/protocol/wheelspeed_6a_test.cc b/modules/canbus/vehicle/lincoln/protocol/wheelspeed_6a_test.cc similarity index 95% rename from modules/canbus_vehicle/lincoln/protocol/wheelspeed_6a_test.cc rename to modules/canbus/vehicle/lincoln/protocol/wheelspeed_6a_test.cc index 1d93311400f..52f4c80fe82 100644 --- a/modules/canbus_vehicle/lincoln/protocol/wheelspeed_6a_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/wheelspeed_6a_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/lincoln/protocol/wheelspeed_6a.h" +#include "modules/canbus/vehicle/lincoln/protocol/wheelspeed_6a.h" #include "gtest/gtest.h" @@ -26,7 +26,7 @@ TEST(Wheelspeed6aTest, General) { Wheelspeed6a wheelspeed; uint8_t data[8] = {0x61, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Lincoln cd; + ChassisDetail cd; struct timeval timestamp; gettimeofday(×tamp, NULL); wheelspeed.Parse(data, length, timestamp, &cd); diff --git a/modules/canbus/vehicle/neolix_edu/BUILD b/modules/canbus/vehicle/neolix_edu/BUILD new file mode 100644 index 00000000000..570d06eb243 --- /dev/null +++ b/modules/canbus/vehicle/neolix_edu/BUILD @@ -0,0 +1,87 @@ +load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") +load("//tools:cpplint.bzl", "cpplint") + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "neolix_edu_vehicle_factory", + srcs = [ + "neolix_edu_vehicle_factory.cc", + ], + hdrs = [ + "neolix_edu_vehicle_factory.h", + ], + deps = [ + ":neolix_edu_controller", + ":neolix_edu_message_manager", + "//modules/canbus/vehicle:abstract_vehicle_factory", + ], +) + +cc_library( + name = "neolix_edu_message_manager", + srcs = [ + "neolix_edu_message_manager.cc", + ], + hdrs = [ + "neolix_edu_message_manager.h", + ], + deps = [ + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_library( + name = "neolix_edu_controller", + srcs = [ + "neolix_edu_controller.cc", + ], + hdrs = [ + "neolix_edu_controller.h", + ], + deps = [ + ":neolix_edu_message_manager", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle:vehicle_controller_base", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/drivers/canbus/can_comm:can_sender", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_test( + name = "neolix_edu_controller_test", + size = "small", + srcs = ["neolix_edu_controller_test.cc"], + data = ["//modules/canbus:test_data"], + deps = [ + ":neolix_edu_controller", + "@com_google_googletest//:gtest_main", + ], +) + +cc_test( + name = "neolix_edu_message_manager_test", + size = "small", + srcs = ["neolix_edu_message_manager_test.cc"], + deps = [ + "//modules/canbus/vehicle/neolix_edu:neolix_edu_message_manager", + "@com_google_googletest//:gtest_main", + ], +) + +cc_test( + name = "neolix_edu_vehicle_factory_test", + size = "small", + srcs = ["neolix_edu_vehicle_factory_test.cc"], + deps = [ + ":neolix_edu_vehicle_factory", + "@com_google_googletest//:gtest_main", + ], +) + +cpplint() diff --git a/modules/canbus_vehicle/neolix_edu/neolix_edu_controller.cc b/modules/canbus/vehicle/neolix_edu/neolix_edu_controller.cc similarity index 79% rename from modules/canbus_vehicle/neolix_edu/neolix_edu_controller.cc rename to modules/canbus/vehicle/neolix_edu/neolix_edu_controller.cc index 6b5e0741399..0d519a1a5da 100644 --- a/modules/canbus_vehicle/neolix_edu/neolix_edu_controller.cc +++ b/modules/canbus/vehicle/neolix_edu/neolix_edu_controller.cc @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/neolix_edu_controller.h" +#include "modules/canbus/vehicle/neolix_edu/neolix_edu_controller.h" #include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "cyber/common/log.h" #include "cyber/time/time.h" -#include "modules/canbus_vehicle/neolix_edu/neolix_edu_message_manager.h" +#include "modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.h" #include "modules/canbus/vehicle/vehicle_controller.h" #include "modules/drivers/canbus/can_comm/can_sender.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" @@ -42,8 +42,8 @@ const int32_t CHECK_RESPONSE_SPEED_UNIT_FLAG = 2; ErrorCode Neolix_eduController::Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Neolix_edu>* const can_sender, - MessageManager<::apollo::canbus::Neolix_edu>* const message_manager) { + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) { if (is_initialized_) { AINFO << "Neolix_eduController has already been initiated."; return ErrorCode::CANBUS_ERROR; @@ -150,13 +150,13 @@ void Neolix_eduController::Stop() { Chassis Neolix_eduController::chassis() { chassis_.Clear(); - Neolix_edu chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); // 21, 22, previously 1, 2 - // if (driving_mode() == Chassis::EMERGENCY_MODE) { - // set_chassis_error_code(Chassis::NO_ERROR); - // } + if (driving_mode() == Chassis::EMERGENCY_MODE) { + set_chassis_error_code(Chassis::NO_ERROR); + } chassis_.set_driving_mode(driving_mode()); chassis_.set_error_code(chassis_error_code()); @@ -165,72 +165,81 @@ Chassis Neolix_eduController::chassis() { chassis_.set_engine_started(true); // 3 speed_mps - if (chassis_detail.has_aeb_frontwheelspeed_353() && - chassis_detail.has_aeb_rearwheelspeed_354()) { + if (chassis_detail.neolix_edu().has_aeb_frontwheelspeed_353() && + chassis_detail.neolix_edu().has_aeb_rearwheelspeed_354()) { auto wheelspeed = chassis_.mutable_wheel_speed(); wheelspeed->set_wheel_spd_fl( - chassis_detail.aeb_frontwheelspeed_353().wheelspeed_fl()); + chassis_detail.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fl()); wheelspeed->set_wheel_spd_fr( - chassis_detail.aeb_frontwheelspeed_353().wheelspeed_fr()); + chassis_detail.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fr()); wheelspeed->set_wheel_spd_rl( - chassis_detail.aeb_rearwheelspeed_354().wheelspeed_rl()); + chassis_detail.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rl()); wheelspeed->set_wheel_spd_rr( - chassis_detail.aeb_rearwheelspeed_354().wheelspeed_rr()); + chassis_detail.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rr()); chassis_.set_speed_mps( - (chassis_detail.aeb_frontwheelspeed_353().wheelspeed_fl() + - chassis_detail.aeb_frontwheelspeed_353().wheelspeed_fr() + - chassis_detail.aeb_rearwheelspeed_354().wheelspeed_rl() + - chassis_detail.aeb_rearwheelspeed_354().wheelspeed_rr()) / + (chassis_detail.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fl() + + chassis_detail.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fr() + + chassis_detail.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rl() + + chassis_detail.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rr()) / 4 / 3.6); } else { chassis_.set_speed_mps(0); } // 4 SOC - if (chassis_detail.has_vcu_vehicle_status_report_101() && - chassis_detail.vcu_vehicle_status_report_101().has_vcu_display_soc()) { - chassis_.set_battery_soc_percentage( - chassis_detail.vcu_vehicle_status_report_101().vcu_display_soc()); + if (chassis_detail.neolix_edu().has_vcu_vehicle_status_report_101() && + chassis_detail.neolix_edu() + .vcu_vehicle_status_report_101() + .has_vcu_display_soc()) { + chassis_.set_battery_soc_percentage(chassis_detail.neolix_edu() + .vcu_vehicle_status_report_101() + .vcu_display_soc()); } else { chassis_.set_battery_soc_percentage(0); } // 5 steering - if (chassis_detail.has_vcu_eps_report_57() && - chassis_detail.vcu_eps_report_57().has_vcu_real_angle()) { + if (chassis_detail.neolix_edu().has_vcu_eps_report_57() && + chassis_detail.neolix_edu().vcu_eps_report_57().has_vcu_real_angle()) { chassis_.set_steering_percentage(static_cast( - chassis_detail.vcu_eps_report_57().vcu_real_angle() * 100 / + chassis_detail.neolix_edu().vcu_eps_report_57().vcu_real_angle() * 100 / vehicle_params_.max_steer_angle() * M_PI / 180)); } else { chassis_.set_steering_percentage(0); } // 6 throttle - if (chassis_detail.has_vcu_drive_report_52() && - chassis_detail.vcu_drive_report_52().has_vcu_real_torque()) { + if (chassis_detail.neolix_edu().has_vcu_drive_report_52() && + chassis_detail.neolix_edu().vcu_drive_report_52().has_vcu_real_torque()) { chassis_.set_throttle_percentage( - chassis_detail.vcu_drive_report_52().vcu_real_torque() * 2); + chassis_detail.neolix_edu().vcu_drive_report_52().vcu_real_torque() * + 2); } else { chassis_.set_throttle_percentage(0); } // 7 brake - if (chassis_detail.has_vcu_brake_report_47() && - chassis_detail.vcu_brake_report_47().has_vcu_real_brake()) { + if (chassis_detail.neolix_edu().has_vcu_brake_report_47() && + chassis_detail.neolix_edu().vcu_brake_report_47().has_vcu_real_brake()) { chassis_.set_brake_percentage( - chassis_detail.vcu_brake_report_47().vcu_real_brake()); + chassis_detail.neolix_edu().vcu_brake_report_47().vcu_real_brake()); } else { chassis_.set_brake_percentage(0); } // 8 gear - if (chassis_detail.has_vcu_drive_report_52() && - chassis_detail.vcu_drive_report_52().has_vcu_real_shift()) { - chassis_.set_gear_location((apollo::canbus::Chassis_GearPosition) - chassis_detail.vcu_drive_report_52() - .vcu_real_shift()); + if (chassis_detail.neolix_edu().has_vcu_drive_report_52() && + chassis_detail.neolix_edu().vcu_drive_report_52().has_vcu_real_shift()) { + chassis_.set_gear_location( + (apollo::canbus::Chassis_GearPosition)chassis_detail.neolix_edu() + .vcu_drive_report_52() + .vcu_real_shift()); } // 9 epb - if (chassis_detail.has_vcu_brake_report_47() && - chassis_detail.vcu_brake_report_47().has_vcu_real_parking_status()) { - if (chassis_detail.vcu_brake_report_47().vcu_real_parking_status() == 1) { + if (chassis_detail.neolix_edu().has_vcu_brake_report_47() && + chassis_detail.neolix_edu() + .vcu_brake_report_47() + .has_vcu_real_parking_status()) { + if (chassis_detail.neolix_edu() + .vcu_brake_report_47() + .vcu_real_parking_status() == 1) { chassis_.set_parking_brake(true); } else { chassis_.set_parking_brake(false); @@ -243,7 +252,7 @@ Chassis Neolix_eduController::chassis() { chassis_.set_chassis_error_mask(chassis_error_mask_); } - // 10 give engage_advice based on error_code and canbus feedback + // give engage_advice based on error_code and canbus feedback if (!chassis_error_mask_ && !chassis_.parking_brake() && (chassis_.throttle_percentage() == 0.0)) { chassis_.mutable_engage_advice()->set_advice( @@ -251,46 +260,13 @@ Chassis Neolix_eduController::chassis() { } else { chassis_.mutable_engage_advice()->set_advice( apollo::common::EngageAdvice::DISALLOW_ENGAGE); - } - - // 11 bumper event - if (chassis_detail.has_vcu_brake_report_47() && - chassis_detail.vcu_brake_report_47().has_vcu_ehb_brake_state()) { - if (chassis_detail.vcu_brake_report_47().vcu_ehb_brake_state() == - Vcu_brake_report_47::VCU_EHB_BUMPER_BRAKE) { - chassis_.set_front_bumper_event(Chassis::BUMPER_PRESSED); - chassis_.set_back_bumper_event(Chassis::BUMPER_PRESSED); - } else { - chassis_.set_front_bumper_event(Chassis::BUMPER_NORMAL); - chassis_.set_back_bumper_event(Chassis::BUMPER_NORMAL); - } - } else { - chassis_.set_front_bumper_event(Chassis::BUMPER_INVALID); - chassis_.set_back_bumper_event(Chassis::BUMPER_INVALID); - } - - // 12 add checkresponse signal - if (chassis_detail.has_vcu_brake_report_47() && - chassis_detail.vcu_brake_report_47().has_brake_enable_resp()) { - chassis_.mutable_check_response()->set_is_esp_online( - chassis_detail.vcu_brake_report_47().brake_enable_resp() == 1); - } - if (chassis_detail.has_vcu_drive_report_52() && - chassis_detail.vcu_drive_report_52().has_drive_enable_resp()) { - chassis_.mutable_check_response()->set_is_vcu_online( - chassis_detail.vcu_drive_report_52().drive_enable_resp() == 1); - } - if (chassis_detail.has_vcu_eps_report_57() && - chassis_detail.vcu_eps_report_57().has_drive_enable_resp()) { - chassis_.mutable_check_response()->set_is_eps_online( - chassis_detail.vcu_eps_report_57().drive_enable_resp() == 1); + chassis_.mutable_engage_advice()->set_reason( + "CANBUS not ready, firmware error or emergency button pressed!"); } return chassis_; } -bool Neolix_eduController::VerifyID() { return true; } - void Neolix_eduController::Emergency() { set_driving_mode(Chassis::EMERGENCY_MODE); ResetProtocol(); @@ -310,8 +286,7 @@ ErrorCode Neolix_eduController::EnableAutoMode() { const int32_t flag = CHECK_RESPONSE_STEER_UNIT_FLAG | CHECK_RESPONSE_SPEED_UNIT_FLAG; if (!CheckResponse(flag, true)) { - AERROR << "Failed to switch to COMPLETE_AUTO_DRIVE mode. Please check the " - "emergency button or chassis."; + AERROR << "Failed to switch to COMPLETE_AUTO_DRIVE mode."; Emergency(); set_chassis_error_code(Chassis::CHASSIS_ERROR); return ErrorCode::CANBUS_ERROR; @@ -512,7 +487,6 @@ void Neolix_eduController::SecurityDogThreadFunc() { ++horizontal_ctrl_fail; if (horizontal_ctrl_fail >= kMaxFailAttempt) { emergency_mode = true; - AINFO << "Driving_mode is into emergency by steer manual intervention"; set_chassis_error_code(Chassis::MANUAL_INTERVENTION); } } else { @@ -526,7 +500,6 @@ void Neolix_eduController::SecurityDogThreadFunc() { ++vertical_ctrl_fail; if (vertical_ctrl_fail >= kMaxFailAttempt) { emergency_mode = true; - AINFO << "Driving_mode is into emergency by speed manual intervention"; set_chassis_error_code(Chassis::MANUAL_INTERVENTION); } } else { @@ -540,7 +513,6 @@ void Neolix_eduController::SecurityDogThreadFunc() { if (emergency_mode && mode != Chassis::EMERGENCY_MODE) { set_driving_mode(Chassis::EMERGENCY_MODE); message_manager_->ResetSendMessages(); - can_sender_->Update(); } end = ::apollo::cyber::Time::Now().ToMicrosecond(); std::chrono::duration elapsed{end - start}; @@ -556,7 +528,7 @@ void Neolix_eduController::SecurityDogThreadFunc() { bool Neolix_eduController::CheckResponse(const int32_t flags, bool need_wait) { int32_t retry_num = 20; - Neolix_edu chassis_detail; + ChassisDetail chassis_detail; bool is_eps_online = false; bool is_vcu_online = false; bool is_esp_online = false; diff --git a/modules/canbus_vehicle/neolix_edu/neolix_edu_controller.h b/modules/canbus/vehicle/neolix_edu/neolix_edu_controller.h similarity index 88% rename from modules/canbus_vehicle/neolix_edu/neolix_edu_controller.h rename to modules/canbus/vehicle/neolix_edu/neolix_edu_controller.h index 82c179e6ff7..00fa46f7c0c 100644 --- a/modules/canbus_vehicle/neolix_edu/neolix_edu_controller.h +++ b/modules/canbus/vehicle/neolix_edu/neolix_edu_controller.h @@ -19,32 +19,32 @@ #include #include +#include "modules/canbus/vehicle/vehicle_controller.h" + #include "modules/canbus/proto/canbus_conf.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" #include "modules/common_msgs/basic_msgs/error_code.pb.h" -#include "modules/common_msgs/chassis_msgs/chassis.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_brake_command_46.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_diagnosis_628.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_drive_command_50.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_eps_command_56.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_light_horn_command_310.h" -#include "modules/canbus/vehicle/vehicle_controller.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.h" namespace apollo { namespace canbus { namespace neolix_edu { -class Neolix_eduController final - : public VehicleController<::apollo::canbus::Neolix_edu> { +class Neolix_eduController final : public VehicleController { public: virtual ~Neolix_eduController(); ::apollo::common::ErrorCode Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Neolix_edu>* const can_sender, - MessageManager<::apollo::canbus::Neolix_edu>* const message_manager) + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) override; bool Start() override; @@ -103,7 +103,6 @@ class Neolix_eduController final void SetTurningSignal( const ::apollo::control::ControlCommand& command) override; - bool VerifyID() override; void ResetProtocol(); bool CheckChassisError(); diff --git a/modules/canbus_vehicle/neolix_edu/neolix_edu_controller_test.cc b/modules/canbus/vehicle/neolix_edu/neolix_edu_controller_test.cc similarity index 93% rename from modules/canbus_vehicle/neolix_edu/neolix_edu_controller_test.cc rename to modules/canbus/vehicle/neolix_edu/neolix_edu_controller_test.cc index df692e639d4..6d5f1111040 100644 --- a/modules/canbus_vehicle/neolix_edu/neolix_edu_controller_test.cc +++ b/modules/canbus/vehicle/neolix_edu/neolix_edu_controller_test.cc @@ -13,15 +13,15 @@ *implied. See the License for the specific language governing permissions *and limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/neolix_edu_controller.h" +#include "modules/canbus/vehicle/neolix_edu/neolix_edu_controller.h" #include "cyber/common/file.h" #include "gtest/gtest.h" #include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" -#include "modules/canbus_vehicle/neolix_edu/neolix_edu_message_manager.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" +#include "modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.h" #include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" #include "modules/drivers/canbus/can_comm/can_sender.h" @@ -52,7 +52,7 @@ class Neolix_eduControllerTest : public ::testing::Test { Neolix_eduController controller_; ControlCommand control_cmd_; VehicleSignal vehicle_signal_; - CanSender<::apollo::canbus::Neolix_edu> sender_; + CanSender<::apollo::canbus::ChassisDetail> sender_; Neolix_eduMessageManager msg_manager_; CanbusConf canbus_conf_; VehicleParameter params_; diff --git a/modules/canbus_vehicle/neolix_edu/neolix_edu_message_manager.cc b/modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.cc similarity index 63% rename from modules/canbus_vehicle/neolix_edu/neolix_edu_message_manager.cc rename to modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.cc index 3613058f839..149e9dcd3c5 100644 --- a/modules/canbus_vehicle/neolix_edu/neolix_edu_message_manager.cc +++ b/modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.cc @@ -14,30 +14,30 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/neolix_edu_message_manager.h" +#include "modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_brake_command_46.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_diagnosis_628.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_drive_command_50.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_eps_command_56.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_light_horn_command_310.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_diagresp_718.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_systemstate_11.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/pas_1st_data_311.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/pas_2nd_data_312.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_brake_report_47.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_drive_report_52.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_eps_report_57.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_nm_401.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_powerstatus_214.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h" namespace apollo { namespace canbus { diff --git a/modules/canbus_vehicle/neolix_edu/neolix_edu_message_manager.h b/modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.h similarity index 90% rename from modules/canbus_vehicle/neolix_edu/neolix_edu_message_manager.h rename to modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.h index a3b946909a0..acb1e307372 100644 --- a/modules/canbus_vehicle/neolix_edu/neolix_edu_message_manager.h +++ b/modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/message_manager.h" namespace apollo { @@ -26,7 +26,7 @@ namespace neolix_edu { using ::apollo::drivers::canbus::MessageManager; class Neolix_eduMessageManager - : public MessageManager<::apollo::canbus::Neolix_edu> { + : public MessageManager<::apollo::canbus::ChassisDetail> { public: Neolix_eduMessageManager(); virtual ~Neolix_eduMessageManager(); diff --git a/modules/canbus_vehicle/neolix_edu/neolix_edu_message_manager_test.cc b/modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager_test.cc similarity index 76% rename from modules/canbus_vehicle/neolix_edu/neolix_edu_message_manager_test.cc rename to modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager_test.cc index 49252a3c669..2720506c683 100644 --- a/modules/canbus_vehicle/neolix_edu/neolix_edu_message_manager_test.cc +++ b/modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager_test.cc @@ -14,35 +14,35 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/neolix_edu_message_manager.h" +#include "modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.h" #include "gtest/gtest.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_brake_command_46.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_diagnosis_628.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_drive_command_50.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_eps_command_56.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_light_horn_command_310.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_diagresp_718.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_systemstate_11.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/pas_1st_data_311.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/pas_2nd_data_312.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_brake_report_47.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_drive_report_52.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_eps_report_57.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_nm_401.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_powerstatus_214.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h" -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h" namespace apollo { namespace canbus { namespace neolix_edu { -using ::apollo::canbus::Neolix_edu; +using ::apollo::canbus::ChassisDetail; using ::apollo::drivers::canbus::ProtocolData; class Neolix_eduMessageManagerTest : public ::testing::Test { @@ -52,35 +52,35 @@ class Neolix_eduMessageManagerTest : public ::testing::Test { // Control Messages TEST_F(Neolix_eduMessageManagerTest, Adsbrakecommand46) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Adsbrakecommand46::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Adsbrakecommand46::ID); } TEST_F(Neolix_eduMessageManagerTest, Adsdiagnosis628) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Adsdiagnosis628::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Adsdiagnosis628::ID); } TEST_F(Neolix_eduMessageManagerTest, Adsdrivecommand50) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Adsdrivecommand50::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Adsdrivecommand50::ID); } TEST_F(Neolix_eduMessageManagerTest, Adsepscommand56) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Adsepscommand56::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Adsepscommand56::ID); } TEST_F(Neolix_eduMessageManagerTest, Adslighthorncommand310) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Adslighthorncommand310::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, @@ -90,49 +90,49 @@ TEST_F(Neolix_eduMessageManagerTest, Adslighthorncommand310) { // Report Messages TEST_F(Neolix_eduMessageManagerTest, Aebsystemstate11) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Aebsystemstate11::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Aebsystemstate11::ID); } TEST_F(Neolix_eduMessageManagerTest, Vcubrakereport47) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Vcubrakereport47::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Vcubrakereport47::ID); } TEST_F(Neolix_eduMessageManagerTest, Vcudrivereport52) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Vcudrivereport52::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Vcudrivereport52::ID); } TEST_F(Neolix_eduMessageManagerTest, Vcuepsreport57) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Vcuepsreport57::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Vcuepsreport57::ID); } TEST_F(Neolix_eduMessageManagerTest, Vcunm401) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Vcunm401::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Vcunm401::ID); } TEST_F(Neolix_eduMessageManagerTest, Vcupowerstatus214) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Vcupowerstatus214::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Vcupowerstatus214::ID); } TEST_F(Neolix_eduMessageManagerTest, Vcuvehiclefaultresponse201) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Vcuvehiclefaultresponse201::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, @@ -140,7 +140,7 @@ TEST_F(Neolix_eduMessageManagerTest, Vcuvehiclefaultresponse201) { } TEST_F(Neolix_eduMessageManagerTest, Vcuvehicleinforesponse502) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Vcuvehicleinforesponse502::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, @@ -148,7 +148,7 @@ TEST_F(Neolix_eduMessageManagerTest, Vcuvehicleinforesponse502) { } TEST_F(Neolix_eduMessageManagerTest, Vcuvehiclestatusreport101) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Vcuvehiclestatusreport101::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, @@ -156,21 +156,21 @@ TEST_F(Neolix_eduMessageManagerTest, Vcuvehiclestatusreport101) { } TEST_F(Neolix_eduMessageManagerTest, Aebdiagnosis1626) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Aebdiagnosis1626::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Aebdiagnosis1626::ID); } TEST_F(Neolix_eduMessageManagerTest, Aebdiagresp718) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Aebdiagresp718::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Aebdiagresp718::ID); } TEST_F(Neolix_eduMessageManagerTest, Aebfrontwheelspeed353) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Aebfrontwheelspeed353::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, @@ -178,7 +178,7 @@ TEST_F(Neolix_eduMessageManagerTest, Aebfrontwheelspeed353) { } TEST_F(Neolix_eduMessageManagerTest, Aebrearwheelspeed354) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Aebrearwheelspeed354::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, @@ -186,21 +186,21 @@ TEST_F(Neolix_eduMessageManagerTest, Aebrearwheelspeed354) { } TEST_F(Neolix_eduMessageManagerTest, Aebwheelimpulse355) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Aebwheelimpulse355::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Aebwheelimpulse355::ID); } TEST_F(Neolix_eduMessageManagerTest, Pas1stdata311) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Pas1stdata311::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Pas1stdata311::ID); } TEST_F(Neolix_eduMessageManagerTest, Pas2nddata312) { Neolix_eduMessageManager manager; - ProtocolData *pd = + ProtocolData *pd = manager.GetMutableProtocolDataById(Pas2nddata312::ID); EXPECT_NE(pd, nullptr); EXPECT_EQ(static_cast(pd)->ID, Pas2nddata312::ID); diff --git a/modules/audio/inference/siren_detection_test.cc b/modules/canbus/vehicle/neolix_edu/neolix_edu_vehicle_factory.cc similarity index 52% rename from modules/audio/inference/siren_detection_test.cc rename to modules/canbus/vehicle/neolix_edu/neolix_edu_vehicle_factory.cc index 0b6fa2fdfe7..6980b0d1601 100644 --- a/modules/audio/inference/siren_detection_test.cc +++ b/modules/canbus/vehicle/neolix_edu/neolix_edu_vehicle_factory.cc @@ -14,27 +14,27 @@ * limitations under the License. *****************************************************************************/ -#include "modules/audio/inference/siren_detection.h" +#include "modules/canbus/vehicle/neolix_edu/neolix_edu_vehicle_factory.h" -#include "gtest/gtest.h" +#include "cyber/common/log.h" +#include "modules/canbus/vehicle/neolix_edu/neolix_edu_controller.h" +#include "modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.h" +#include "modules/common/util/util.h" namespace apollo { -namespace audio { +namespace canbus { -class SirenDetectionTest : public ::testing::Test { - public: - virtual void SetUp() {} - - protected: - SirenDetection siren_detection_; -}; +std::unique_ptr +Neolix_eduVehicleFactory::CreateVehicleController() { + return std::unique_ptr( + new neolix_edu::Neolix_eduController()); +} -TEST_F(SirenDetectionTest, is_siren) { - std::vector> signals(4, - (std::vector (72000, 0.01))); - bool result = siren_detection_.Evaluate(signals); - EXPECT_EQ(result, false); +std::unique_ptr> +Neolix_eduVehicleFactory::CreateMessageManager() { + return std::unique_ptr>( + new neolix_edu::Neolix_eduMessageManager()); } -} // namespace audio +} // namespace canbus } // namespace apollo diff --git a/modules/canbus/vehicle/neolix_edu/neolix_edu_vehicle_factory.h b/modules/canbus/vehicle/neolix_edu/neolix_edu_vehicle_factory.h new file mode 100644 index 00000000000..5291f3ecfa0 --- /dev/null +++ b/modules/canbus/vehicle/neolix_edu/neolix_edu_vehicle_factory.h @@ -0,0 +1,65 @@ +/****************************************************************************** + * 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 neolix_edu_vehicle_factory.h + */ + +#pragma once + +#include + +#include "modules/canbus/proto/vehicle_parameter.pb.h" +#include "modules/canbus/vehicle/abstract_vehicle_factory.h" +#include "modules/canbus/vehicle/vehicle_controller.h" +#include "modules/drivers/canbus/can_comm/message_manager.h" + +/** + * @namespace apollo::canbus + * @brief apollo::canbus + */ +namespace apollo { +namespace canbus { + +/** + * @class Neolix_eduVehicleFactory + * + * @brief this class is inherited from AbstractVehicleFactory. It can be used to + * create controller and message manager for neolix_edu vehicle. + */ +class Neolix_eduVehicleFactory : public AbstractVehicleFactory { + public: + /** + * @brief destructor + */ + virtual ~Neolix_eduVehicleFactory() = default; + + /** + * @brief create neolix_edu vehicle controller + * @returns a unique_ptr that points to the created controller + */ + std::unique_ptr CreateVehicleController() override; + + /** + * @brief create neolix_edu message manager + * @returns a unique_ptr that points to the created message manager + */ + std::unique_ptr> + CreateMessageManager() override; +}; + +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/neolix_edu/neolix_edu_vehicle_factory_test.cc b/modules/canbus/vehicle/neolix_edu/neolix_edu_vehicle_factory_test.cc similarity index 55% rename from modules/canbus_vehicle/neolix_edu/neolix_edu_vehicle_factory_test.cc rename to modules/canbus/vehicle/neolix_edu/neolix_edu_vehicle_factory_test.cc index 9c1ece29c4a..130bfcc6c8b 100644 --- a/modules/canbus_vehicle/neolix_edu/neolix_edu_vehicle_factory_test.cc +++ b/modules/canbus/vehicle/neolix_edu/neolix_edu_vehicle_factory_test.cc @@ -1,5 +1,5 @@ /****************************************************************************** - * Copyright 2019 The Apollo Authors. All Rights Reserved. + * 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. @@ -14,40 +14,32 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/neolix_edu_vehicle_factory.h" - +#include "modules/canbus/vehicle/neolix_edu/neolix_edu_vehicle_factory.h" #include "gtest/gtest.h" - -#include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "cyber/common/file.h" - namespace apollo { namespace canbus { class Neolix_eduVehicleFactoryTest : public ::testing::Test { public: virtual void SetUp() { - std::string canbus_conf_file = - "/apollo/modules/canbus_vehicle/neolix_edu/testdata/" - "neolix_edu_canbus_conf_test.pb.txt"; - cyber::common::GetProtoFromFile(canbus_conf_file, &canbus_conf_); - params_ = canbus_conf_.vehicle_parameter(); - params_.set_brand(apollo::common::NEOLIX); - neolix_edu_factory_.SetVehicleParameter(params_); + VehicleParameter parameter; + parameter.set_brand(apollo::common::CH); + ch_factory_.SetVehicleParameter(parameter); } virtual void TearDown() {} protected: - Neolix_eduVehicleFactory neolix_edu_factory_; - CanbusConf canbus_conf_; - VehicleParameter params_; + Neolix_eduVehicleFactory ch_factory_; }; -TEST_F(Neolix_eduVehicleFactoryTest, Init) { - apollo::cyber::Init("vehicle_factory_test"); - EXPECT_EQ(neolix_edu_factory_.Init(&canbus_conf_), true); +TEST_F(Neolix_eduVehicleFactoryTest, InitVehicleController) { + EXPECT_NE(ch_factory_.CreateVehicleController(), nullptr); +} + +TEST_F(Neolix_eduVehicleFactoryTest, InitMessageManager) { + EXPECT_NE(ch_factory_.CreateMessageManager(), nullptr); } } // namespace canbus diff --git a/modules/canbus_vehicle/neolix_edu/protocol/BUILD b/modules/canbus/vehicle/neolix_edu/protocol/BUILD similarity index 79% rename from modules/canbus_vehicle/neolix_edu/protocol/BUILD rename to modules/canbus/vehicle/neolix_edu/protocol/BUILD index 472314c703e..83cdc5d768a 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/BUILD +++ b/modules/canbus/vehicle/neolix_edu/protocol/BUILD @@ -52,7 +52,7 @@ cc_library( "vcu_vehicle_status_report_101.h", ], deps = [ - "//modules/canbus_vehicle/neolix_edu/proto:neolix_edu_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -63,7 +63,7 @@ cc_test( size = "small", srcs = ["ads_brake_command_46_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -73,7 +73,7 @@ cc_test( size = "small", srcs = ["ads_eps_command_56_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -83,7 +83,7 @@ cc_test( size = "small", srcs = ["aeb_diagresp_718_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -93,7 +93,7 @@ cc_test( size = "small", srcs = ["aeb_systemstate_11_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -103,7 +103,7 @@ cc_test( size = "small", srcs = ["pas_2nd_data_312_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -113,7 +113,7 @@ cc_test( size = "small", srcs = ["vcu_eps_report_57_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -123,10 +123,9 @@ cc_test( size = "small", srcs = ["vcu_vehicle_fault_response_201_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -134,7 +133,7 @@ cc_test( size = "small", srcs = ["ads_diagnosis_628_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -144,10 +143,9 @@ cc_test( size = "small", srcs = ["ads_light_horn_command_310_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -155,10 +153,9 @@ cc_test( size = "small", srcs = ["aeb_frontwheelspeed_353_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -166,7 +163,7 @@ cc_test( size = "small", srcs = ["aeb_wheelimpulse_355_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -176,7 +173,7 @@ cc_test( size = "small", srcs = ["vcu_brake_report_47_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -186,10 +183,9 @@ cc_test( size = "small", srcs = ["vcu_nm_401_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -197,10 +193,9 @@ cc_test( size = "small", srcs = ["vcu_vehicle_info_response_502_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -208,7 +203,7 @@ cc_test( size = "small", srcs = ["ads_drive_command_50_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -218,7 +213,7 @@ cc_test( size = "small", srcs = ["aeb_diagnosis1_626_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -228,10 +223,9 @@ cc_test( size = "small", srcs = ["aeb_rearwheelspeed_354_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -239,7 +233,7 @@ cc_test( size = "small", srcs = ["pas_1st_data_311_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -249,7 +243,7 @@ cc_test( size = "small", srcs = ["vcu_drive_report_52_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -259,7 +253,7 @@ cc_test( size = "small", srcs = ["vcu_powerstatus_214_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -269,10 +263,9 @@ cc_test( size = "small", srcs = ["vcu_vehicle_status_report_101_test.cc"], deps = [ - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", + "//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cpplint() diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_brake_command_46.cc b/modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.cc similarity index 98% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_brake_command_46.cc rename to modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.cc index 28643211264..235c95150a0 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_brake_command_46.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_brake_command_46.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_brake_command_46.h b/modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.h similarity index 97% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_brake_command_46.h rename to modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.h index 3c6c800a301..e1078d07dde 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_brake_command_46.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace neolix_edu { class Adsbrakecommand46 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_brake_command_46_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46_test.cc similarity index 95% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_brake_command_46_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46_test.cc index 469c9e59536..56db9b5baff 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_brake_command_46_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_brake_command_46.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_diagnosis_628.cc b/modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.cc similarity index 98% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_diagnosis_628.cc rename to modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.cc index fc2d37b31c2..dd2eaeb8738 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_diagnosis_628.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_diagnosis_628.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_diagnosis_628.h b/modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.h similarity index 96% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_diagnosis_628.h rename to modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.h index 8cd30c3d8b1..c9f838cb45d 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_diagnosis_628.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace neolix_edu { class Adsdiagnosis628 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_diagnosis_628_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628_test.cc similarity index 95% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_diagnosis_628_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628_test.cc index 5090ccab061..54f2181e91c 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_diagnosis_628_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_diagnosis_628.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_drive_command_50.cc b/modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.cc similarity index 98% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_drive_command_50.cc rename to modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.cc index c9d2b6328e9..eea9bbb7034 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_drive_command_50.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_drive_command_50.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_drive_command_50.h b/modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.h similarity index 97% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_drive_command_50.h rename to modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.h index 9e85281a006..b98e157555a 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_drive_command_50.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace neolix_edu { class Adsdrivecommand50 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_drive_command_50_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50_test.cc similarity index 95% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_drive_command_50_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50_test.cc index c96272543ce..d73dee9b313 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_drive_command_50_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_drive_command_50.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_eps_command_56.cc b/modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.cc similarity index 98% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_eps_command_56.cc rename to modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.cc index 11efa8e2a4a..630a463adfe 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_eps_command_56.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_eps_command_56.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_eps_command_56.h b/modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.h similarity index 96% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_eps_command_56.h rename to modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.h index a1bfd7ca090..b0f65732dcf 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_eps_command_56.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace neolix_edu { class Adsepscommand56 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_eps_command_56_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56_test.cc similarity index 95% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_eps_command_56_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56_test.cc index 1d26254a73e..9884f40e040 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_eps_command_56_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_eps_command_56.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_light_horn_command_310.cc b/modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.cc similarity index 98% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_light_horn_command_310.cc rename to modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.cc index e67f7b01295..161835ec399 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_light_horn_command_310.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_light_horn_command_310.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_light_horn_command_310.h b/modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.h similarity index 97% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_light_horn_command_310.h rename to modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.h index 5e658c00ff1..0b012ea8708 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_light_horn_command_310.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace neolix_edu { class Adslighthorncommand310 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/neolix_edu/protocol/ads_light_horn_command_310_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310_test.cc similarity index 96% rename from modules/canbus_vehicle/neolix_edu/protocol/ads_light_horn_command_310_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310_test.cc index 05e7be18ac9..0d4bd385849 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/ads_light_horn_command_310_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/ads_light_horn_command_310.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_diagnosis1_626.cc b/modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626.cc similarity index 84% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_diagnosis1_626.cc rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626.cc index 7847fdb4190..0907b2d0ab3 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_diagnosis1_626.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h" #include "glog/logging.h" @@ -31,11 +31,13 @@ Aebdiagnosis1626::Aebdiagnosis1626() {} const int32_t Aebdiagnosis1626::ID = 0x626; void Aebdiagnosis1626::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_aeb_diagnosis1_626()->set_aeb_softwareversion( - aeb_softwareversion(bytes, length)); - chassis->mutable_aeb_diagnosis1_626()->set_aeb_hardwareversion( - aeb_hardwareversion(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu() + ->mutable_aeb_diagnosis1_626() + ->set_aeb_softwareversion(aeb_softwareversion(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_diagnosis1_626() + ->set_aeb_hardwareversion(aeb_hardwareversion(bytes, length)); } // config detail: {'name': 'aeb_softwareversion', 'offset': 0.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h b/modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h similarity index 91% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h index 151c7369080..cdc6a28b316 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace neolix_edu { class Aebdiagnosis1626 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Aebdiagnosis1626(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'AEB_SoftwareVersion', 'offset': 0.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_diagnosis1_626_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626_test.cc similarity index 87% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_diagnosis1_626_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626_test.cc index bbd637db470..1707a2d647e 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_diagnosis1_626_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Aebdiagnosis1626Test : public ::testing::Test { TEST_F(Aebdiagnosis1626Test, reset) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Aebdiagnosis1626 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b01100111); @@ -45,8 +45,8 @@ TEST_F(Aebdiagnosis1626Test, reset) { EXPECT_EQ(data[6], 0b01010011); EXPECT_EQ(data[7], 0b01010100); - EXPECT_EQ(cd.aeb_diagnosis1_626().aeb_softwareversion(), 83); - EXPECT_EQ(cd.aeb_diagnosis1_626().aeb_hardwareversion(), 84); + EXPECT_EQ(cd.neolix_edu().aeb_diagnosis1_626().aeb_softwareversion(), 83); + EXPECT_EQ(cd.neolix_edu().aeb_diagnosis1_626().aeb_hardwareversion(), 84); } } // namespace neolix_edu diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_diagresp_718.cc b/modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718.cc similarity index 89% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_diagresp_718.cc rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718.cc index 41b12989b84..126cc711d97 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_diagresp_718.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_diagresp_718.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718.h" #include "glog/logging.h" @@ -31,8 +31,8 @@ Aebdiagresp718::Aebdiagresp718() {} const int32_t Aebdiagresp718::ID = 0x718; void Aebdiagresp718::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_aeb_diagresp_718()->set_aeb_diagresp( + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu()->mutable_aeb_diagresp_718()->set_aeb_diagresp( aeb_diagresp(bytes, length)); } diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_diagresp_718.h b/modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718.h similarity index 89% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_diagresp_718.h rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718.h index 1590e8784f3..074d8da9661 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_diagresp_718.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace neolix_edu { class Aebdiagresp718 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Aebdiagresp718(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'AEB_DiagResp', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_diagresp_718_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718_test.cc similarity index 91% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_diagresp_718_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718_test.cc index 3df96dfa1c1..54ed63d2c2e 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_diagresp_718_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_diagresp_718.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Aebdiagresp718Test : public ::testing::Test { TEST_F(Aebdiagresp718Test, reset) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Aebdiagresp718 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b01100111); @@ -45,7 +45,7 @@ TEST_F(Aebdiagresp718Test, reset) { EXPECT_EQ(data[6], 0b01010011); EXPECT_EQ(data[7], 0b01010100); - EXPECT_EQ(cd.aeb_diagresp_718().aeb_diagresp(), true); + EXPECT_EQ(cd.neolix_edu().aeb_diagresp_718().aeb_diagresp(), true); } } // namespace neolix_edu diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.cc b/modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.cc similarity index 80% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.cc rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.cc index d9c606c7103..c60e48300b9 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h" #include "glog/logging.h" @@ -31,29 +31,40 @@ Aebfrontwheelspeed353::Aebfrontwheelspeed353() {} const int32_t Aebfrontwheelspeed353::ID = 0x353; void Aebfrontwheelspeed353::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_aeb_frontwheelspeed_353()->set_vehiclespeedvalid( - vehiclespeedvalid(bytes, length)); - chassis->mutable_aeb_frontwheelspeed_353()->set_vehiclespeed( - vehiclespeed(bytes, length)); - chassis->mutable_aeb_frontwheelspeed_353()->set_vehiclerealdirect( - vehiclerealdirect(bytes, length)); - chassis->mutable_aeb_frontwheelspeed_353()->set_wheelspeed_fl_valid( - wheelspeed_fl_valid(bytes, length)); - chassis->mutable_aeb_frontwheelspeed_353()->set_wheelspeed_fl( - wheelspeed_fl(bytes, length)); - chassis->mutable_aeb_frontwheelspeed_353()->set_wheelspeed_fr_valid( - wheelspeed_fr_valid(bytes, length)); - chassis->mutable_aeb_frontwheelspeed_353()->set_wheelspeed_fr( - wheelspeed_fr(bytes, length)); - chassis->mutable_aeb_frontwheelspeed_353()->set_wheelspeed_fl_direct( - wheelspeed_fl_direct(bytes, length)); - chassis->mutable_aeb_frontwheelspeed_353()->set_wheelspeed_fr_direct( - wheelspeed_fr_direct(bytes, length)); - chassis->mutable_aeb_frontwheelspeed_353()->set_alivecounter_front( - alivecounter_front(bytes, length)); - chassis->mutable_aeb_frontwheelspeed_353()->set_checksum_front( - checksum_front(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu() + ->mutable_aeb_frontwheelspeed_353() + ->set_vehiclespeedvalid(vehiclespeedvalid(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_frontwheelspeed_353() + ->set_vehiclespeed(vehiclespeed(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_frontwheelspeed_353() + ->set_vehiclerealdirect(vehiclerealdirect(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_frontwheelspeed_353() + ->set_wheelspeed_fl_valid(wheelspeed_fl_valid(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_frontwheelspeed_353() + ->set_wheelspeed_fl(wheelspeed_fl(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_frontwheelspeed_353() + ->set_wheelspeed_fr_valid(wheelspeed_fr_valid(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_frontwheelspeed_353() + ->set_wheelspeed_fr(wheelspeed_fr(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_frontwheelspeed_353() + ->set_wheelspeed_fl_direct(wheelspeed_fl_direct(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_frontwheelspeed_353() + ->set_wheelspeed_fr_direct(wheelspeed_fr_direct(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_frontwheelspeed_353() + ->set_alivecounter_front(alivecounter_front(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_frontwheelspeed_353() + ->set_checksum_front(checksum_front(bytes, length)); } // config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h b/modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h similarity index 96% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h index 88fe00a8f78..7968c521ce9 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace neolix_edu { class Aebfrontwheelspeed353 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Aebfrontwheelspeed353(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353_test.cc similarity index 68% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353_test.cc index 6b4dbac1e14..b027883013b 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Aebfrontwheelspeed353Test : public ::testing::Test { TEST_F(Aebfrontwheelspeed353Test, reset) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Aebfrontwheelspeed353 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b01100111); @@ -45,20 +45,20 @@ TEST_F(Aebfrontwheelspeed353Test, reset) { EXPECT_EQ(data[6], 0b01010011); EXPECT_EQ(data[7], 0b01010100); - EXPECT_EQ(cd.aeb_frontwheelspeed_353().vehiclespeedvalid(), + EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().vehiclespeedvalid(), false); - EXPECT_DOUBLE_EQ(cd.aeb_frontwheelspeed_353().vehiclespeed(), + EXPECT_DOUBLE_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().vehiclespeed(), 106.3125); - EXPECT_EQ(cd.aeb_frontwheelspeed_353().vehiclerealdirect(), 3); - EXPECT_EQ(cd.aeb_frontwheelspeed_353().wheelspeed_fl_valid(), + EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().vehiclerealdirect(), 3); + EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fl_valid(), false); - EXPECT_EQ(cd.aeb_frontwheelspeed_353().wheelspeed_fl(), 254.44); - EXPECT_EQ(cd.aeb_frontwheelspeed_353().wheelspeed_fr_valid(), + EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fl(), 254.44); + EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fr_valid(), false); - EXPECT_EQ(cd.aeb_frontwheelspeed_353().wheelspeed_fr(), 208.18); - EXPECT_EQ(cd.aeb_frontwheelspeed_353().wheelspeed_fl_direct(), + EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fr(), 208.18); + EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fl_direct(), 1); - EXPECT_EQ(cd.aeb_frontwheelspeed_353().wheelspeed_fr_direct(), + EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fr_direct(), 1); } diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.cc b/modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.cc similarity index 81% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.cc rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.cc index 09c9e0663c6..1eae6c8b933 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h" #include "glog/logging.h" @@ -31,23 +31,31 @@ Aebrearwheelspeed354::Aebrearwheelspeed354() {} const int32_t Aebrearwheelspeed354::ID = 0x354; void Aebrearwheelspeed354::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_aeb_rearwheelspeed_354()->set_wheelspeed_rl_valid( - wheelspeed_rl_valid(bytes, length)); - chassis->mutable_aeb_rearwheelspeed_354()->set_wheelspeed_rl( - wheelspeed_rl(bytes, length)); - chassis->mutable_aeb_rearwheelspeed_354()->set_wheelspeed_rr_valid( - wheelspeed_rr_valid(bytes, length)); - chassis->mutable_aeb_rearwheelspeed_354()->set_wheelspeed_rr( - wheelspeed_rr(bytes, length)); - chassis->mutable_aeb_rearwheelspeed_354()->set_wheelspeed_rl_direct( - wheelspeed_rl_direct(bytes, length)); - chassis->mutable_aeb_rearwheelspeed_354()->set_wheelspeed_rr_direct( - wheelspeed_rr_direct(bytes, length)); - chassis->mutable_aeb_rearwheelspeed_354()->set_alivecounter_rear( - alivecounter_rear(bytes, length)); - chassis->mutable_aeb_rearwheelspeed_354()->set_checksum_rear( - checksum_rear(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu() + ->mutable_aeb_rearwheelspeed_354() + ->set_wheelspeed_rl_valid(wheelspeed_rl_valid(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_rearwheelspeed_354() + ->set_wheelspeed_rl(wheelspeed_rl(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_rearwheelspeed_354() + ->set_wheelspeed_rr_valid(wheelspeed_rr_valid(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_rearwheelspeed_354() + ->set_wheelspeed_rr(wheelspeed_rr(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_rearwheelspeed_354() + ->set_wheelspeed_rl_direct(wheelspeed_rl_direct(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_rearwheelspeed_354() + ->set_wheelspeed_rr_direct(wheelspeed_rr_direct(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_rearwheelspeed_354() + ->set_alivecounter_rear(alivecounter_rear(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_rearwheelspeed_354() + ->set_checksum_rear(checksum_rear(bytes, length)); } // config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h b/modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h similarity index 95% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h index 6e0a6d2ce3f..8c380812000 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace neolix_edu { class Aebrearwheelspeed354 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Aebrearwheelspeed354(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354_test.cc similarity index 74% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354_test.cc index 1c650c7dfa4..c8c403b883b 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Aebrearwheelspeed354Test : public ::testing::Test { TEST_F(Aebrearwheelspeed354Test, reset) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Aebrearwheelspeed354 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b01100111); @@ -45,14 +45,14 @@ TEST_F(Aebrearwheelspeed354Test, reset) { EXPECT_EQ(data[6], 0b01010011); EXPECT_EQ(data[7], 0b01010100); - EXPECT_EQ(cd.aeb_rearwheelspeed_354().wheelspeed_rl_valid(), + EXPECT_EQ(cd.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rl_valid(), false); - EXPECT_EQ(cd.aeb_rearwheelspeed_354().wheelspeed_rl(), 254.44); - EXPECT_EQ(cd.aeb_rearwheelspeed_354().wheelspeed_rr_valid(), + EXPECT_EQ(cd.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rl(), 254.44); + EXPECT_EQ(cd.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rr_valid(), false); - EXPECT_EQ(cd.aeb_rearwheelspeed_354().wheelspeed_rr(), 208.18); - EXPECT_EQ(cd.aeb_rearwheelspeed_354().wheelspeed_rl_direct(), 1); - EXPECT_EQ(cd.aeb_rearwheelspeed_354().wheelspeed_rr_direct(), 1); + EXPECT_EQ(cd.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rr(), 208.18); + EXPECT_EQ(cd.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rl_direct(), 1); + EXPECT_EQ(cd.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rr_direct(), 1); } } // namespace neolix_edu diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_systemstate_11.cc b/modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11.cc similarity index 85% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_systemstate_11.cc rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11.cc index 4a767a2fbe0..64187281261 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_systemstate_11.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_systemstate_11.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11.h" #include "glog/logging.h" @@ -31,34 +31,37 @@ Aebsystemstate11::Aebsystemstate11() {} const int32_t Aebsystemstate11::ID = 0x11; void Aebsystemstate11::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_aeb_systemstate_11()->set_aeb_state( + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_aeb_state( aeb_state(bytes, length)); - chassis->mutable_aeb_systemstate_11()->set_aeb_brakestate( - aeb_brakestate(bytes, length)); - chassis->mutable_aeb_systemstate_11()->set_faultrank( + chassis->mutable_neolix_edu() + ->mutable_aeb_systemstate_11() + ->set_aeb_brakestate(aeb_brakestate(bytes, length)); + chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_faultrank( faultrank(bytes, length)); - chassis->mutable_aeb_systemstate_11()->set_currenttemperature( - currenttemperature(bytes, length)); - chassis->mutable_aeb_systemstate_11()->set_pas_f1_stop( + chassis->mutable_neolix_edu() + ->mutable_aeb_systemstate_11() + ->set_currenttemperature(currenttemperature(bytes, length)); + chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_f1_stop( pas_f1_stop(bytes, length)); - chassis->mutable_aeb_systemstate_11()->set_pas_f2_stop( + chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_f2_stop( pas_f2_stop(bytes, length)); - chassis->mutable_aeb_systemstate_11()->set_pas_f3_stop( + chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_f3_stop( pas_f3_stop(bytes, length)); - chassis->mutable_aeb_systemstate_11()->set_pas_f4_stop( + chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_f4_stop( pas_f4_stop(bytes, length)); - chassis->mutable_aeb_systemstate_11()->set_pas_b1_stop( + chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_b1_stop( pas_b1_stop(bytes, length)); - chassis->mutable_aeb_systemstate_11()->set_pas_b2_stop( + chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_b2_stop( pas_b2_stop(bytes, length)); - chassis->mutable_aeb_systemstate_11()->set_pas_b3_stop( + chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_b3_stop( pas_b3_stop(bytes, length)); - chassis->mutable_aeb_systemstate_11()->set_pas_b4_stop( + chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_b4_stop( pas_b4_stop(bytes, length)); - chassis->mutable_aeb_systemstate_11()->set_aeb_livecounter_rear( - aeb_livecounter_rear(bytes, length)); - chassis->mutable_aeb_systemstate_11()->set_aeb_cheksum( + chassis->mutable_neolix_edu() + ->mutable_aeb_systemstate_11() + ->set_aeb_livecounter_rear(aeb_livecounter_rear(bytes, length)); + chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_aeb_cheksum( aeb_cheksum(bytes, length)); } diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_systemstate_11.h b/modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11.h similarity index 97% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_systemstate_11.h rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11.h index 4046b6894a7..eee7f68ed5e 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_systemstate_11.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace neolix_edu { class Aebsystemstate11 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Aebsystemstate11(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': '0x00:read only;0x01:brake enable', diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_systemstate_11_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11_test.cc similarity index 62% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_systemstate_11_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11_test.cc index 98017c9bd64..1e3d275a2b8 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_systemstate_11_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_systemstate_11.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Aebsystemstate11Test : public ::testing::Test { TEST_F(Aebsystemstate11Test, reset) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Aebsystemstate11 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b01100111); @@ -45,18 +45,18 @@ TEST_F(Aebsystemstate11Test, reset) { EXPECT_EQ(data[6], 0b01010011); EXPECT_EQ(data[7], 0b01010100); - EXPECT_EQ(cd.aeb_systemstate_11().aeb_state(), 3); - EXPECT_EQ(cd.aeb_systemstate_11().aeb_brakestate(), true); - EXPECT_EQ(cd.aeb_systemstate_11().faultrank(), 2); - EXPECT_EQ(cd.aeb_systemstate_11().currenttemperature(), 59); - EXPECT_EQ(cd.aeb_systemstate_11().pas_f1_stop(), false); - EXPECT_EQ(cd.aeb_systemstate_11().pas_f2_stop(), false); - EXPECT_EQ(cd.aeb_systemstate_11().pas_f3_stop(), true); - EXPECT_EQ(cd.aeb_systemstate_11().pas_f4_stop(), false); - EXPECT_EQ(cd.aeb_systemstate_11().pas_b1_stop(), false); - EXPECT_EQ(cd.aeb_systemstate_11().pas_b2_stop(), true); - EXPECT_EQ(cd.aeb_systemstate_11().pas_b3_stop(), true); - EXPECT_EQ(cd.aeb_systemstate_11().pas_b4_stop(), false); + EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().aeb_state(), 3); + EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().aeb_brakestate(), true); + EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().faultrank(), 2); + EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().currenttemperature(), 59); + EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_f1_stop(), false); + EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_f2_stop(), false); + EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_f3_stop(), true); + EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_f4_stop(), false); + EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_b1_stop(), false); + EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_b2_stop(), true); + EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_b3_stop(), true); + EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_b4_stop(), false); } } // namespace neolix_edu diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.cc b/modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.cc similarity index 84% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.cc rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.cc index bf7fab327c4..ab9cb1439ec 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h" #include "glog/logging.h" @@ -31,26 +31,31 @@ Aebwheelimpulse355::Aebwheelimpulse355() {} const int32_t Aebwheelimpulse355::ID = 0x355; void Aebwheelimpulse355::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_aeb_wheelimpulse_355()->set_flimpulse( + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu()->mutable_aeb_wheelimpulse_355()->set_flimpulse( flimpulse(bytes, length)); - chassis->mutable_aeb_wheelimpulse_355()->set_flimpulsevalid( - flimpulsevalid(bytes, length)); - chassis->mutable_aeb_wheelimpulse_355()->set_frimpulse( + chassis->mutable_neolix_edu() + ->mutable_aeb_wheelimpulse_355() + ->set_flimpulsevalid(flimpulsevalid(bytes, length)); + chassis->mutable_neolix_edu()->mutable_aeb_wheelimpulse_355()->set_frimpulse( frimpulse(bytes, length)); - chassis->mutable_aeb_wheelimpulse_355()->set_frimpulsevalid( - frimpulsevalid(bytes, length)); - chassis->mutable_aeb_wheelimpulse_355()->set_rlimpulse( + chassis->mutable_neolix_edu() + ->mutable_aeb_wheelimpulse_355() + ->set_frimpulsevalid(frimpulsevalid(bytes, length)); + chassis->mutable_neolix_edu()->mutable_aeb_wheelimpulse_355()->set_rlimpulse( rlimpulse(bytes, length)); - chassis->mutable_aeb_wheelimpulse_355()->set_rlimpulsevalid( - rlimpulsevalid(bytes, length)); - chassis->mutable_aeb_wheelimpulse_355()->set_rrimpulse( + chassis->mutable_neolix_edu() + ->mutable_aeb_wheelimpulse_355() + ->set_rlimpulsevalid(rlimpulsevalid(bytes, length)); + chassis->mutable_neolix_edu()->mutable_aeb_wheelimpulse_355()->set_rrimpulse( rrimpulse(bytes, length)); - chassis->mutable_aeb_wheelimpulse_355()->set_rrimpulsevalid( - rrimpulsevalid(bytes, length)); - chassis->mutable_aeb_wheelimpulse_355()->set_alivecounter( - alivecounter(bytes, length)); - chassis->mutable_aeb_wheelimpulse_355()->set_checksum( + chassis->mutable_neolix_edu() + ->mutable_aeb_wheelimpulse_355() + ->set_rrimpulsevalid(rrimpulsevalid(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_aeb_wheelimpulse_355() + ->set_alivecounter(alivecounter(bytes, length)); + chassis->mutable_neolix_edu()->mutable_aeb_wheelimpulse_355()->set_checksum( checksum(bytes, length)); } diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h b/modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h similarity index 96% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h index 6f64009db0b..61952497736 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace neolix_edu { class Aebwheelimpulse355 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Aebwheelimpulse355(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/aeb_wheelimpulse_355_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355_test.cc similarity index 70% rename from modules/canbus_vehicle/neolix_edu/protocol/aeb_wheelimpulse_355_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355_test.cc index bee62fc932f..1a35bf63aaa 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/aeb_wheelimpulse_355_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Aebwheelimpulse355Test : public ::testing::Test { TEST_F(Aebwheelimpulse355Test, reset) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Aebwheelimpulse355 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b01100111); @@ -45,14 +45,14 @@ TEST_F(Aebwheelimpulse355Test, reset) { EXPECT_EQ(data[6], 0b01010011); EXPECT_EQ(data[7], 0b01010100); - EXPECT_EQ(cd.aeb_wheelimpulse_355().flimpulse(), 413); - EXPECT_EQ(cd.aeb_wheelimpulse_355().flimpulsevalid(), true); - EXPECT_EQ(cd.aeb_wheelimpulse_355().frimpulse(), 76); - EXPECT_EQ(cd.aeb_wheelimpulse_355().frimpulsevalid(), false); - EXPECT_EQ(cd.aeb_wheelimpulse_355().rlimpulse(), 868); - EXPECT_EQ(cd.aeb_wheelimpulse_355().rlimpulsevalid(), false); - EXPECT_EQ(cd.aeb_wheelimpulse_355().rrimpulse(), 650); - EXPECT_EQ(cd.aeb_wheelimpulse_355().rrimpulsevalid(), true); + EXPECT_EQ(cd.neolix_edu().aeb_wheelimpulse_355().flimpulse(), 413); + EXPECT_EQ(cd.neolix_edu().aeb_wheelimpulse_355().flimpulsevalid(), true); + EXPECT_EQ(cd.neolix_edu().aeb_wheelimpulse_355().frimpulse(), 76); + EXPECT_EQ(cd.neolix_edu().aeb_wheelimpulse_355().frimpulsevalid(), false); + EXPECT_EQ(cd.neolix_edu().aeb_wheelimpulse_355().rlimpulse(), 868); + EXPECT_EQ(cd.neolix_edu().aeb_wheelimpulse_355().rlimpulsevalid(), false); + EXPECT_EQ(cd.neolix_edu().aeb_wheelimpulse_355().rrimpulse(), 650); + EXPECT_EQ(cd.neolix_edu().aeb_wheelimpulse_355().rrimpulsevalid(), true); } } // namespace neolix_edu diff --git a/modules/canbus_vehicle/neolix_edu/protocol/pas_1st_data_311.cc b/modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311.cc similarity index 87% rename from modules/canbus_vehicle/neolix_edu/protocol/pas_1st_data_311.cc rename to modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311.cc index c64493df2e9..a7d6cfcfad6 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/pas_1st_data_311.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/pas_1st_data_311.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311.h" #include "glog/logging.h" @@ -31,22 +31,22 @@ Pas1stdata311::Pas1stdata311() {} const int32_t Pas1stdata311::ID = 0x311; void Pas1stdata311::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_pas_1st_data_311()->set_pasdistance4( + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu()->mutable_pas_1st_data_311()->set_pasdistance4( pasdistance4(bytes, length)); - chassis->mutable_pas_1st_data_311()->set_pasdistance3( + chassis->mutable_neolix_edu()->mutable_pas_1st_data_311()->set_pasdistance3( pasdistance3(bytes, length)); - chassis->mutable_pas_1st_data_311()->set_pas_f1_status( + chassis->mutable_neolix_edu()->mutable_pas_1st_data_311()->set_pas_f1_status( pas_f1_status(bytes, length)); - chassis->mutable_pas_1st_data_311()->set_pas_f2_status( + chassis->mutable_neolix_edu()->mutable_pas_1st_data_311()->set_pas_f2_status( pas_f2_status(bytes, length)); - chassis->mutable_pas_1st_data_311()->set_pas_f3_status( + chassis->mutable_neolix_edu()->mutable_pas_1st_data_311()->set_pas_f3_status( pas_f3_status(bytes, length)); - chassis->mutable_pas_1st_data_311()->set_pas_f4_status( + chassis->mutable_neolix_edu()->mutable_pas_1st_data_311()->set_pas_f4_status( pas_f4_status(bytes, length)); - chassis->mutable_pas_1st_data_311()->set_pasdistance2( + chassis->mutable_neolix_edu()->mutable_pas_1st_data_311()->set_pasdistance2( pasdistance2(bytes, length)); - chassis->mutable_pas_1st_data_311()->set_pasdistance1( + chassis->mutable_neolix_edu()->mutable_pas_1st_data_311()->set_pasdistance1( pasdistance1(bytes, length)); } diff --git a/modules/canbus_vehicle/neolix_edu/protocol/pas_1st_data_311.h b/modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311.h similarity index 95% rename from modules/canbus_vehicle/neolix_edu/protocol/pas_1st_data_311.h rename to modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311.h index bbe5494cf78..3001d02b006 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/pas_1st_data_311.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace neolix_edu { class Pas1stdata311 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Pas1stdata311(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'phy=int*2;0xFF:no obstacle', 'offset': 0.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/pas_1st_data_311_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311_test.cc similarity index 71% rename from modules/canbus_vehicle/neolix_edu/protocol/pas_1st_data_311_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311_test.cc index 14d90da9301..4664538fd49 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/pas_1st_data_311_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/pas_1st_data_311.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Pas1stdata311Test : public ::testing::Test { TEST_F(Pas1stdata311Test, reset) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Pas1stdata311 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b01100111); @@ -45,14 +45,14 @@ TEST_F(Pas1stdata311Test, reset) { EXPECT_EQ(data[6], 0b01010011); EXPECT_EQ(data[7], 0b01010100); - EXPECT_EQ(cd.pas_1st_data_311().pasdistance4(), 162); - EXPECT_EQ(cd.pas_1st_data_311().pasdistance3(), 200); - EXPECT_EQ(cd.pas_1st_data_311().pas_f1_status(), true); - EXPECT_EQ(cd.pas_1st_data_311().pas_f2_status(), true); - EXPECT_EQ(cd.pas_1st_data_311().pas_f3_status(), true); - EXPECT_EQ(cd.pas_1st_data_311().pas_f4_status(), false); - EXPECT_EQ(cd.pas_1st_data_311().pasdistance2(), 198); - EXPECT_EQ(cd.pas_1st_data_311().pasdistance1(), 196); + EXPECT_EQ(cd.neolix_edu().pas_1st_data_311().pasdistance4(), 162); + EXPECT_EQ(cd.neolix_edu().pas_1st_data_311().pasdistance3(), 200); + EXPECT_EQ(cd.neolix_edu().pas_1st_data_311().pas_f1_status(), true); + EXPECT_EQ(cd.neolix_edu().pas_1st_data_311().pas_f2_status(), true); + EXPECT_EQ(cd.neolix_edu().pas_1st_data_311().pas_f3_status(), true); + EXPECT_EQ(cd.neolix_edu().pas_1st_data_311().pas_f4_status(), false); + EXPECT_EQ(cd.neolix_edu().pas_1st_data_311().pasdistance2(), 198); + EXPECT_EQ(cd.neolix_edu().pas_1st_data_311().pasdistance1(), 196); } } // namespace neolix_edu diff --git a/modules/canbus_vehicle/neolix_edu/protocol/pas_2nd_data_312.cc b/modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312.cc similarity index 87% rename from modules/canbus_vehicle/neolix_edu/protocol/pas_2nd_data_312.cc rename to modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312.cc index f6ee1880b11..f324ba47ff5 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/pas_2nd_data_312.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/pas_2nd_data_312.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312.h" #include "glog/logging.h" @@ -31,22 +31,22 @@ Pas2nddata312::Pas2nddata312() {} const int32_t Pas2nddata312::ID = 0x312; void Pas2nddata312::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_pas_2nd_data_312()->set_pas_b1_status( + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu()->mutable_pas_2nd_data_312()->set_pas_b1_status( pas_b1_status(bytes, length)); - chassis->mutable_pas_2nd_data_312()->set_pas_b2_status( + chassis->mutable_neolix_edu()->mutable_pas_2nd_data_312()->set_pas_b2_status( pas_b2_status(bytes, length)); - chassis->mutable_pas_2nd_data_312()->set_pas_b3_status( + chassis->mutable_neolix_edu()->mutable_pas_2nd_data_312()->set_pas_b3_status( pas_b3_status(bytes, length)); - chassis->mutable_pas_2nd_data_312()->set_pas_b4_status( + chassis->mutable_neolix_edu()->mutable_pas_2nd_data_312()->set_pas_b4_status( pas_b4_status(bytes, length)); - chassis->mutable_pas_2nd_data_312()->set_pasdistance1( + chassis->mutable_neolix_edu()->mutable_pas_2nd_data_312()->set_pasdistance1( pasdistance1(bytes, length)); - chassis->mutable_pas_2nd_data_312()->set_pasdistance2( + chassis->mutable_neolix_edu()->mutable_pas_2nd_data_312()->set_pasdistance2( pasdistance2(bytes, length)); - chassis->mutable_pas_2nd_data_312()->set_pasdistance3( + chassis->mutable_neolix_edu()->mutable_pas_2nd_data_312()->set_pasdistance3( pasdistance3(bytes, length)); - chassis->mutable_pas_2nd_data_312()->set_pasdistance4( + chassis->mutable_neolix_edu()->mutable_pas_2nd_data_312()->set_pasdistance4( pasdistance4(bytes, length)); } diff --git a/modules/canbus_vehicle/neolix_edu/protocol/pas_2nd_data_312.h b/modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312.h similarity index 95% rename from modules/canbus_vehicle/neolix_edu/protocol/pas_2nd_data_312.h rename to modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312.h index fc1acd59aa1..3cbe63427b2 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/pas_2nd_data_312.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace neolix_edu { class Pas2nddata312 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Pas2nddata312(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/pas_2nd_data_312_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312_test.cc similarity index 71% rename from modules/canbus_vehicle/neolix_edu/protocol/pas_2nd_data_312_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312_test.cc index a450d5f90b1..160ca08fb1b 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/pas_2nd_data_312_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/pas_2nd_data_312.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Pas2nddata312Test : public ::testing::Test { TEST_F(Pas2nddata312Test, reset) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Pas2nddata312 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b01100111); @@ -45,14 +45,14 @@ TEST_F(Pas2nddata312Test, reset) { EXPECT_EQ(data[6], 0b01010011); EXPECT_EQ(data[7], 0b01010100); - EXPECT_EQ(cd.pas_2nd_data_312().pas_b1_status(), true); - EXPECT_EQ(cd.pas_2nd_data_312().pas_b2_status(), true); - EXPECT_EQ(cd.pas_2nd_data_312().pas_b3_status(), true); - EXPECT_EQ(cd.pas_2nd_data_312().pas_b4_status(), false); - EXPECT_EQ(cd.pas_2nd_data_312().pasdistance1(), 196); - EXPECT_EQ(cd.pas_2nd_data_312().pasdistance2(), 198); - EXPECT_EQ(cd.pas_2nd_data_312().pasdistance3(), 200); - EXPECT_EQ(cd.pas_2nd_data_312().pasdistance4(), 162); + EXPECT_EQ(cd.neolix_edu().pas_2nd_data_312().pas_b1_status(), true); + EXPECT_EQ(cd.neolix_edu().pas_2nd_data_312().pas_b2_status(), true); + EXPECT_EQ(cd.neolix_edu().pas_2nd_data_312().pas_b3_status(), true); + EXPECT_EQ(cd.neolix_edu().pas_2nd_data_312().pas_b4_status(), false); + EXPECT_EQ(cd.neolix_edu().pas_2nd_data_312().pasdistance1(), 196); + EXPECT_EQ(cd.neolix_edu().pas_2nd_data_312().pasdistance2(), 198); + EXPECT_EQ(cd.neolix_edu().pas_2nd_data_312().pasdistance3(), 200); + EXPECT_EQ(cd.neolix_edu().pas_2nd_data_312().pasdistance4(), 162); } } // namespace neolix_edu diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_brake_report_47.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47.cc similarity index 76% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_brake_report_47.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47.cc index 488191f33a1..1e5db2ae4b0 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_brake_report_47.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_brake_report_47.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47.h" #include "glog/logging.h" @@ -31,29 +31,38 @@ Vcubrakereport47::Vcubrakereport47() {} const int32_t Vcubrakereport47::ID = 0x47; void Vcubrakereport47::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_vcu_brake_report_47()->set_brake_enable_resp( - brake_enable_resp(bytes, length)); - chassis->mutable_vcu_brake_report_47()->set_control_mode_resp( - control_mode_resp(bytes, length)); - chassis->mutable_vcu_brake_report_47()->set_vcu_real_brake_valid( - vcu_real_brake_valid(bytes, length)); - chassis->mutable_vcu_brake_report_47()->set_vcu_real_brake( - vcu_real_brake(bytes, length)); - chassis->mutable_vcu_brake_report_47()->set_vcu_real_parking_status( - vcu_real_parking_status(bytes, length)); - chassis->mutable_vcu_brake_report_47()->set_vcu_real_parking_valid( - vcu_real_parking_valid(bytes, length)); - chassis->mutable_vcu_brake_report_47()->set_rampauxiliaryindication( - rampauxiliaryindication(bytes, length)); - chassis->mutable_vcu_brake_report_47()->set_vehicleslope( - vehicleslope(bytes, length)); - chassis->mutable_vcu_brake_report_47()->set_vcu_brakerept_alivecounter( - vcu_brakerept_alivecounter(bytes, length)); - chassis->mutable_vcu_brake_report_47()->set_vcu_brakerept_checksum( - vcu_brakerept_checksum(bytes, length)); - chassis->mutable_vcu_brake_report_47()->set_vcu_ehb_brake_state( - vcu_ehb_brake_state(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu() + ->mutable_vcu_brake_report_47() + ->set_brake_enable_resp(brake_enable_resp(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_brake_report_47() + ->set_control_mode_resp(control_mode_resp(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_brake_report_47() + ->set_vcu_real_brake_valid(vcu_real_brake_valid(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_brake_report_47() + ->set_vcu_real_brake(vcu_real_brake(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_brake_report_47() + ->set_vcu_real_parking_status(vcu_real_parking_status(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_brake_report_47() + ->set_vcu_real_parking_valid(vcu_real_parking_valid(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_brake_report_47() + ->set_rampauxiliaryindication(rampauxiliaryindication(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_brake_report_47() + ->set_vehicleslope(vehicleslope(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_brake_report_47() + ->set_vcu_brakerept_alivecounter( + vcu_brakerept_alivecounter(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_brake_report_47() + ->set_vcu_brakerept_checksum(vcu_brakerept_checksum(bytes, length)); chassis->mutable_brake()->set_brake_pedal_position( vcu_real_brake(bytes, length)); @@ -174,22 +183,6 @@ double Vcubrakereport47::vehicleslope(const std::uint8_t* bytes, return ret; } -// config detail: {'bit': 32, 'description': 'the vcu brake was caused reason', -// 'enum': {0: 'VCU_EHB_NORMAL_BRAKE', 1: 'VCU_EHB_BACKUP_REMOTE_BRAKE', -// 2: 'VCU_EHB_EMERGENCY_BUTTON_BRAKE', 3: 'VCU_EHB_ULTR_BRAKE', 4: -// 'VCU_EHB_BUMPER_BRAKE'}, 'is_signed_var': False, 'len': 3, 'name': -// 'vcu_ehb_brake_state', 'offset': 0.0, 'order': 'motorola', 'physical_range': -// '[0|4]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Vcu_brake_report_47::Vcu_ehb_brakeType Vcubrakereport47::vcu_ehb_brake_state( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 4); - int32_t x = t0.get_byte(0, 3); - - Vcu_brake_report_47::Vcu_ehb_brakeType ret = - static_cast(x); - return ret; -} - // config detail: {'name': 'vcu_brakerept_alivecounter', 'offset': 0.0, // 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range': // '[0|0]', 'bit': 51, 'type': 'int', 'order': 'motorola', 'physical_unit': ''} diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_brake_report_47.h b/modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47.h similarity index 87% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_brake_report_47.h rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47.h index 9f7449d4f1e..42dc4734860 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_brake_report_47.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47.h @@ -16,8 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" - +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,12 +24,12 @@ namespace canbus { namespace neolix_edu { class Vcubrakereport47 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vcubrakereport47(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': '0x0:disable;0x1:enable', 'offset': 0.0, @@ -104,16 +103,6 @@ class Vcubrakereport47 : public ::apollo::drivers::canbus::ProtocolData< // ''} int vcu_brakerept_checksum(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 32, 'description': 'the vcu brake was caused - // reason', 'enum': {0: 'VCU_EHB_NORMAL_BRAKE', 1: - // 'VCU_EHB_BACKUP_REMOTE_BRAKE', 2: 'VCU_EHB_EMERGENCY_BUTTON_BRAKE', 3: - // 'VCU_EHB_ULTR_BRAKE', 4: 'VCU_EHB_BUMPER_BRAKE'}, 'is_signed_var': False, - // 'len': 3, 'name': 'vcu_ehb_brake_state', 'offset': 0.0, 'order': - // 'motorola', 'physical_range': - // '[0|4]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Vcu_brake_report_47::Vcu_ehb_brakeType vcu_ehb_brake_state( - const std::uint8_t* bytes, const int32_t length) const; }; } // namespace neolix_edu diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_brake_report_47_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47_test.cc similarity index 70% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_brake_report_47_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47_test.cc index 20d6c9e22f5..690be481e3d 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_brake_report_47_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_brake_report_47.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Vcubrakereport47Test : public ::testing::Test { TEST_F(Vcubrakereport47Test, reset) { uint8_t data[8] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Vcubrakereport47 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b00000000); @@ -45,18 +45,17 @@ TEST_F(Vcubrakereport47Test, reset) { EXPECT_EQ(data[6], 0b00000000); EXPECT_EQ(data[7], 0b00000000); - EXPECT_EQ(cd.vcu_brake_report_47().brake_enable_resp(), false); - EXPECT_EQ(cd.vcu_brake_report_47().control_mode_resp(), 0); - EXPECT_EQ(cd.vcu_brake_report_47().vcu_real_brake_valid(), + EXPECT_EQ(cd.neolix_edu().vcu_brake_report_47().brake_enable_resp(), false); + EXPECT_EQ(cd.neolix_edu().vcu_brake_report_47().control_mode_resp(), 0); + EXPECT_EQ(cd.neolix_edu().vcu_brake_report_47().vcu_real_brake_valid(), false); - EXPECT_EQ(cd.vcu_brake_report_47().vcu_real_brake(), 0); - EXPECT_EQ(cd.vcu_brake_report_47().vcu_real_parking_status(), 0); - EXPECT_EQ(cd.vcu_brake_report_47().vcu_real_parking_valid(), + EXPECT_EQ(cd.neolix_edu().vcu_brake_report_47().vcu_real_brake(), 0); + EXPECT_EQ(cd.neolix_edu().vcu_brake_report_47().vcu_real_parking_status(), 0); + EXPECT_EQ(cd.neolix_edu().vcu_brake_report_47().vcu_real_parking_valid(), false); - EXPECT_EQ(cd.vcu_brake_report_47().rampauxiliaryindication(), + EXPECT_EQ(cd.neolix_edu().vcu_brake_report_47().rampauxiliaryindication(), false); - EXPECT_EQ(cd.vcu_brake_report_47().vehicleslope(), 0); - EXPECT_EQ(cd.vcu_brake_report_47().vcu_ehb_brake_state(), 0); + EXPECT_EQ(cd.neolix_edu().vcu_brake_report_47().vehicleslope(), 0); } } // namespace neolix_edu diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_drive_report_52.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52.cc similarity index 82% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_drive_report_52.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52.cc index 731ff33f255..c80b3a69cce 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_drive_report_52.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_drive_report_52.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52.h" #include "glog/logging.h" @@ -31,25 +31,35 @@ Vcudrivereport52::Vcudrivereport52() {} const int32_t Vcudrivereport52::ID = 0x52; void Vcudrivereport52::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_vcu_drive_report_52()->set_drive_enable_resp( - drive_enable_resp(bytes, length)); - chassis->mutable_vcu_drive_report_52()->set_control_mode_resp( - control_mode_resp(bytes, length)); - chassis->mutable_vcu_drive_report_52()->set_vcu_real_shift( - vcu_real_shift(bytes, length)); - chassis->mutable_vcu_drive_report_52()->set_vcu_real_shift_valid( - vcu_real_shift_valid(bytes, length)); - chassis->mutable_vcu_drive_report_52()->set_vcu_real_torque_valid( - vcu_real_torque_valid(bytes, length)); - chassis->mutable_vcu_drive_report_52()->set_vcu_real_torque( - vcu_real_torque(bytes, length)); - chassis->mutable_vcu_drive_report_52()->set_vcu_limitedtorquemode( - vcu_limitedtorquemode(bytes, length)); - chassis->mutable_vcu_drive_report_52()->set_vcu_driverept_alivecounter( - vcu_driverept_alivecounter(bytes, length)); - chassis->mutable_vcu_drive_report_52()->set_vcu_driverept_checksum( - vcu_driverept_checksum(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu() + ->mutable_vcu_drive_report_52() + ->set_drive_enable_resp(drive_enable_resp(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_drive_report_52() + ->set_control_mode_resp(control_mode_resp(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_drive_report_52() + ->set_vcu_real_shift(vcu_real_shift(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_drive_report_52() + ->set_vcu_real_shift_valid(vcu_real_shift_valid(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_drive_report_52() + ->set_vcu_real_torque_valid(vcu_real_torque_valid(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_drive_report_52() + ->set_vcu_real_torque(vcu_real_torque(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_drive_report_52() + ->set_vcu_limitedtorquemode(vcu_limitedtorquemode(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_drive_report_52() + ->set_vcu_driverept_alivecounter( + vcu_driverept_alivecounter(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_drive_report_52() + ->set_vcu_driverept_checksum(vcu_driverept_checksum(bytes, length)); chassis->mutable_safety()->set_driving_mode(Chassis::COMPLETE_AUTO_DRIVE); chassis->mutable_gas()->set_gas_pedal_position( diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_drive_report_52.h b/modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52.h similarity index 96% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_drive_report_52.h rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52.h index 2bbf719c371..c27cfb56496 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_drive_report_52.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace neolix_edu { class Vcudrivereport52 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vcudrivereport52(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': '0x0:disable;0x1:enable', 'offset': 0.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_drive_report_52_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52_test.cc similarity index 73% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_drive_report_52_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52_test.cc index 1ea46803a40..ea5e17edd8d 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_drive_report_52_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_drive_report_52.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Vcudrivereport52Test : public ::testing::Test { TEST_F(Vcudrivereport52Test, reset) { uint8_t data[8] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Vcudrivereport52 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b00000000); @@ -45,15 +45,15 @@ TEST_F(Vcudrivereport52Test, reset) { EXPECT_EQ(data[6], 0b00000000); EXPECT_EQ(data[7], 0b00000000); - EXPECT_EQ(cd.vcu_drive_report_52().drive_enable_resp(), false); - EXPECT_EQ(cd.vcu_drive_report_52().control_mode_resp(), 0); - EXPECT_EQ(cd.vcu_drive_report_52().vcu_real_shift(), 0); - EXPECT_EQ(cd.vcu_drive_report_52().vcu_real_shift_valid(), + EXPECT_EQ(cd.neolix_edu().vcu_drive_report_52().drive_enable_resp(), false); + EXPECT_EQ(cd.neolix_edu().vcu_drive_report_52().control_mode_resp(), 0); + EXPECT_EQ(cd.neolix_edu().vcu_drive_report_52().vcu_real_shift(), 0); + EXPECT_EQ(cd.neolix_edu().vcu_drive_report_52().vcu_real_shift_valid(), false); - EXPECT_EQ(cd.vcu_drive_report_52().vcu_real_torque_valid(), + EXPECT_EQ(cd.neolix_edu().vcu_drive_report_52().vcu_real_torque_valid(), false); - EXPECT_EQ(cd.vcu_drive_report_52().vcu_real_torque(), -665); - EXPECT_EQ(cd.vcu_drive_report_52().vcu_limitedtorquemode(), + EXPECT_EQ(cd.neolix_edu().vcu_drive_report_52().vcu_real_torque(), -665); + EXPECT_EQ(cd.neolix_edu().vcu_drive_report_52().vcu_limitedtorquemode(), false); } diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_eps_report_57.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57.cc similarity index 82% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_eps_report_57.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57.cc index 0fdb41828bc..4e742cc3b8b 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_eps_report_57.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_eps_report_57.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57.h" #include "glog/logging.h" @@ -31,25 +31,34 @@ Vcuepsreport57::Vcuepsreport57() {} const int32_t Vcuepsreport57::ID = 0x57; void Vcuepsreport57::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_vcu_eps_report_57()->set_drive_enable_resp( - drive_enable_resp(bytes, length)); - chassis->mutable_vcu_eps_report_57()->set_control_mode_resp( - control_mode_resp(bytes, length)); - chassis->mutable_vcu_eps_report_57()->set_vcu_eps_report( - vcu_eps_report(bytes, length)); - chassis->mutable_vcu_eps_report_57()->set_vcu_real_angle( - vcu_real_angle(bytes, length)); - chassis->mutable_vcu_eps_report_57()->set_vcu_real_angle_valid( - vcu_real_angle_valid(bytes, length)); - chassis->mutable_vcu_eps_report_57()->set_vcu_target_angle_valid( - vcu_target_angle_valid(bytes, length)); - chassis->mutable_vcu_eps_report_57()->set_vcu_target_angle( - vcu_target_angle(bytes, length)); - chassis->mutable_vcu_eps_report_57()->set_vcu_eps_rept_alivecounter( - vcu_eps_rept_alivecounter(bytes, length)); - chassis->mutable_vcu_eps_report_57()->set_vcu_eps_rept_checksum( - vcu_eps_rept_checksum(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu() + ->mutable_vcu_eps_report_57() + ->set_drive_enable_resp(drive_enable_resp(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_eps_report_57() + ->set_control_mode_resp(control_mode_resp(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_eps_report_57() + ->set_vcu_eps_report(vcu_eps_report(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_eps_report_57() + ->set_vcu_real_angle(vcu_real_angle(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_eps_report_57() + ->set_vcu_real_angle_valid(vcu_real_angle_valid(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_eps_report_57() + ->set_vcu_target_angle_valid(vcu_target_angle_valid(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_eps_report_57() + ->set_vcu_target_angle(vcu_target_angle(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_eps_report_57() + ->set_vcu_eps_rept_alivecounter(vcu_eps_rept_alivecounter(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_eps_report_57() + ->set_vcu_eps_rept_checksum(vcu_eps_rept_checksum(bytes, length)); chassis->mutable_eps()->set_steering_angle(vcu_real_angle(bytes, length)); chassis->mutable_check_response()->set_is_eps_online( diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_eps_report_57.h b/modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57.h similarity index 96% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_eps_report_57.h rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57.h index 2d328f9fce3..37719ad2119 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_eps_report_57.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace neolix_edu { class Vcuepsreport57 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vcuepsreport57(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': '0x0:disable;0x1:enable', 'offset': 0.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_eps_report_57_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57_test.cc similarity index 72% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_eps_report_57_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57_test.cc index e344cb802b5..fad384dac13 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_eps_report_57_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_eps_report_57.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Vcuepsreport57Test : public ::testing::Test { TEST_F(Vcuepsreport57Test, reset) { uint8_t data[8] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Vcuepsreport57 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b00000000); @@ -45,14 +45,14 @@ TEST_F(Vcuepsreport57Test, reset) { EXPECT_EQ(data[6], 0b00000000); EXPECT_EQ(data[7], 0b00000000); - EXPECT_EQ(cd.vcu_eps_report_57().drive_enable_resp(), false); - EXPECT_EQ(cd.vcu_eps_report_57().control_mode_resp(), 0); - EXPECT_EQ(cd.vcu_eps_report_57().vcu_eps_report(), false); - EXPECT_EQ(cd.vcu_eps_report_57().vcu_real_angle(), 2048); - EXPECT_EQ(cd.vcu_eps_report_57().vcu_real_angle_valid(), false); - EXPECT_EQ(cd.vcu_eps_report_57().vcu_target_angle_valid(), + EXPECT_EQ(cd.neolix_edu().vcu_eps_report_57().drive_enable_resp(), false); + EXPECT_EQ(cd.neolix_edu().vcu_eps_report_57().control_mode_resp(), 0); + EXPECT_EQ(cd.neolix_edu().vcu_eps_report_57().vcu_eps_report(), false); + EXPECT_EQ(cd.neolix_edu().vcu_eps_report_57().vcu_real_angle(), 2048); + EXPECT_EQ(cd.neolix_edu().vcu_eps_report_57().vcu_real_angle_valid(), false); + EXPECT_EQ(cd.neolix_edu().vcu_eps_report_57().vcu_target_angle_valid(), false); - EXPECT_EQ(cd.vcu_eps_report_57().vcu_target_angle(), -512); + EXPECT_EQ(cd.neolix_edu().vcu_eps_report_57().vcu_target_angle(), -512); } } // namespace neolix_edu diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_nm_401.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401.cc similarity index 89% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_nm_401.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401.cc index 929361d29cc..f765b74c5a8 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_nm_401.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_nm_401.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401.h" #include "glog/logging.h" @@ -31,8 +31,8 @@ Vcunm401::Vcunm401() {} const int32_t Vcunm401::ID = 0x401; void Vcunm401::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_vcu_nm_401()->set_vcu_sleepcommand( + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu()->mutable_vcu_nm_401()->set_vcu_sleepcommand( vcu_sleepcommand(bytes, length)); } diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_nm_401.h b/modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401.h similarity index 89% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_nm_401.h rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401.h index fd955ecab42..c2ec1f0f183 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_nm_401.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace neolix_edu { class Vcunm401 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vcunm401(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': '0x0:Inactive;0x1:Active', 'offset': 0.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_nm_401_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401_test.cc similarity index 91% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_nm_401_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401_test.cc index 1208ed18f71..6c1cf276bf7 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_nm_401_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_nm_401.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Vcunm401Test : public ::testing::Test { TEST_F(Vcunm401Test, reset) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Vcunm401 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b01100111); @@ -45,7 +45,7 @@ TEST_F(Vcunm401Test, reset) { EXPECT_EQ(data[6], 0b01010011); EXPECT_EQ(data[7], 0b01010100); - EXPECT_EQ(cd.vcu_nm_401().vcu_sleepcommand(), true); + EXPECT_EQ(cd.neolix_edu().vcu_nm_401().vcu_sleepcommand(), true); } } // namespace neolix_edu diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_powerstatus_214.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214.cc similarity index 77% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_powerstatus_214.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214.cc index 173c9d50808..2e0a6fe69e4 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_powerstatus_214.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_powerstatus_214.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214.h" #include "glog/logging.h" @@ -31,23 +31,34 @@ Vcupowerstatus214::Vcupowerstatus214() {} const int32_t Vcupowerstatus214::ID = 0x214; void Vcupowerstatus214::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_vcu_powerstatus_214()->set_vcu_powermode( - vcu_powermode(bytes, length)); - chassis->mutable_vcu_powerstatus_214()->set_vcu_powermodevalid( - vcu_powermodevalid(bytes, length)); - chassis->mutable_vcu_powerstatus_214()->set_replacebatterystateindication( - replacebatterystateindication(bytes, length)); - chassis->mutable_vcu_powerstatus_214()->set_forbidden_aeb_signal( - forbidden_aeb_signal(bytes, length)); - chassis->mutable_vcu_powerstatus_214()->set_bcu_chargedischargecurrent( - bcu_chargedischargecurrent(bytes, length)); - chassis->mutable_vcu_powerstatus_214()->set_bcu_batt_internalvoltage( - bcu_batt_internalvoltage(bytes, length)); - chassis->mutable_vcu_powerstatus_214()->set_vcu_driverinfo_alivecounter( - vcu_driverinfo_alivecounter(bytes, length)); - chassis->mutable_vcu_powerstatus_214()->set_vcu_driverinfo_checksum( - vcu_driverinfo_checksum(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu() + ->mutable_vcu_powerstatus_214() + ->set_vcu_powermode(vcu_powermode(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_powerstatus_214() + ->set_vcu_powermodevalid(vcu_powermodevalid(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_powerstatus_214() + ->set_replacebatterystateindication( + replacebatterystateindication(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_powerstatus_214() + ->set_forbidden_aeb_signal(forbidden_aeb_signal(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_powerstatus_214() + ->set_bcu_chargedischargecurrent( + bcu_chargedischargecurrent(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_powerstatus_214() + ->set_bcu_batt_internalvoltage(bcu_batt_internalvoltage(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_powerstatus_214() + ->set_vcu_driverinfo_alivecounter( + vcu_driverinfo_alivecounter(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_powerstatus_214() + ->set_vcu_driverinfo_checksum(vcu_driverinfo_checksum(bytes, length)); } // config detail: {'description': diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_powerstatus_214.h b/modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214.h similarity index 95% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_powerstatus_214.h rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214.h index c2384e4e9d7..3fd18280348 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_powerstatus_214.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace neolix_edu { class Vcupowerstatus214 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vcupowerstatus214(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_powerstatus_214_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214_test.cc similarity index 82% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_powerstatus_214_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214_test.cc index 894872e9dd7..959793dd11a 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_powerstatus_214_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_powerstatus_214.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Vcupowerstatus214Test : public ::testing::Test { TEST_F(Vcupowerstatus214Test, reset) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Vcupowerstatus214 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b01100111); @@ -45,9 +45,11 @@ TEST_F(Vcupowerstatus214Test, reset) { EXPECT_EQ(data[6], 0b01010011); EXPECT_EQ(data[7], 0b01010100); - EXPECT_EQ(cd.vcu_powerstatus_214().vcu_powermode(), 1); - EXPECT_EQ(cd.vcu_powerstatus_214().vcu_powermodevalid(), 2); - EXPECT_EQ(cd.vcu_powerstatus_214().replacebatterystateindication(), true); + EXPECT_EQ(cd.neolix_edu().vcu_powerstatus_214().vcu_powermode(), 1); + EXPECT_EQ(cd.neolix_edu().vcu_powerstatus_214().vcu_powermodevalid(), 2); + EXPECT_EQ( + cd.neolix_edu().vcu_powerstatus_214().replacebatterystateindication(), + true); } } // namespace neolix_edu diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.cc similarity index 87% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.cc index b0dfd8454be..518aff12bf4 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h" #include "glog/logging.h" @@ -32,52 +32,66 @@ const int32_t Vcuvehiclefaultresponse201::ID = 0x201; void Vcuvehiclefaultresponse201::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_vcu_vehicle_fault_response_201() + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() ->set_vehicle_error_indicationsvcu( vehicle_error_indicationsvcu(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() - ->set_brake_system_errorehb( - brake_system_errorehb(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() + ->set_brake_system_errorehb(brake_system_errorehb(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() ->set_eps_error(eps_error(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() ->set_motor_error(motor_error(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() ->set_epb_error(epb_error(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() ->set_high_voltage_battery_errorbcu( high_voltage_battery_errorbcu(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() ->set_automode_exit_reason_losscommuni( automode_exit_reason_losscommuni(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() ->set_automode_exit_reason_reqsignalno( automode_exit_reason_reqsignalno(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() ->set_automode_exit_reason_low_power( automode_exit_reason_low_power(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() ->set_automode_exit_reason_highvolt( automode_exit_reason_highvolt(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() ->set_automode_exit_reason_vehicle_flt( automode_exit_reason_vehicle_flt(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() ->set_automode_exit_reason_press_emerg( automode_exit_reason_press_emerg(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() ->set_automode_exit_reason_press_remot( automode_exit_reason_press_remot(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() ->set_automode_exit_reason_pdu_control( automode_exit_reason_pdu_control(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() ->set_vcu_faultrept_alivecounter( vcu_faultrept_alivecounter(bytes, length)); - chassis->mutable_vcu_vehicle_fault_response_201() - ->set_vcu_faultrept_checksum( - vcu_faultrept_checksum(bytes, length)); + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_fault_response_201() + ->set_vcu_faultrept_checksum(vcu_faultrept_checksum(bytes, length)); } // config detail: {'description': '0x0: no error;0x1: level 1 error;0x2: level 2 diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h similarity index 98% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h index 2b38a919cfe..21edfc087bf 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,12 +25,12 @@ namespace neolix_edu { class Vcuvehiclefaultresponse201 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vcuvehiclefaultresponse201(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': '0x0: no error;0x1: level 1 error;0x2: level diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201_test.cc similarity index 64% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201_test.cc index 758e8f66ab4..7f9093f9e81 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Vcuvehiclefaultresponse201Test : public ::testing::Test { TEST_F(Vcuvehiclefaultresponse201Test, reset) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Vcuvehiclefaultresponse201 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b01100111); @@ -45,39 +45,51 @@ TEST_F(Vcuvehiclefaultresponse201Test, reset) { EXPECT_EQ(data[6], 0b01010011); EXPECT_EQ(data[7], 0b01010100); - EXPECT_EQ(cd.vcu_vehicle_fault_response_201() + EXPECT_EQ(cd.neolix_edu() + .vcu_vehicle_fault_response_201() .vehicle_error_indicationsvcu(), 7); - EXPECT_EQ(cd.vcu_vehicle_fault_response_201() - .brake_system_errorehb(), 6); - EXPECT_EQ(cd.vcu_vehicle_fault_response_201().eps_error(), 2); - EXPECT_EQ(cd.vcu_vehicle_fault_response_201().motor_error(), 6); - EXPECT_EQ(cd.vcu_vehicle_fault_response_201().epb_error(), 3); - EXPECT_EQ(cd.vcu_vehicle_fault_response_201() - .high_voltage_battery_errorbcu(), 6); - EXPECT_EQ(cd.vcu_vehicle_fault_response_201() + EXPECT_EQ( + cd.neolix_edu().vcu_vehicle_fault_response_201().brake_system_errorehb(), + 6); + EXPECT_EQ(cd.neolix_edu().vcu_vehicle_fault_response_201().eps_error(), 2); + EXPECT_EQ(cd.neolix_edu().vcu_vehicle_fault_response_201().motor_error(), 6); + EXPECT_EQ(cd.neolix_edu().vcu_vehicle_fault_response_201().epb_error(), 3); + EXPECT_EQ(cd.neolix_edu() + .vcu_vehicle_fault_response_201() + .high_voltage_battery_errorbcu(), + 6); + EXPECT_EQ(cd.neolix_edu() + .vcu_vehicle_fault_response_201() .automode_exit_reason_losscommuni(), true); - EXPECT_EQ(cd.vcu_vehicle_fault_response_201() + EXPECT_EQ(cd.neolix_edu() + .vcu_vehicle_fault_response_201() .automode_exit_reason_reqsignalno(), false); - EXPECT_EQ(cd.vcu_vehicle_fault_response_201() + EXPECT_EQ(cd.neolix_edu() + .vcu_vehicle_fault_response_201() .automode_exit_reason_low_power(), false); - EXPECT_EQ(cd.vcu_vehicle_fault_response_201() + EXPECT_EQ(cd.neolix_edu() + .vcu_vehicle_fault_response_201() .automode_exit_reason_highvolt(), false); - EXPECT_EQ(cd.vcu_vehicle_fault_response_201() + EXPECT_EQ(cd.neolix_edu() + .vcu_vehicle_fault_response_201() .automode_exit_reason_vehicle_flt(), true); - EXPECT_EQ(cd.vcu_vehicle_fault_response_201() + EXPECT_EQ(cd.neolix_edu() + .vcu_vehicle_fault_response_201() .automode_exit_reason_press_emerg(), false); - EXPECT_EQ(cd.vcu_vehicle_fault_response_201() + EXPECT_EQ(cd.neolix_edu() + .vcu_vehicle_fault_response_201() .automode_exit_reason_press_remot(), true); - EXPECT_EQ(cd.vcu_vehicle_fault_response_201() + EXPECT_EQ(cd.neolix_edu() + .vcu_vehicle_fault_response_201() .automode_exit_reason_pdu_control(), false); } diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.cc similarity index 87% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.cc index 4ae122bc461..b94c6239d22 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h" #include "glog/logging.h" @@ -31,21 +31,28 @@ Vcuvehicleinforesponse502::Vcuvehicleinforesponse502() {} const int32_t Vcuvehicleinforesponse502::ID = 0x502; void Vcuvehicleinforesponse502::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_vcu_vehicle_info_response_502() + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_info_response_502() ->set_vehicle_softwareversion_indicati( vehicle_softwareversion_indicati(bytes, length)); - chassis->mutable_vcu_vehicle_info_response_502() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_info_response_502() ->set_project(project(bytes, length)); - chassis->mutable_vcu_vehicle_info_response_502() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_info_response_502() ->set_manufacturer(manufacturer(bytes, length)); - chassis ->mutable_vcu_vehicle_info_response_502() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_info_response_502() ->set_year(year(bytes, length)); - chassis->mutable_vcu_vehicle_info_response_502() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_info_response_502() ->set_month(month(bytes, length)); - chassis->mutable_vcu_vehicle_info_response_502() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_info_response_502() ->set_day(day(bytes, length)); - chassis->mutable_vcu_vehicle_info_response_502() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_info_response_502() ->set_vehicle_serial_number(vehicle_serial_number(bytes, length)); } diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h similarity index 95% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h index 0ed230d0365..8b577767355 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,12 +25,12 @@ namespace neolix_edu { class Vcuvehicleinforesponse502 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vcuvehicleinforesponse502(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'Vehicle_Softwareversion_Indicati', 'offset': 0.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502_test.cc similarity index 72% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502_test.cc index c4995accd1c..f8c4479274d 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Vcuvehicleinforesponse502Test : public ::testing::Test { TEST_F(Vcuvehicleinforesponse502Test, reset) { uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Vcuvehicleinforesponse502 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b01100111); @@ -45,15 +45,18 @@ TEST_F(Vcuvehicleinforesponse502Test, reset) { EXPECT_EQ(data[6], 0b01010011); EXPECT_EQ(data[7], 0b01010100); - EXPECT_EQ(cd.vcu_vehicle_info_response_502() + EXPECT_EQ(cd.neolix_edu() + .vcu_vehicle_info_response_502() .vehicle_softwareversion_indicati(), 6775395); - EXPECT_EQ(cd.vcu_vehicle_info_response_502().project(), 4); - EXPECT_EQ(cd.vcu_vehicle_info_response_502().manufacturer(), 6); - EXPECT_EQ(cd.vcu_vehicle_info_response_502().year(), 81); - EXPECT_EQ(cd.vcu_vehicle_info_response_502().month(), 5); - EXPECT_EQ(cd.vcu_vehicle_info_response_502().day(), 4); - EXPECT_EQ(cd.vcu_vehicle_info_response_502().vehicle_serial_number(), 21332); + EXPECT_EQ(cd.neolix_edu().vcu_vehicle_info_response_502().project(), 4); + EXPECT_EQ(cd.neolix_edu().vcu_vehicle_info_response_502().manufacturer(), 6); + EXPECT_EQ(cd.neolix_edu().vcu_vehicle_info_response_502().year(), 81); + EXPECT_EQ(cd.neolix_edu().vcu_vehicle_info_response_502().month(), 5); + EXPECT_EQ(cd.neolix_edu().vcu_vehicle_info_response_502().day(), 4); + EXPECT_EQ( + cd.neolix_edu().vcu_vehicle_info_response_502().vehicle_serial_number(), + 21332); } } // namespace neolix_edu diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.cc similarity index 88% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.cc index f4887b3b540..bc13ff7dbb3 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h" #include "glog/logging.h" @@ -31,33 +31,45 @@ Vcuvehiclestatusreport101::Vcuvehiclestatusreport101() {} const int32_t Vcuvehiclestatusreport101::ID = 0x101; void Vcuvehiclestatusreport101::Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const { - chassis->mutable_vcu_vehicle_status_report_101() + ChassisDetail* chassis) const { + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_status_report_101() ->set_drive_enable_resp(drive_enable_resp(bytes, length)); - chassis->mutable_vcu_vehicle_status_report_101() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_status_report_101() ->set_vcu_highvoltagecircuitstate( vcu_highvoltagecircuitstate(bytes, length)); - chassis->mutable_vcu_vehicle_status_report_101() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_status_report_101() ->set_vcu_dcdc_enabledstates(vcu_dcdc_enabledstates(bytes, length)); - chassis->mutable_vcu_vehicle_status_report_101() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_status_report_101() ->set_control_mode_resp(control_mode_resp(bytes, length)); - chassis->mutable_vcu_vehicle_status_report_101() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_status_report_101() ->set_vcu_vehicle_speed(vcu_vehicle_speed(bytes, length)); - chassis->mutable_vcu_vehicle_status_report_101() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_status_report_101() ->set_vcu_lowbatterychargingfunctionst( vcu_lowbatterychargingfunctionst(bytes, length)); - chassis->mutable_vcu_vehicle_status_report_101() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_status_report_101() ->set_vcu_display_soc(vcu_display_soc(bytes, length)); - chassis->mutable_vcu_vehicle_status_report_101() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_status_report_101() ->set_vcu_motor_speed(vcu_motor_speed(bytes, length)); - chassis->mutable_vcu_vehicle_status_report_101() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_status_report_101() ->set_vcu_motor_direction(vcu_motor_direction(bytes, length)); - chassis->mutable_vcu_vehicle_status_report_101() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_status_report_101() ->set_vcu_motor_speed_valid(vcu_motor_speed_valid(bytes, length)); - chassis->mutable_vcu_vehicle_status_report_101() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_status_report_101() ->set_vcu_statusrept_alivecounter( vcu_statusrept_alivecounter(bytes, length)); - chassis->mutable_vcu_vehicle_status_report_101() + chassis->mutable_neolix_edu() + ->mutable_vcu_vehicle_status_report_101() ->set_vcu_statusrept_checksum(vcu_statusrept_checksum(bytes, length)); chassis->mutable_vehicle_spd()->set_vehicle_spd( diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h similarity index 97% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h index 07f190759ba..b35debf5343 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,12 +25,12 @@ namespace neolix_edu { class Vcuvehiclestatusreport101 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Neolix_edu> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vcuvehiclestatusreport101(); void Parse(const std::uint8_t* bytes, int32_t length, - Neolix_edu* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': '0x0:disable;0x1:enable', 'offset': 0.0, diff --git a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101_test.cc b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101_test.cc similarity index 66% rename from modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101_test.cc rename to modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101_test.cc index 72129747e68..fc90155b4d5 100644 --- a/modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101_test.cc +++ b/modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h" +#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h" #include "glog/logging.h" @@ -33,7 +33,7 @@ class Vcuvehiclestatusreport101Test : public ::testing::Test { TEST_F(Vcuvehiclestatusreport101Test, reset) { uint8_t data[8] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; int32_t length = 8; - Neolix_edu cd; + ChassisDetail cd; Vcuvehiclestatusreport101 accel_cmd; accel_cmd.Parse(data, length, &cd); EXPECT_EQ(data[0], 0b00000000); @@ -45,28 +45,33 @@ TEST_F(Vcuvehiclestatusreport101Test, reset) { EXPECT_EQ(data[6], 0b00000000); EXPECT_EQ(data[7], 0b00000000); - EXPECT_EQ(cd.vcu_vehicle_status_report_101().drive_enable_resp(), + EXPECT_EQ(cd.neolix_edu().vcu_vehicle_status_report_101().drive_enable_resp(), false); - EXPECT_EQ(cd.vcu_vehicle_status_report_101() + EXPECT_EQ(cd.neolix_edu() + .vcu_vehicle_status_report_101() .vcu_highvoltagecircuitstate(), false); - EXPECT_EQ(cd.vcu_vehicle_status_report_101().vcu_dcdc_enabledstates(), - false); - EXPECT_EQ(cd.vcu_vehicle_status_report_101().control_mode_resp(), + EXPECT_EQ( + cd.neolix_edu().vcu_vehicle_status_report_101().vcu_dcdc_enabledstates(), + false); + EXPECT_EQ(cd.neolix_edu().vcu_vehicle_status_report_101().control_mode_resp(), 0); - EXPECT_EQ(cd.vcu_vehicle_status_report_101().vcu_vehicle_speed(), + EXPECT_EQ(cd.neolix_edu().vcu_vehicle_status_report_101().vcu_vehicle_speed(), 0); - EXPECT_EQ(cd.vcu_vehicle_status_report_101() + EXPECT_EQ(cd.neolix_edu() + .vcu_vehicle_status_report_101() .vcu_lowbatterychargingfunctionst(), 0); - EXPECT_EQ(cd.vcu_vehicle_status_report_101().vcu_display_soc(), - 0); - EXPECT_EQ(cd.vcu_vehicle_status_report_101().vcu_motor_speed(), + EXPECT_EQ(cd.neolix_edu().vcu_vehicle_status_report_101().vcu_display_soc(), 0); - EXPECT_EQ(cd.vcu_vehicle_status_report_101().vcu_motor_direction(), + EXPECT_EQ(cd.neolix_edu().vcu_vehicle_status_report_101().vcu_motor_speed(), 0); - EXPECT_EQ(cd.vcu_vehicle_status_report_101().vcu_motor_speed_valid(), - false); + EXPECT_EQ( + cd.neolix_edu().vcu_vehicle_status_report_101().vcu_motor_direction(), + 0); + EXPECT_EQ( + cd.neolix_edu().vcu_vehicle_status_report_101().vcu_motor_speed_valid(), + false); } } // namespace neolix_edu diff --git a/modules/canbus/vehicle/transit/BUILD b/modules/canbus/vehicle/transit/BUILD new file mode 100644 index 00000000000..ed399fa9f93 --- /dev/null +++ b/modules/canbus/vehicle/transit/BUILD @@ -0,0 +1,70 @@ +load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") +load("//tools:cpplint.bzl", "cpplint") + +package(default_visibility = ["//visibility:public"]) + +CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] + +cc_library( + name = "transit_vehicle_factory", + srcs = ["transit_vehicle_factory.cc"], + hdrs = ["transit_vehicle_factory.h"], + copts = CANBUS_COPTS, + deps = [ + ":transit_controller", + ":transit_message_manager", + "//modules/canbus/vehicle:abstract_vehicle_factory", + ], +) + +cc_library( + name = "transit_message_manager", + srcs = ["transit_message_manager.cc"], + hdrs = ["transit_message_manager.h"], + copts = CANBUS_COPTS, + deps = [ + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle/transit/protocol:canbus_transit_protocol", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_library( + name = "transit_controller", + srcs = ["transit_controller.cc"], + hdrs = ["transit_controller.h"], + copts = CANBUS_COPTS, + deps = [ + ":transit_message_manager", + "//modules/canbus/vehicle:vehicle_controller_base", + "//modules/common/kv_db", + "//modules/common_msgs/basic_msgs:vehicle_signal_cc_proto", + "//modules/drivers/canbus/can_comm:can_sender", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_test( + name = "transit_vehicle_factory_test", + size = "small", + srcs = ["transit_vehicle_factory_test.cc"], + deps = [ + ":transit_vehicle_factory", + "@com_google_googletest//:gtest_main", + ], +) + +cc_test( + name = "transit_controller_test", + size = "small", + srcs = ["transit_controller_test.cc"], + data = ["//modules/canbus:test_data"], + deps = [ + ":transit_controller", + "//modules/common/util", + "@com_google_googletest//:gtest_main", + ], +) + +cpplint() diff --git a/modules/canbus_vehicle/transit/protocol/BUILD b/modules/canbus/vehicle/transit/protocol/BUILD similarity index 81% rename from modules/canbus_vehicle/transit/protocol/BUILD rename to modules/canbus/vehicle/transit/protocol/BUILD index 12929a41d47..79034ff9781 100644 --- a/modules/canbus_vehicle/transit/protocol/BUILD +++ b/modules/canbus/vehicle/transit/protocol/BUILD @@ -29,7 +29,7 @@ cc_library( hdrs = ["adc_auxiliarycontrol_110.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/transit/proto:transit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", "@com_google_googletest//:gtest", @@ -42,10 +42,9 @@ cc_test( srcs = ["adc_auxiliarycontrol_110_test.cc"], deps = [ ":adc_auxiliarycontrol_110", - "//modules/canbus_vehicle/transit/protocol:canbus_transit_protocol", + "//modules/canbus/vehicle/transit/protocol:canbus_transit_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_library( @@ -54,7 +53,7 @@ cc_library( hdrs = ["adc_motioncontrol1_10.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/transit/proto:transit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", "@com_google_googletest//:gtest", @@ -67,10 +66,9 @@ cc_test( srcs = ["adc_motioncontrol1_10_test.cc"], deps = [ ":adc_motioncontrol1_10", - "//modules/canbus_vehicle/transit/protocol:canbus_transit_protocol", + "//modules/canbus/vehicle/transit/protocol:canbus_transit_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_library( @@ -79,7 +77,7 @@ cc_library( hdrs = ["adc_motioncontrollimits1_12.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/transit/proto:transit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", "@com_google_googletest//:gtest", @@ -92,10 +90,9 @@ cc_test( srcs = ["adc_motioncontrollimits1_12_test.cc"], deps = [ ":adc_motioncontrollimits1_12", - "//modules/canbus_vehicle/transit/protocol:canbus_transit_protocol", + "//modules/canbus/vehicle/transit/protocol:canbus_transit_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_library( @@ -104,7 +101,7 @@ cc_library( hdrs = ["llc_auxiliaryfeedback_120.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/transit/proto:transit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", "@com_google_googletest//:gtest", @@ -117,10 +114,9 @@ cc_test( srcs = ["llc_auxiliaryfeedback_120_test.cc"], deps = [ ":llc_auxiliaryfeedback_120", - "//modules/canbus_vehicle/transit/protocol:canbus_transit_protocol", + "//modules/canbus/vehicle/transit/protocol:canbus_transit_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_library( @@ -129,7 +125,7 @@ cc_library( hdrs = ["llc_diag_brakecontrol_721.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/transit/proto:transit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", "@com_google_googletest//:gtest", @@ -142,7 +138,7 @@ cc_test( srcs = ["llc_diag_brakecontrol_721_test.cc"], deps = [ ":llc_diag_brakecontrol_721", - "//modules/canbus_vehicle/transit/protocol:canbus_transit_protocol", + "//modules/canbus/vehicle/transit/protocol:canbus_transit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -153,7 +149,7 @@ cc_library( hdrs = ["llc_diag_fault_620.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/transit/proto:transit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", "@com_google_googletest//:gtest", @@ -166,7 +162,7 @@ cc_test( srcs = ["llc_diag_fault_620_test.cc"], deps = [ ":llc_diag_fault_620", - "//modules/canbus_vehicle/transit/protocol:canbus_transit_protocol", + "//modules/canbus/vehicle/transit/protocol:canbus_transit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -177,7 +173,7 @@ cc_library( hdrs = ["llc_diag_steeringcontrol_722.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/transit/proto:transit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", "@com_google_googletest//:gtest", @@ -190,10 +186,9 @@ cc_test( srcs = ["llc_diag_steeringcontrol_722_test.cc"], deps = [ ":llc_diag_steeringcontrol_722", - "//modules/canbus_vehicle/transit/protocol:canbus_transit_protocol", + "//modules/canbus/vehicle/transit/protocol:canbus_transit_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_library( @@ -202,7 +197,7 @@ cc_library( hdrs = ["llc_motioncommandfeedback1_22.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/transit/proto:transit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", "@com_google_googletest//:gtest", @@ -215,10 +210,9 @@ cc_test( srcs = ["llc_motioncommandfeedback1_22_test.cc"], deps = [ ":llc_motioncommandfeedback1_22", - "//modules/canbus_vehicle/transit/protocol:canbus_transit_protocol", + "//modules/canbus/vehicle/transit/protocol:canbus_transit_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_library( @@ -227,7 +221,7 @@ cc_library( hdrs = ["llc_motionfeedback1_20.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/transit/proto:transit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", "@com_google_googletest//:gtest", @@ -240,7 +234,7 @@ cc_test( srcs = ["llc_motionfeedback1_20_test.cc"], deps = [ ":llc_motionfeedback1_20", - "//modules/canbus_vehicle/transit/protocol:canbus_transit_protocol", + "//modules/canbus/vehicle/transit/protocol:canbus_transit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -251,7 +245,7 @@ cc_library( hdrs = ["llc_motionfeedback2_21.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/transit/proto:transit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", "@com_google_googletest//:gtest", @@ -264,10 +258,9 @@ cc_test( srcs = ["llc_motionfeedback2_21_test.cc"], deps = [ ":llc_motionfeedback2_21", - "//modules/canbus_vehicle/transit/protocol:canbus_transit_protocol", + "//modules/canbus/vehicle/transit/protocol:canbus_transit_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_library( @@ -276,7 +269,7 @@ cc_library( hdrs = ["llc_vehiclelimits_24.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/transit/proto:transit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", "@com_google_googletest//:gtest", @@ -289,7 +282,7 @@ cc_test( srcs = ["llc_vehiclelimits_24_test.cc"], deps = [ ":llc_vehiclelimits_24", - "//modules/canbus_vehicle/transit/protocol:canbus_transit_protocol", + "//modules/canbus/vehicle/transit/protocol:canbus_transit_protocol", "@com_google_googletest//:gtest_main", ], ) @@ -300,7 +293,7 @@ cc_library( hdrs = ["llc_vehiclestatus_25.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/transit/proto:transit_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", "@com_google_googletest//:gtest", @@ -313,10 +306,9 @@ cc_test( srcs = ["llc_vehiclestatus_25_test.cc"], deps = [ ":llc_vehiclestatus_25", - "//modules/canbus_vehicle/transit/protocol:canbus_transit_protocol", + "//modules/canbus/vehicle/transit/protocol:canbus_transit_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cpplint() diff --git a/modules/canbus_vehicle/transit/protocol/adc_auxiliarycontrol_110.cc b/modules/canbus/vehicle/transit/protocol/adc_auxiliarycontrol_110.cc similarity index 99% rename from modules/canbus_vehicle/transit/protocol/adc_auxiliarycontrol_110.cc rename to modules/canbus/vehicle/transit/protocol/adc_auxiliarycontrol_110.cc index 12d9d057e02..1afc622ad77 100644 --- a/modules/canbus_vehicle/transit/protocol/adc_auxiliarycontrol_110.cc +++ b/modules/canbus/vehicle/transit/protocol/adc_auxiliarycontrol_110.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/adc_auxiliarycontrol_110.h" +#include "modules/canbus/vehicle/transit/protocol/adc_auxiliarycontrol_110.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/transit/protocol/adc_auxiliarycontrol_110.h b/modules/canbus/vehicle/transit/protocol/adc_auxiliarycontrol_110.h similarity index 99% rename from modules/canbus_vehicle/transit/protocol/adc_auxiliarycontrol_110.h rename to modules/canbus/vehicle/transit/protocol/adc_auxiliarycontrol_110.h index 230d0907771..91ea4dbce27 100644 --- a/modules/canbus_vehicle/transit/protocol/adc_auxiliarycontrol_110.h +++ b/modules/canbus/vehicle/transit/protocol/adc_auxiliarycontrol_110.h @@ -17,7 +17,7 @@ #pragma once #include "gtest/gtest_prod.h" -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,7 +25,7 @@ namespace canbus { namespace transit { class Adcauxiliarycontrol110 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Transit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/transit/protocol/adc_auxiliarycontrol_110_test.cc b/modules/canbus/vehicle/transit/protocol/adc_auxiliarycontrol_110_test.cc similarity index 98% rename from modules/canbus_vehicle/transit/protocol/adc_auxiliarycontrol_110_test.cc rename to modules/canbus/vehicle/transit/protocol/adc_auxiliarycontrol_110_test.cc index fe2707d86f6..63d83f60480 100644 --- a/modules/canbus_vehicle/transit/protocol/adc_auxiliarycontrol_110_test.cc +++ b/modules/canbus/vehicle/transit/protocol/adc_auxiliarycontrol_110_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/adc_auxiliarycontrol_110.h" +#include "modules/canbus/vehicle/transit/protocol/adc_auxiliarycontrol_110.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/transit/protocol/adc_motioncontrol1_10.cc b/modules/canbus/vehicle/transit/protocol/adc_motioncontrol1_10.cc similarity index 99% rename from modules/canbus_vehicle/transit/protocol/adc_motioncontrol1_10.cc rename to modules/canbus/vehicle/transit/protocol/adc_motioncontrol1_10.cc index eeb0ddfc063..9f08e726da1 100644 --- a/modules/canbus_vehicle/transit/protocol/adc_motioncontrol1_10.cc +++ b/modules/canbus/vehicle/transit/protocol/adc_motioncontrol1_10.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/adc_motioncontrol1_10.h" +#include "modules/canbus/vehicle/transit/protocol/adc_motioncontrol1_10.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/transit/protocol/adc_motioncontrol1_10.h b/modules/canbus/vehicle/transit/protocol/adc_motioncontrol1_10.h similarity index 98% rename from modules/canbus_vehicle/transit/protocol/adc_motioncontrol1_10.h rename to modules/canbus/vehicle/transit/protocol/adc_motioncontrol1_10.h index c539de139df..9ba7185da3f 100644 --- a/modules/canbus_vehicle/transit/protocol/adc_motioncontrol1_10.h +++ b/modules/canbus/vehicle/transit/protocol/adc_motioncontrol1_10.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" #include "gtest/gtest_prod.h" @@ -26,7 +26,7 @@ namespace canbus { namespace transit { class Adcmotioncontrol110 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Transit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/transit/protocol/adc_motioncontrol1_10_test.cc b/modules/canbus/vehicle/transit/protocol/adc_motioncontrol1_10_test.cc similarity index 98% rename from modules/canbus_vehicle/transit/protocol/adc_motioncontrol1_10_test.cc rename to modules/canbus/vehicle/transit/protocol/adc_motioncontrol1_10_test.cc index 351bab764b8..0f54eeea7c8 100644 --- a/modules/canbus_vehicle/transit/protocol/adc_motioncontrol1_10_test.cc +++ b/modules/canbus/vehicle/transit/protocol/adc_motioncontrol1_10_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/adc_motioncontrol1_10.h" +#include "modules/canbus/vehicle/transit/protocol/adc_motioncontrol1_10.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/transit/protocol/adc_motioncontrollimits1_12.cc b/modules/canbus/vehicle/transit/protocol/adc_motioncontrollimits1_12.cc similarity index 98% rename from modules/canbus_vehicle/transit/protocol/adc_motioncontrollimits1_12.cc rename to modules/canbus/vehicle/transit/protocol/adc_motioncontrollimits1_12.cc index 67ecd6179e6..98387ef55bb 100644 --- a/modules/canbus_vehicle/transit/protocol/adc_motioncontrollimits1_12.cc +++ b/modules/canbus/vehicle/transit/protocol/adc_motioncontrollimits1_12.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/adc_motioncontrollimits1_12.h" +#include "modules/canbus/vehicle/transit/protocol/adc_motioncontrollimits1_12.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/transit/protocol/adc_motioncontrollimits1_12.h b/modules/canbus/vehicle/transit/protocol/adc_motioncontrollimits1_12.h similarity index 97% rename from modules/canbus_vehicle/transit/protocol/adc_motioncontrollimits1_12.h rename to modules/canbus/vehicle/transit/protocol/adc_motioncontrollimits1_12.h index a3a04475fd4..b6617167dd2 100644 --- a/modules/canbus_vehicle/transit/protocol/adc_motioncontrollimits1_12.h +++ b/modules/canbus/vehicle/transit/protocol/adc_motioncontrollimits1_12.h @@ -17,7 +17,7 @@ #pragma once #include "gtest/gtest.h" -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -26,7 +26,7 @@ namespace transit { class Adcmotioncontrollimits112 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Transit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/transit/protocol/adc_motioncontrollimits1_12_test.cc b/modules/canbus/vehicle/transit/protocol/adc_motioncontrollimits1_12_test.cc similarity index 97% rename from modules/canbus_vehicle/transit/protocol/adc_motioncontrollimits1_12_test.cc rename to modules/canbus/vehicle/transit/protocol/adc_motioncontrollimits1_12_test.cc index 5864d10ec33..a849178152d 100644 --- a/modules/canbus_vehicle/transit/protocol/adc_motioncontrollimits1_12_test.cc +++ b/modules/canbus/vehicle/transit/protocol/adc_motioncontrollimits1_12_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/adc_motioncontrollimits1_12.h" +#include "modules/canbus/vehicle/transit/protocol/adc_motioncontrollimits1_12.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/transit/protocol/llc_auxiliaryfeedback_120.cc b/modules/canbus/vehicle/transit/protocol/llc_auxiliaryfeedback_120.cc similarity index 80% rename from modules/canbus_vehicle/transit/protocol/llc_auxiliaryfeedback_120.cc rename to modules/canbus/vehicle/transit/protocol/llc_auxiliaryfeedback_120.cc index 9e45bbc8daa..49b9df17bfa 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_auxiliaryfeedback_120.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_auxiliaryfeedback_120.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_auxiliaryfeedback_120.h" +#include "modules/canbus/vehicle/transit/protocol/llc_auxiliaryfeedback_120.h" #include "glog/logging.h" @@ -31,42 +31,60 @@ Llcauxiliaryfeedback120::Llcauxiliaryfeedback120() {} const int32_t Llcauxiliaryfeedback120::ID = 0x120; void Llcauxiliaryfeedback120::Parse(const std::uint8_t* bytes, int32_t length, - Transit* chassis) const { - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_inverter( - llc_fbk_inverter(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_pdu_ch8( - llc_fbk_pdu_ch8(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_pdu_ch7( - llc_fbk_pdu_ch7(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_pdu_ch6( - llc_fbk_pdu_ch6(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_pdu_ch5( - llc_fbk_pdu_ch5(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_pdu_ch4( - llc_fbk_pdu_ch4(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_pdu_ch3( - llc_fbk_pdu_ch3(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_pdu_ch2( - llc_fbk_pdu_ch2(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_pdu_ch1( - llc_fbk_pdu_ch1(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_hazardlights( - llc_fbk_hazardlights(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_ledgreenon( - llc_fbk_ledgreenon(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_horn( - llc_fbk_horn(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_buzzeron( - llc_fbk_buzzeron(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_turnsignal( - llc_fbk_turnsignal(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_lowbeam( - llc_fbk_lowbeam(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_highbeam( - llc_fbk_highbeam(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120()->set_llc_fbk_ledredon( - llc_fbk_ledredon(bytes, length)); - chassis->mutable_llc_auxiliaryfeedback_120() + ChassisDetail* chassis) const { + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_inverter(llc_fbk_inverter(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_pdu_ch8(llc_fbk_pdu_ch8(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_pdu_ch7(llc_fbk_pdu_ch7(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_pdu_ch6(llc_fbk_pdu_ch6(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_pdu_ch5(llc_fbk_pdu_ch5(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_pdu_ch4(llc_fbk_pdu_ch4(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_pdu_ch3(llc_fbk_pdu_ch3(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_pdu_ch2(llc_fbk_pdu_ch2(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_pdu_ch1(llc_fbk_pdu_ch1(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_hazardlights(llc_fbk_hazardlights(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_ledgreenon(llc_fbk_ledgreenon(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_horn(llc_fbk_horn(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_buzzeron(llc_fbk_buzzeron(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_turnsignal(llc_fbk_turnsignal(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_lowbeam(llc_fbk_lowbeam(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_highbeam(llc_fbk_highbeam(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() + ->set_llc_fbk_ledredon(llc_fbk_ledredon(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_auxiliaryfeedback_120() ->set_llc_fbk_autonomybuttonpressed( llc_fbk_autonomybuttonpressed(bytes, length)); } diff --git a/modules/canbus_vehicle/transit/protocol/llc_auxiliaryfeedback_120.h b/modules/canbus/vehicle/transit/protocol/llc_auxiliaryfeedback_120.h similarity index 97% rename from modules/canbus_vehicle/transit/protocol/llc_auxiliaryfeedback_120.h rename to modules/canbus/vehicle/transit/protocol/llc_auxiliaryfeedback_120.h index a99b7a2939b..bc2f889c4a9 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_auxiliaryfeedback_120.h +++ b/modules/canbus/vehicle/transit/protocol/llc_auxiliaryfeedback_120.h @@ -18,7 +18,7 @@ #include "gtest/gtest_prod.h" -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -26,12 +26,12 @@ namespace canbus { namespace transit { class Llcauxiliaryfeedback120 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Transit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Llcauxiliaryfeedback120(); void Parse(const std::uint8_t* bytes, int32_t length, - Transit* chassis) const override; + ChassisDetail* chassis) const override; FRIEND_TEST(llc_auxiliaryfeedback_120Test, General); diff --git a/modules/canbus_vehicle/transit/protocol/llc_auxiliaryfeedback_120_test.cc b/modules/canbus/vehicle/transit/protocol/llc_auxiliaryfeedback_120_test.cc similarity index 95% rename from modules/canbus_vehicle/transit/protocol/llc_auxiliaryfeedback_120_test.cc rename to modules/canbus/vehicle/transit/protocol/llc_auxiliaryfeedback_120_test.cc index eeb95342d00..032715998be 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_auxiliaryfeedback_120_test.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_auxiliaryfeedback_120_test.cc @@ -14,10 +14,10 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_auxiliaryfeedback_120.h" +#include "modules/canbus/vehicle/transit/protocol/llc_auxiliaryfeedback_120.h" #include "gtest/gtest.h" -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" +#include "modules/common_msgs/chassis_msgs/transit.pb.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/common/canbus_consts.h" diff --git a/modules/canbus_vehicle/transit/protocol/llc_diag_brakecontrol_721.cc b/modules/canbus/vehicle/transit/protocol/llc_diag_brakecontrol_721.cc similarity index 99% rename from modules/canbus_vehicle/transit/protocol/llc_diag_brakecontrol_721.cc rename to modules/canbus/vehicle/transit/protocol/llc_diag_brakecontrol_721.cc index 6359b151d16..8ec5f691609 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_diag_brakecontrol_721.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_diag_brakecontrol_721.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_diag_brakecontrol_721.h" +#include "modules/canbus/vehicle/transit/protocol/llc_diag_brakecontrol_721.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/transit/protocol/llc_diag_brakecontrol_721.h b/modules/canbus/vehicle/transit/protocol/llc_diag_brakecontrol_721.h similarity index 97% rename from modules/canbus_vehicle/transit/protocol/llc_diag_brakecontrol_721.h rename to modules/canbus/vehicle/transit/protocol/llc_diag_brakecontrol_721.h index 359fbc802d7..7996dbea8f3 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_diag_brakecontrol_721.h +++ b/modules/canbus/vehicle/transit/protocol/llc_diag_brakecontrol_721.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" #include "gtest/gtest_prod.h" @@ -26,7 +26,7 @@ namespace canbus { namespace transit { class Llcdiagbrakecontrol721 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Transit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/transit/protocol/llc_diag_brakecontrol_721_test.cc b/modules/canbus/vehicle/transit/protocol/llc_diag_brakecontrol_721_test.cc similarity index 97% rename from modules/canbus_vehicle/transit/protocol/llc_diag_brakecontrol_721_test.cc rename to modules/canbus/vehicle/transit/protocol/llc_diag_brakecontrol_721_test.cc index 0f5c8c1412b..06d35163588 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_diag_brakecontrol_721_test.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_diag_brakecontrol_721_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_diag_brakecontrol_721.h" +#include "modules/canbus/vehicle/transit/protocol/llc_diag_brakecontrol_721.h" #include "gtest/gtest.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/transit/protocol/llc_diag_fault_620.cc b/modules/canbus/vehicle/transit/protocol/llc_diag_fault_620.cc similarity index 80% rename from modules/canbus_vehicle/transit/protocol/llc_diag_fault_620.cc rename to modules/canbus/vehicle/transit/protocol/llc_diag_fault_620.cc index e54e395f4e3..2020e675773 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_diag_fault_620.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_diag_fault_620.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_diag_fault_620.h" +#include "modules/canbus/vehicle/transit/protocol/llc_diag_fault_620.h" #include "glog/logging.h" @@ -31,25 +31,38 @@ Llcdiagfault620::Llcdiagfault620() {} const int32_t Llcdiagfault620::ID = 0x620; void Llcdiagfault620::Parse(const std::uint8_t* bytes, int32_t length, - Transit* chassis) const { - chassis->mutable_llc_diag_fault_620()->set_llc_disengagecounter_brake( - llc_disengagecounter_brake(bytes, length)); - chassis->mutable_llc_diag_fault_620()->set_llc_disengagecounter_steer( - llc_disengagecounter_steer(bytes, length)); - chassis->mutable_llc_diag_fault_620()->set_llc_disengagecounter_throttle( - llc_disengagecounter_throttle(bytes, length)); - chassis->mutable_llc_diag_fault_620()->set_llc_fbk_faultcounter( - llc_fbk_faultcounter(bytes, length)); - chassis->mutable_llc_diag_fault_620()->set_llc_disengagecounter_button( - llc_disengagecounter_button(bytes, length)); - chassis->mutable_llc_diag_fault_620()->set_llc_fbk_version_year( - llc_fbk_version_year(bytes, length)); - chassis->mutable_llc_diag_fault_620()->set_llc_fbk_version_month( - llc_fbk_version_month(bytes, length)); - chassis->mutable_llc_diag_fault_620()->set_llc_fbk_version_day( - llc_fbk_version_day(bytes, length)); - chassis->mutable_llc_diag_fault_620()->set_llc_fbk_version_hour( - llc_fbk_version_hour(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_transit() + ->mutable_llc_diag_fault_620() + ->set_llc_disengagecounter_brake( + llc_disengagecounter_brake(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_diag_fault_620() + ->set_llc_disengagecounter_steer( + llc_disengagecounter_steer(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_diag_fault_620() + ->set_llc_disengagecounter_throttle( + llc_disengagecounter_throttle(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_diag_fault_620() + ->set_llc_fbk_faultcounter(llc_fbk_faultcounter(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_diag_fault_620() + ->set_llc_disengagecounter_button( + llc_disengagecounter_button(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_diag_fault_620() + ->set_llc_fbk_version_year(llc_fbk_version_year(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_diag_fault_620() + ->set_llc_fbk_version_month(llc_fbk_version_month(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_diag_fault_620() + ->set_llc_fbk_version_day(llc_fbk_version_day(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_diag_fault_620() + ->set_llc_fbk_version_hour(llc_fbk_version_hour(bytes, length)); } // config detail: {'description': 'Counts the number of times that the driver diff --git a/modules/canbus_vehicle/transit/protocol/llc_diag_fault_620.h b/modules/canbus/vehicle/transit/protocol/llc_diag_fault_620.h similarity index 96% rename from modules/canbus_vehicle/transit/protocol/llc_diag_fault_620.h rename to modules/canbus/vehicle/transit/protocol/llc_diag_fault_620.h index 2332795cd83..f0009029d42 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_diag_fault_620.h +++ b/modules/canbus/vehicle/transit/protocol/llc_diag_fault_620.h @@ -17,7 +17,7 @@ #pragma once #include "gtest/gtest_prod.h" -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,12 +25,12 @@ namespace canbus { namespace transit { class Llcdiagfault620 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Transit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Llcdiagfault620(); void Parse(const std::uint8_t* bytes, int32_t length, - Transit* chassis) const override; + ChassisDetail* chassis) const override; FRIEND_TEST(Diag_fault_620_test, General); private: diff --git a/modules/canbus_vehicle/transit/protocol/llc_diag_fault_620_test.cc b/modules/canbus/vehicle/transit/protocol/llc_diag_fault_620_test.cc similarity index 98% rename from modules/canbus_vehicle/transit/protocol/llc_diag_fault_620_test.cc rename to modules/canbus/vehicle/transit/protocol/llc_diag_fault_620_test.cc index 74afab4d0c5..4b7fc968483 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_diag_fault_620_test.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_diag_fault_620_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_diag_fault_620.h" +#include "modules/canbus/vehicle/transit/protocol/llc_diag_fault_620.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/transit/protocol/llc_diag_steeringcontrol_722.cc b/modules/canbus/vehicle/transit/protocol/llc_diag_steeringcontrol_722.cc similarity index 98% rename from modules/canbus_vehicle/transit/protocol/llc_diag_steeringcontrol_722.cc rename to modules/canbus/vehicle/transit/protocol/llc_diag_steeringcontrol_722.cc index 5346e0e2a53..8c2caa61837 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_diag_steeringcontrol_722.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_diag_steeringcontrol_722.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_diag_steeringcontrol_722.h" +#include "modules/canbus/vehicle/transit/protocol/llc_diag_steeringcontrol_722.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/transit/protocol/llc_diag_steeringcontrol_722.h b/modules/canbus/vehicle/transit/protocol/llc_diag_steeringcontrol_722.h similarity index 97% rename from modules/canbus_vehicle/transit/protocol/llc_diag_steeringcontrol_722.h rename to modules/canbus/vehicle/transit/protocol/llc_diag_steeringcontrol_722.h index c89ca483733..37c47c927fb 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_diag_steeringcontrol_722.h +++ b/modules/canbus/vehicle/transit/protocol/llc_diag_steeringcontrol_722.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,7 +25,7 @@ namespace transit { class Llcdiagsteeringcontrol722 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Transit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/transit/protocol/llc_diag_steeringcontrol_722_test.cc b/modules/canbus/vehicle/transit/protocol/llc_diag_steeringcontrol_722_test.cc similarity index 96% rename from modules/canbus_vehicle/transit/protocol/llc_diag_steeringcontrol_722_test.cc rename to modules/canbus/vehicle/transit/protocol/llc_diag_steeringcontrol_722_test.cc index 3ff3b6e60b1..05046b61db0 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_diag_steeringcontrol_722_test.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_diag_steeringcontrol_722_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_diag_steeringcontrol_722.h" +#include "modules/canbus/vehicle/transit/protocol/llc_diag_steeringcontrol_722.h" #include "gtest/gtest.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/transit/protocol/llc_motioncommandfeedback1_22.cc b/modules/canbus/vehicle/transit/protocol/llc_motioncommandfeedback1_22.cc similarity index 90% rename from modules/canbus_vehicle/transit/protocol/llc_motioncommandfeedback1_22.cc rename to modules/canbus/vehicle/transit/protocol/llc_motioncommandfeedback1_22.cc index 73e512231bd..090679447f7 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_motioncommandfeedback1_22.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_motioncommandfeedback1_22.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_motioncommandfeedback1_22.h" +#include "modules/canbus/vehicle/transit/protocol/llc_motioncommandfeedback1_22.h" #include "glog/logging.h" @@ -32,19 +32,24 @@ const int32_t Llcmotioncommandfeedback122::ID = 0x22; void Llcmotioncommandfeedback122::Parse(const std::uint8_t* bytes, int32_t length, - Transit* chassis) const { - chassis->mutable_llc_motioncommandfeedback1_22() + ChassisDetail* chassis) const { + chassis->mutable_transit() + ->mutable_llc_motioncommandfeedback1_22() ->set_llc_fbk_steeringanglesetpoint( llc_fbk_steeringanglesetpoint(bytes, length)); - chassis->mutable_llc_motioncommandfeedback1_22() + chassis->mutable_transit() + ->mutable_llc_motioncommandfeedback1_22() ->set_llc_fbk_throttlesetpoint(llc_fbk_throttlesetpoint(bytes, length)); - chassis->mutable_llc_motioncommandfeedback1_22() + chassis->mutable_transit() + ->mutable_llc_motioncommandfeedback1_22() ->set_llc_fbk_brakepercentsetpoint( llc_fbk_brakepercentsetpoint(bytes, length)); - chassis->mutable_llc_motioncommandfeedback1_22() + chassis->mutable_transit() + ->mutable_llc_motioncommandfeedback1_22() ->set_llc_motioncommandfeedback1_count( llc_motioncommandfeedback1_count(bytes, length)); - chassis->mutable_llc_motioncommandfeedback1_22() + chassis->mutable_transit() + ->mutable_llc_motioncommandfeedback1_22() ->set_llc_motioncommandfeedback1_check( llc_motioncommandfeedback1_check(bytes, length)); } diff --git a/modules/canbus_vehicle/transit/protocol/llc_motioncommandfeedback1_22.h b/modules/canbus/vehicle/transit/protocol/llc_motioncommandfeedback1_22.h similarity index 95% rename from modules/canbus_vehicle/transit/protocol/llc_motioncommandfeedback1_22.h rename to modules/canbus/vehicle/transit/protocol/llc_motioncommandfeedback1_22.h index 689ab1735c0..80a45330626 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_motioncommandfeedback1_22.h +++ b/modules/canbus/vehicle/transit/protocol/llc_motioncommandfeedback1_22.h @@ -17,7 +17,7 @@ #pragma once #include "gtest/gtest_prod.h" -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -26,12 +26,12 @@ namespace transit { class Llcmotioncommandfeedback122 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Transit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Llcmotioncommandfeedback122(); void Parse(const std::uint8_t* bytes, int32_t length, - Transit* chassis) const override; + ChassisDetail* chassis) const override; FRIEND_TEST(Motioncommandfeedback1_22_test, General); private: diff --git a/modules/canbus_vehicle/transit/protocol/llc_motioncommandfeedback1_22_test.cc b/modules/canbus/vehicle/transit/protocol/llc_motioncommandfeedback1_22_test.cc similarity index 97% rename from modules/canbus_vehicle/transit/protocol/llc_motioncommandfeedback1_22_test.cc rename to modules/canbus/vehicle/transit/protocol/llc_motioncommandfeedback1_22_test.cc index 82de17cc01c..acfdfba8525 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_motioncommandfeedback1_22_test.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_motioncommandfeedback1_22_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_motioncommandfeedback1_22.h" +#include "modules/canbus/vehicle/transit/protocol/llc_motioncommandfeedback1_22.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/transit/protocol/llc_motionfeedback1_20.cc b/modules/canbus/vehicle/transit/protocol/llc_motionfeedback1_20.cc similarity index 83% rename from modules/canbus_vehicle/transit/protocol/llc_motionfeedback1_20.cc rename to modules/canbus/vehicle/transit/protocol/llc_motionfeedback1_20.cc index dbd6d17a5ff..95cd9b1d279 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_motionfeedback1_20.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_motionfeedback1_20.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_motionfeedback1_20.h" +#include "modules/canbus/vehicle/transit/protocol/llc_motionfeedback1_20.h" #include "glog/logging.h" @@ -31,36 +31,54 @@ Llcmotionfeedback120::Llcmotionfeedback120() {} const int32_t Llcmotionfeedback120::ID = 0x20; void Llcmotionfeedback120::Parse(const std::uint8_t* bytes, int32_t length, - Transit* chassis) const { - chassis->mutable_llc_motionfeedback1_20()->set_llc_fbk_gear( - llc_fbk_gear(bytes, length)); - chassis->mutable_llc_motionfeedback1_20()->set_llc_fbk_parkingbrake( - llc_fbk_parkingbrake(bytes, length)); - chassis->mutable_llc_motionfeedback1_20()->set_llc_fbk_throttleposition( - llc_fbk_throttleposition(bytes, length)); - chassis->mutable_llc_motionfeedback1_20()->set_llc_fbk_brakepercentrear( - llc_fbk_brakepercentrear(bytes, length)); - chassis->mutable_llc_motionfeedback1_20()->set_llc_fbk_brakepercentfront( - llc_fbk_brakepercentfront(bytes, length)); - chassis->mutable_llc_motionfeedback1_20()->set_llc_fbk_steeringcontrolmode( - llc_fbk_steeringcontrolmode(bytes, length)); - chassis->mutable_llc_motionfeedback1_20()->set_llc_motionfeedback1_counter( - llc_motionfeedback1_counter(bytes, length)); - chassis->mutable_llc_motionfeedback1_20()->set_llc_motionfeedback1_checksum( - llc_motionfeedback1_checksum(bytes, length)); - chassis->mutable_llc_motionfeedback1_20()->set_llc_fbk_commandaligned( - llc_fbk_commandaligned(bytes, length)); - chassis->mutable_llc_motionfeedback1_20()->set_llc_fbk_estoppressed( - llc_fbk_estoppressed(bytes, length)); - chassis->mutable_llc_motionfeedback1_20()->set_llc_fbk_adcrequestautonomy( - llc_fbk_adcrequestautonomy(bytes, length)); - chassis->mutable_llc_motionfeedback1_20()->set_llc_fbk_allowautonomy( - llc_fbk_allowautonomy(bytes, length)); - chassis->mutable_llc_motionfeedback1_20() + ChassisDetail* chassis) const { + chassis->mutable_transit() + ->mutable_llc_motionfeedback1_20() + ->set_llc_fbk_gear(llc_fbk_gear(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback1_20() + ->set_llc_fbk_parkingbrake(llc_fbk_parkingbrake(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback1_20() + ->set_llc_fbk_throttleposition(llc_fbk_throttleposition(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback1_20() + ->set_llc_fbk_brakepercentrear(llc_fbk_brakepercentrear(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback1_20() + ->set_llc_fbk_brakepercentfront(llc_fbk_brakepercentfront(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback1_20() + ->set_llc_fbk_steeringcontrolmode( + llc_fbk_steeringcontrolmode(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback1_20() + ->set_llc_motionfeedback1_counter( + llc_motionfeedback1_counter(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback1_20() + ->set_llc_motionfeedback1_checksum( + llc_motionfeedback1_checksum(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback1_20() + ->set_llc_fbk_commandaligned(llc_fbk_commandaligned(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback1_20() + ->set_llc_fbk_estoppressed(llc_fbk_estoppressed(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback1_20() + ->set_llc_fbk_adcrequestautonomy( + llc_fbk_adcrequestautonomy(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback1_20() + ->set_llc_fbk_allowautonomy(llc_fbk_allowautonomy(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback1_20() ->set_llc_fbk_longitudinalcontrolmode( llc_fbk_longitudinalcontrolmode(bytes, length)); - chassis->mutable_llc_motionfeedback1_20()->set_llc_fbk_state( - llc_fbk_state(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback1_20() + ->set_llc_fbk_state(llc_fbk_state(bytes, length)); } // config detail: {'description': 'Current gear', 'enum': {0: diff --git a/modules/canbus_vehicle/transit/protocol/llc_motionfeedback1_20.h b/modules/canbus/vehicle/transit/protocol/llc_motionfeedback1_20.h similarity index 97% rename from modules/canbus_vehicle/transit/protocol/llc_motionfeedback1_20.h rename to modules/canbus/vehicle/transit/protocol/llc_motionfeedback1_20.h index 439ec935c35..44f156ccfc9 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_motionfeedback1_20.h +++ b/modules/canbus/vehicle/transit/protocol/llc_motionfeedback1_20.h @@ -17,7 +17,7 @@ #pragma once #include "gtest/gtest_prod.h" -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,12 +25,12 @@ namespace canbus { namespace transit { class Llcmotionfeedback120 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Transit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Llcmotionfeedback120(); void Parse(const std::uint8_t* bytes, int32_t length, - Transit* chassis) const override; + ChassisDetail* chassis) const override; FRIEND_TEST(Motionfeedback1_20_test, General); private: diff --git a/modules/canbus_vehicle/transit/protocol/llc_motionfeedback1_20_test.cc b/modules/canbus/vehicle/transit/protocol/llc_motionfeedback1_20_test.cc similarity index 98% rename from modules/canbus_vehicle/transit/protocol/llc_motionfeedback1_20_test.cc rename to modules/canbus/vehicle/transit/protocol/llc_motionfeedback1_20_test.cc index cf159018356..4c56c333c3a 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_motionfeedback1_20_test.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_motionfeedback1_20_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_motionfeedback1_20.h" +#include "modules/canbus/vehicle/transit/protocol/llc_motionfeedback1_20.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/transit/protocol/llc_motionfeedback2_21.cc b/modules/canbus/vehicle/transit/protocol/llc_motionfeedback2_21.cc similarity index 82% rename from modules/canbus_vehicle/transit/protocol/llc_motionfeedback2_21.cc rename to modules/canbus/vehicle/transit/protocol/llc_motionfeedback2_21.cc index 1778ec0f763..937c8eaef33 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_motionfeedback2_21.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_motionfeedback2_21.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_motionfeedback2_21.h" +#include "modules/canbus/vehicle/transit/protocol/llc_motionfeedback2_21.h" #include "glog/logging.h" @@ -31,17 +31,24 @@ Llcmotionfeedback221::Llcmotionfeedback221() {} const int32_t Llcmotionfeedback221::ID = 0x21; void Llcmotionfeedback221::Parse(const std::uint8_t* bytes, int32_t length, - Transit* chassis) const { - chassis->mutable_llc_motionfeedback2_21()->set_llc_fbk_vehiclespeed( - llc_fbk_vehiclespeed(bytes, length)); - chassis->mutable_llc_motionfeedback2_21()->set_llc_motionfeedback2_counter( - llc_motionfeedback2_counter(bytes, length)); - chassis->mutable_llc_motionfeedback2_21()->set_llc_motionfeedback2_checksum( - llc_motionfeedback2_checksum(bytes, length)); - chassis->mutable_llc_motionfeedback2_21()->set_llc_fbk_steeringrate( - llc_fbk_steeringrate(bytes, length)); - chassis->mutable_llc_motionfeedback2_21()->set_llc_fbk_steeringangle( - llc_fbk_steeringangle(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_transit() + ->mutable_llc_motionfeedback2_21() + ->set_llc_fbk_vehiclespeed(llc_fbk_vehiclespeed(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback2_21() + ->set_llc_motionfeedback2_counter( + llc_motionfeedback2_counter(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback2_21() + ->set_llc_motionfeedback2_checksum( + llc_motionfeedback2_checksum(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback2_21() + ->set_llc_fbk_steeringrate(llc_fbk_steeringrate(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_motionfeedback2_21() + ->set_llc_fbk_steeringangle(llc_fbk_steeringangle(bytes, length)); } // config detail: {'name': 'llc_fbk_vehiclespeed', 'offset': 0.0, 'precision': diff --git a/modules/canbus_vehicle/transit/protocol/llc_motionfeedback2_21.h b/modules/canbus/vehicle/transit/protocol/llc_motionfeedback2_21.h similarity index 94% rename from modules/canbus_vehicle/transit/protocol/llc_motionfeedback2_21.h rename to modules/canbus/vehicle/transit/protocol/llc_motionfeedback2_21.h index 446ebf65ab6..478f2cf747f 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_motionfeedback2_21.h +++ b/modules/canbus/vehicle/transit/protocol/llc_motionfeedback2_21.h @@ -17,7 +17,7 @@ #pragma once #include "gtest/gtest_prod.h" -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,12 +25,12 @@ namespace canbus { namespace transit { class Llcmotionfeedback221 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Transit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Llcmotionfeedback221(); void Parse(const std::uint8_t* bytes, int32_t length, - Transit* chassis) const override; + ChassisDetail* chassis) const override; FRIEND_TEST(llc_motionfeedback2_21Test, motion_fdk); diff --git a/modules/canbus_vehicle/transit/protocol/llc_motionfeedback2_21_test.cc b/modules/canbus/vehicle/transit/protocol/llc_motionfeedback2_21_test.cc similarity index 96% rename from modules/canbus_vehicle/transit/protocol/llc_motionfeedback2_21_test.cc rename to modules/canbus/vehicle/transit/protocol/llc_motionfeedback2_21_test.cc index 9772b2d3f93..73fbbe41a92 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_motionfeedback2_21_test.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_motionfeedback2_21_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_motionfeedback2_21.h" +#include "modules/canbus/vehicle/transit/protocol/llc_motionfeedback2_21.h" #include "gtest/gtest.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/transit/protocol/llc_vehiclelimits_24.cc b/modules/canbus/vehicle/transit/protocol/llc_vehiclelimits_24.cc similarity index 85% rename from modules/canbus_vehicle/transit/protocol/llc_vehiclelimits_24.cc rename to modules/canbus/vehicle/transit/protocol/llc_vehiclelimits_24.cc index ca5331fb22d..0263bdac630 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_vehiclelimits_24.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_vehiclelimits_24.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_vehiclelimits_24.h" +#include "modules/canbus/vehicle/transit/protocol/llc_vehiclelimits_24.h" #include "glog/logging.h" @@ -31,11 +31,13 @@ Llcvehiclelimits24::Llcvehiclelimits24() {} const int32_t Llcvehiclelimits24::ID = 0x24; void Llcvehiclelimits24::Parse(const std::uint8_t* bytes, int32_t length, - Transit* chassis) const { - chassis->mutable_llc_vehiclelimits_24()->set_llc_fbk_maxsteeringangle( - llc_fbk_maxsteeringangle(bytes, length)); - chassis->mutable_llc_vehiclelimits_24()->set_llc_fbk_maxbrakepercent( - llc_fbk_maxbrakepercent(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_transit() + ->mutable_llc_vehiclelimits_24() + ->set_llc_fbk_maxsteeringangle(llc_fbk_maxsteeringangle(bytes, length)); + chassis->mutable_transit() + ->mutable_llc_vehiclelimits_24() + ->set_llc_fbk_maxbrakepercent(llc_fbk_maxbrakepercent(bytes, length)); } // config detail: {'description': 'Steering angle feedback', 'offset': 0.0, diff --git a/modules/canbus_vehicle/transit/protocol/llc_vehiclelimits_24.h b/modules/canbus/vehicle/transit/protocol/llc_vehiclelimits_24.h similarity index 91% rename from modules/canbus_vehicle/transit/protocol/llc_vehiclelimits_24.h rename to modules/canbus/vehicle/transit/protocol/llc_vehiclelimits_24.h index 2af3dd635e0..874d399baee 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_vehiclelimits_24.h +++ b/modules/canbus/vehicle/transit/protocol/llc_vehiclelimits_24.h @@ -17,7 +17,7 @@ #pragma once #include "gtest/gtest_prod.h" -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -25,12 +25,12 @@ namespace canbus { namespace transit { class Llcvehiclelimits24 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Transit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Llcvehiclelimits24(); void Parse(const std::uint8_t* bytes, int32_t length, - Transit* chassis) const override; + ChassisDetail* chassis) const override; FRIEND_TEST(Vehiclelimits_24_test, General); private: diff --git a/modules/canbus_vehicle/transit/protocol/llc_vehiclelimits_24_test.cc b/modules/canbus/vehicle/transit/protocol/llc_vehiclelimits_24_test.cc similarity index 96% rename from modules/canbus_vehicle/transit/protocol/llc_vehiclelimits_24_test.cc rename to modules/canbus/vehicle/transit/protocol/llc_vehiclelimits_24_test.cc index 29a5abeab61..572fd7c452c 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_vehiclelimits_24_test.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_vehiclelimits_24_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_vehiclelimits_24.h" +#include "modules/canbus/vehicle/transit/protocol/llc_vehiclelimits_24.h" #include "gtest/gtest.h" diff --git a/modules/canbus_vehicle/transit/protocol/llc_vehiclestatus_25.cc b/modules/canbus/vehicle/transit/protocol/llc_vehiclestatus_25.cc similarity index 87% rename from modules/canbus_vehicle/transit/protocol/llc_vehiclestatus_25.cc rename to modules/canbus/vehicle/transit/protocol/llc_vehiclestatus_25.cc index 29f1dcba203..df4cdf0193c 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_vehiclestatus_25.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_vehiclestatus_25.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_vehiclestatus_25.h" +#include "modules/canbus/vehicle/transit/protocol/llc_vehiclestatus_25.h" #include "glog/logging.h" @@ -31,9 +31,10 @@ Llcvehiclestatus25::Llcvehiclestatus25() {} const int32_t Llcvehiclestatus25::ID = 0x25; void Llcvehiclestatus25::Parse(const std::uint8_t* bytes, int32_t length, - Transit* chassis) const { - chassis->mutable_llc_vehiclestatus_25()->set_llc_fbk_12voltage( - llc_fbk_12voltage(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_transit() + ->mutable_llc_vehiclestatus_25() + ->set_llc_fbk_12voltage(llc_fbk_12voltage(bytes, length)); } // config detail: {'description': 'Vehicle 12V voltage feedback', 'offset': 0.0, diff --git a/modules/canbus_vehicle/transit/protocol/llc_vehiclestatus_25.h b/modules/canbus/vehicle/transit/protocol/llc_vehiclestatus_25.h similarity index 90% rename from modules/canbus_vehicle/transit/protocol/llc_vehiclestatus_25.h rename to modules/canbus/vehicle/transit/protocol/llc_vehiclestatus_25.h index 88eff3f091f..5ed1b285a35 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_vehiclestatus_25.h +++ b/modules/canbus/vehicle/transit/protocol/llc_vehiclestatus_25.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" #include "gtest/gtest_prod.h" @@ -26,12 +26,12 @@ namespace canbus { namespace transit { class Llcvehiclestatus25 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Transit> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Llcvehiclestatus25(); void Parse(const std::uint8_t* bytes, int32_t length, - Transit* chassis) const override; + ChassisDetail* chassis) const override; FRIEND_TEST(llc_vehiclestatus_25Test, 12voltage); diff --git a/modules/canbus_vehicle/transit/protocol/llc_vehiclestatus_25_test.cc b/modules/canbus/vehicle/transit/protocol/llc_vehiclestatus_25_test.cc similarity index 95% rename from modules/canbus_vehicle/transit/protocol/llc_vehiclestatus_25_test.cc rename to modules/canbus/vehicle/transit/protocol/llc_vehiclestatus_25_test.cc index eb2b3259e89..d8a6d6bc4aa 100644 --- a/modules/canbus_vehicle/transit/protocol/llc_vehiclestatus_25_test.cc +++ b/modules/canbus/vehicle/transit/protocol/llc_vehiclestatus_25_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/protocol/llc_vehiclestatus_25.h" +#include "modules/canbus/vehicle/transit/protocol/llc_vehiclestatus_25.h" #include "gtest/gtest.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/transit/transit_controller.cc b/modules/canbus/vehicle/transit/transit_controller.cc similarity index 96% rename from modules/canbus_vehicle/transit/transit_controller.cc rename to modules/canbus/vehicle/transit/transit_controller.cc index 046f01bf38c..fec7991b8b8 100644 --- a/modules/canbus_vehicle/transit/transit_controller.cc +++ b/modules/canbus/vehicle/transit/transit_controller.cc @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/transit_controller.h" +#include "modules/canbus/vehicle/transit/transit_controller.h" #include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "cyber/common/log.h" #include "cyber/time/time.h" -#include "modules/canbus_vehicle/transit/transit_message_manager.h" +#include "modules/canbus/vehicle/transit/transit_message_manager.h" #include "modules/canbus/vehicle/vehicle_controller.h" #include "modules/common/kv_db/kv_db.h" #include "modules/drivers/canbus/can_comm/can_sender.h" @@ -44,8 +44,8 @@ const int32_t CHECK_RESPONSE_SPEED_UNIT_FLAG = 2; ErrorCode TransitController::Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Transit>* const can_sender, - MessageManager<::apollo::canbus::Transit>* const message_manager) { + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) { if (is_initialized_) { AINFO << "TransitController has already been initialized."; return ErrorCode::CANBUS_ERROR; @@ -162,7 +162,7 @@ void TransitController::Stop() { Chassis TransitController::chassis() { chassis_.Clear(); - Transit chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); // 21, 22, previously 1, 2 @@ -175,14 +175,16 @@ Chassis TransitController::chassis() { // 3 chassis_.set_engine_started(true); + // 4 + auto& transit = chassis_detail.transit(); - auto& motion20 = chassis_detail.llc_motionfeedback1_20(); + auto& motion20 = transit.llc_motionfeedback1_20(); if (motion20.has_llc_fbk_throttleposition()) { chassis_.set_throttle_percentage( static_cast(motion20.llc_fbk_throttleposition())); } - button_pressed_ = (chassis_detail.llc_motionfeedback1_20().llc_fbk_state() == + button_pressed_ = (transit.llc_motionfeedback1_20().llc_fbk_state() == Llc_motionfeedback1_20::LLC_FBK_STATE_AUTONOMY); if (motion20.has_llc_fbk_brakepercentrear()) { @@ -210,7 +212,7 @@ Chassis TransitController::chassis() { } } - auto& motion21 = chassis_detail.llc_motionfeedback2_21(); + auto& motion21 = transit.llc_motionfeedback2_21(); if (motion21.has_llc_fbk_vehiclespeed()) { chassis_.set_speed_mps(static_cast(motion21.llc_fbk_vehiclespeed())); } @@ -221,7 +223,7 @@ Chassis TransitController::chassis() { 180 / vehicle_params_.max_steer_angle() * 100)); } - auto& aux = chassis_detail.llc_auxiliaryfeedback_120(); + auto& aux = transit.llc_auxiliaryfeedback_120(); if (aux.has_llc_fbk_turnsignal()) { switch (aux.llc_fbk_turnsignal()) { case Adc_auxiliarycontrol_110::ADC_CMD_TURNSIGNAL_LEFT: @@ -244,8 +246,6 @@ Chassis TransitController::chassis() { return chassis_; } -bool TransitController::VerifyID() { return true; } - void TransitController::Emergency() { set_driving_mode(Chassis::EMERGENCY_MODE); ResetProtocol(); @@ -599,13 +599,13 @@ void TransitController::SecurityDogThreadFunc() { bool TransitController::CheckResponse() { // TODO(Udelv): Add separate indicators - Transit chassis_detail; + ChassisDetail chassis_detail; if (message_manager_->GetSensorData(&chassis_detail) != ErrorCode::OK) { AERROR_EVERY(100) << "get chassis detail failed."; return false; } - auto& motion1_20 = chassis_detail.llc_motionfeedback1_20(); + auto& motion1_20 = chassis_detail.transit().llc_motionfeedback1_20(); return (motion1_20.llc_fbk_state() == Llc_motionfeedback1_20::LLC_FBK_STATE_AUTONOMY_NOT_ALLOWED || @@ -639,7 +639,7 @@ void TransitController::set_chassis_error_code( } bool TransitController::CheckSafetyError( - const ::apollo::canbus::Transit& chassis_detail) { + const ::apollo::canbus::ChassisDetail& chassis_detail) { return true; } diff --git a/modules/canbus_vehicle/transit/transit_controller.h b/modules/canbus/vehicle/transit/transit_controller.h similarity index 87% rename from modules/canbus_vehicle/transit/transit_controller.h rename to modules/canbus/vehicle/transit/transit_controller.h index 78e133e99da..00045624426 100644 --- a/modules/canbus_vehicle/transit/transit_controller.h +++ b/modules/canbus/vehicle/transit/transit_controller.h @@ -27,18 +27,17 @@ #include "modules/common_msgs/basic_msgs/error_code.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" -#include "modules/canbus_vehicle/transit/protocol/adc_auxiliarycontrol_110.h" -#include "modules/canbus_vehicle/transit/protocol/adc_motioncontrol1_10.h" -#include "modules/canbus_vehicle/transit/protocol/adc_motioncontrollimits1_12.h" -#include "modules/canbus_vehicle/transit/protocol/llc_diag_brakecontrol_721.h" -#include "modules/canbus_vehicle/transit/protocol/llc_diag_steeringcontrol_722.h" +#include "modules/canbus/vehicle/transit/protocol/adc_auxiliarycontrol_110.h" +#include "modules/canbus/vehicle/transit/protocol/adc_motioncontrol1_10.h" +#include "modules/canbus/vehicle/transit/protocol/adc_motioncontrollimits1_12.h" +#include "modules/canbus/vehicle/transit/protocol/llc_diag_brakecontrol_721.h" +#include "modules/canbus/vehicle/transit/protocol/llc_diag_steeringcontrol_722.h" namespace apollo { namespace canbus { namespace transit { -class TransitController final - : public VehicleController<::apollo::canbus::Transit> { +class TransitController final : public VehicleController { public: TransitController() {} @@ -46,8 +45,8 @@ class TransitController final ::apollo::common::ErrorCode Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Transit>* const can_sender, - MessageManager<::apollo::canbus::Transit>* const message_manager) + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) override; bool Start() override; @@ -106,10 +105,9 @@ class TransitController final void SetTurningSignal( const ::apollo::control::ControlCommand& command) override; - bool VerifyID() override; void ResetProtocol(); bool CheckChassisError(); - bool CheckSafetyError(const canbus::Transit& chassis); + bool CheckSafetyError(const canbus::ChassisDetail& chassis); void SetLimits() override; diff --git a/modules/canbus_vehicle/transit/transit_controller_test.cc b/modules/canbus/vehicle/transit/transit_controller_test.cc similarity index 94% rename from modules/canbus_vehicle/transit/transit_controller_test.cc rename to modules/canbus/vehicle/transit/transit_controller_test.cc index 9625e3f67d3..1f85490ddd4 100644 --- a/modules/canbus_vehicle/transit/transit_controller_test.cc +++ b/modules/canbus/vehicle/transit/transit_controller_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/transit_controller.h" +#include "modules/canbus/vehicle/transit/transit_controller.h" #include @@ -23,7 +23,7 @@ #include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/canbus_vehicle/transit/transit_message_manager.h" +#include "modules/canbus/vehicle/transit/transit_message_manager.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" #include "modules/drivers/canbus/can_comm/can_sender.h" @@ -45,7 +45,7 @@ class TransitControllerTest : public ::testing::Test { protected: TransitController controller_; - CanSender<::apollo::canbus::Transit> sender_; + CanSender<::apollo::canbus::ChassisDetail> sender_; CanbusConf canbus_conf_; VehicleParameter params_; TransitMessageManager msg_manager_; diff --git a/modules/canbus_vehicle/transit/transit_message_manager.cc b/modules/canbus/vehicle/transit/transit_message_manager.cc similarity index 67% rename from modules/canbus_vehicle/transit/transit_message_manager.cc rename to modules/canbus/vehicle/transit/transit_message_manager.cc index a2e176cc8b3..a0b19033a98 100644 --- a/modules/canbus_vehicle/transit/transit_message_manager.cc +++ b/modules/canbus/vehicle/transit/transit_message_manager.cc @@ -13,21 +13,21 @@ See the License for the specific language governing permissions and limitations under the License. ==============================================================================*/ -#include "modules/canbus_vehicle/transit/transit_message_manager.h" - -#include "modules/canbus_vehicle/transit/protocol/adc_auxiliarycontrol_110.h" -#include "modules/canbus_vehicle/transit/protocol/adc_motioncontrol1_10.h" -#include "modules/canbus_vehicle/transit/protocol/adc_motioncontrollimits1_12.h" -#include "modules/canbus_vehicle/transit/protocol/llc_diag_brakecontrol_721.h" -#include "modules/canbus_vehicle/transit/protocol/llc_diag_steeringcontrol_722.h" - -#include "modules/canbus_vehicle/transit/protocol/llc_auxiliaryfeedback_120.h" -#include "modules/canbus_vehicle/transit/protocol/llc_diag_fault_620.h" -#include "modules/canbus_vehicle/transit/protocol/llc_motioncommandfeedback1_22.h" -#include "modules/canbus_vehicle/transit/protocol/llc_motionfeedback1_20.h" -#include "modules/canbus_vehicle/transit/protocol/llc_motionfeedback2_21.h" -#include "modules/canbus_vehicle/transit/protocol/llc_vehiclelimits_24.h" -#include "modules/canbus_vehicle/transit/protocol/llc_vehiclestatus_25.h" +#include "modules/canbus/vehicle/transit/transit_message_manager.h" + +#include "modules/canbus/vehicle/transit/protocol/adc_auxiliarycontrol_110.h" +#include "modules/canbus/vehicle/transit/protocol/adc_motioncontrol1_10.h" +#include "modules/canbus/vehicle/transit/protocol/adc_motioncontrollimits1_12.h" +#include "modules/canbus/vehicle/transit/protocol/llc_diag_brakecontrol_721.h" +#include "modules/canbus/vehicle/transit/protocol/llc_diag_steeringcontrol_722.h" + +#include "modules/canbus/vehicle/transit/protocol/llc_auxiliaryfeedback_120.h" +#include "modules/canbus/vehicle/transit/protocol/llc_diag_fault_620.h" +#include "modules/canbus/vehicle/transit/protocol/llc_motioncommandfeedback1_22.h" +#include "modules/canbus/vehicle/transit/protocol/llc_motionfeedback1_20.h" +#include "modules/canbus/vehicle/transit/protocol/llc_motionfeedback2_21.h" +#include "modules/canbus/vehicle/transit/protocol/llc_vehiclelimits_24.h" +#include "modules/canbus/vehicle/transit/protocol/llc_vehiclestatus_25.h" namespace apollo { namespace canbus { diff --git a/modules/canbus_vehicle/transit/transit_message_manager.h b/modules/canbus/vehicle/transit/transit_message_manager.h similarity index 88% rename from modules/canbus_vehicle/transit/transit_message_manager.h rename to modules/canbus/vehicle/transit/transit_message_manager.h index 56a466e2d6c..d4ceed49610 100644 --- a/modules/canbus_vehicle/transit/transit_message_manager.h +++ b/modules/canbus/vehicle/transit/transit_message_manager.h @@ -15,7 +15,7 @@ limitations under the License. #pragma once -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/message_manager.h" namespace apollo { @@ -25,7 +25,7 @@ namespace transit { using ::apollo::drivers::canbus::MessageManager; class TransitMessageManager - : public MessageManager<::apollo::canbus::Transit> { + : public MessageManager<::apollo::canbus::ChassisDetail> { public: TransitMessageManager(); virtual ~TransitMessageManager(); diff --git a/modules/third_party_perception/integration_tests/third_party_perception_test_base.cc b/modules/canbus/vehicle/transit/transit_vehicle_factory.cc similarity index 53% rename from modules/third_party_perception/integration_tests/third_party_perception_test_base.cc rename to modules/canbus/vehicle/transit/transit_vehicle_factory.cc index 685b4a073d4..b0a014dacc0 100644 --- a/modules/third_party_perception/integration_tests/third_party_perception_test_base.cc +++ b/modules/canbus/vehicle/transit/transit_vehicle_factory.cc @@ -14,20 +14,26 @@ * limitations under the License. *****************************************************************************/ -#include "modules/third_party_perception/integration_tests/third_party_perception_test_base.h" +#include "modules/canbus/vehicle/transit/transit_vehicle_factory.h" -DEFINE_string(test_data_dir, "", "the test data folder"); -DEFINE_string(test_localization_file, "", "localization input file"); -DEFINE_string(test_monitor_file, "", "montor input file"); - -DEFINE_bool(test_update_golden_log, false, "true to update golden log file."); +#include "cyber/common/log.h" +#include "modules/canbus/vehicle/transit/transit_controller.h" +#include "modules/canbus/vehicle/transit/transit_message_manager.h" +#include "modules/common/util/util.h" namespace apollo { -namespace third_party_perception { +namespace canbus { -uint32_t ThirdPartyPerceptionTestBase::s_seq_num_ = 0; +std::unique_ptr +TransitVehicleFactory::CreateVehicleController() { + return std::unique_ptr(new transit::TransitController()); +} -void ThirdPartyPerceptionTestBase::SetUp() { ++s_seq_num_; } +std::unique_ptr> +TransitVehicleFactory::CreateMessageManager() { + return std::unique_ptr>( + new transit::TransitMessageManager()); +} -} // namespace third_party_perception +} // namespace canbus } // namespace apollo diff --git a/modules/canbus/vehicle/transit/transit_vehicle_factory.h b/modules/canbus/vehicle/transit/transit_vehicle_factory.h new file mode 100644 index 00000000000..a79180e9883 --- /dev/null +++ b/modules/canbus/vehicle/transit/transit_vehicle_factory.h @@ -0,0 +1,65 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file transit_vehicle_factory.h + */ + +#pragma once + +#include + +#include "modules/canbus/proto/vehicle_parameter.pb.h" +#include "modules/canbus/vehicle/abstract_vehicle_factory.h" +#include "modules/canbus/vehicle/vehicle_controller.h" +#include "modules/drivers/canbus/can_comm/message_manager.h" + +/** + * @namespace apollo::canbus + * @brief apollo::canbus + */ +namespace apollo { +namespace canbus { + +/** + * @class TransitVehicleFactory + * + * @brief this class is inherited from AbstractVehicleFactory. It can be used to + * create controller and message manager for transit vehicle. + */ +class TransitVehicleFactory : public AbstractVehicleFactory { + public: + /** + * @brief destructor + */ + virtual ~TransitVehicleFactory() = default; + + /** + * @brief create transit vehicle controller + * @returns a unique_ptr that points to the created controller + */ + std::unique_ptr CreateVehicleController() override; + + /** + * @brief create transit message manager + * @returns a unique_ptr that points to the created message manager + */ + std::unique_ptr> + CreateMessageManager() override; +}; + +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/transit/transit_vehicle_factory_test.cc b/modules/canbus/vehicle/transit/transit_vehicle_factory_test.cc similarity index 58% rename from modules/canbus_vehicle/transit/transit_vehicle_factory_test.cc rename to modules/canbus/vehicle/transit/transit_vehicle_factory_test.cc index 4286946def1..595ec7ead08 100644 --- a/modules/canbus_vehicle/transit/transit_vehicle_factory_test.cc +++ b/modules/canbus/vehicle/transit/transit_vehicle_factory_test.cc @@ -1,5 +1,5 @@ /****************************************************************************** - * Copyright 2019 The Apollo Authors. All Rights Reserved. + * 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. @@ -14,40 +14,34 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/transit/transit_vehicle_factory.h" +#include "modules/canbus/vehicle/transit/transit_vehicle_factory.h" #include "gtest/gtest.h" -#include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "cyber/common/file.h" - namespace apollo { namespace canbus { class TransitVehicleFactoryTest : public ::testing::Test { public: virtual void SetUp() { - std::string canbus_conf_file = - "/apollo/modules/canbus_vehicle/transit/testdata/" - "transit_canbus_conf_test.pb.txt"; - cyber::common::GetProtoFromFile(canbus_conf_file, &canbus_conf_); - params_ = canbus_conf_.vehicle_parameter(); - params_.set_brand(apollo::common::TRANSIT); - transit_factory_.SetVehicleParameter(params_); + VehicleParameter parameter; + parameter.set_brand(apollo::common::TRANSIT); + transit_factory_.SetVehicleParameter(parameter); } virtual void TearDown() {} protected: TransitVehicleFactory transit_factory_; - CanbusConf canbus_conf_; - VehicleParameter params_; }; -TEST_F(TransitVehicleFactoryTest, Init) { - apollo::cyber::Init("vehicle_factory_test"); - EXPECT_EQ(transit_factory_.Init(&canbus_conf_), true); +TEST_F(TransitVehicleFactoryTest, InitVehicleController) { + EXPECT_NE(transit_factory_.CreateVehicleController(), nullptr); +} + +TEST_F(TransitVehicleFactoryTest, InitMessageManager) { + EXPECT_NE(transit_factory_.CreateMessageManager(), nullptr); } } // namespace canbus diff --git a/modules/canbus/vehicle/vehicle_controller.cc b/modules/canbus/vehicle/vehicle_controller.cc new file mode 100644 index 00000000000..b1cd429d6e2 --- /dev/null +++ b/modules/canbus/vehicle/vehicle_controller.cc @@ -0,0 +1,159 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "modules/canbus/vehicle/vehicle_controller.h" + +#include "cyber/common/log.h" + +namespace apollo { +namespace canbus { + +using common::ErrorCode; +using control::ControlCommand; + +Chassis::DrivingMode VehicleController::driving_mode() { + std::lock_guard lock(mode_mutex_); + return driving_mode_; +} + +void VehicleController::set_driving_mode( + const Chassis::DrivingMode &driving_mode) { + std::lock_guard lock(mode_mutex_); + driving_mode_ = driving_mode; +} + +ErrorCode VehicleController::SetDrivingMode( + const Chassis::DrivingMode &driving_mode) { + if (driving_mode == Chassis::EMERGENCY_MODE) { + AINFO << "Can't set vehicle to EMERGENCY_MODE driving mode."; + return ErrorCode::CANBUS_ERROR; + } + + // vehicle in emergency mode only response to manual mode to reset. + if (this->driving_mode() == Chassis::EMERGENCY_MODE && + driving_mode != Chassis::COMPLETE_MANUAL) { + AINFO + << "Vehicle in EMERGENCY_MODE, only response to COMPLETE_MANUAL mode."; + AINFO << "Only response to RESET ACTION."; + return ErrorCode::CANBUS_ERROR; + } + + // if current mode is same as previous, no need to set. + if (this->driving_mode() == driving_mode) { + return ErrorCode::OK; + } + + switch (driving_mode) { + case Chassis::COMPLETE_AUTO_DRIVE: { + if (EnableAutoMode() != ErrorCode::OK) { + AERROR << "Failed to enable auto mode."; + return ErrorCode::CANBUS_ERROR; + } + break; + } + case Chassis::COMPLETE_MANUAL: { + if (DisableAutoMode() != ErrorCode::OK) { + AERROR << "Failed to disable auto mode."; + return ErrorCode::CANBUS_ERROR; + } + break; + } + case Chassis::AUTO_STEER_ONLY: { + if (EnableSteeringOnlyMode() != ErrorCode::OK) { + AERROR << "Failed to enable steer only mode."; + return ErrorCode::CANBUS_ERROR; + } + break; + } + case Chassis::AUTO_SPEED_ONLY: { + if (EnableSpeedOnlyMode() != ErrorCode::OK) { + AERROR << "Failed to enable speed only mode"; + return ErrorCode::CANBUS_ERROR; + } + break; + } + default: + break; + } + return ErrorCode::OK; +} + +ErrorCode VehicleController::Update(const ControlCommand &control_command) { + if (!is_initialized_) { + AERROR << "Controller is not initialized."; + return ErrorCode::CANBUS_ERROR; + } + + // Execute action to transform driving mode + if (control_command.has_pad_msg() && control_command.pad_msg().has_action()) { + AINFO << "Canbus received pad msg: " + << control_command.pad_msg().ShortDebugString(); + Chassis::DrivingMode mode = Chassis::COMPLETE_MANUAL; + switch (control_command.pad_msg().action()) { + case control::DrivingAction::START: { + mode = Chassis::COMPLETE_AUTO_DRIVE; + break; + } + case control::DrivingAction::STOP: + case control::DrivingAction::RESET: { + // In COMPLETE_MANUAL mode + break; + } + default: { + AERROR << "No response for this action."; + break; + } + } + auto error_code = SetDrivingMode(mode); + if (error_code != ErrorCode::OK) { + AERROR << "Failed to set driving mode."; + } + } + + if (driving_mode() == Chassis::COMPLETE_AUTO_DRIVE || + driving_mode() == Chassis::AUTO_SPEED_ONLY) { + Gear(control_command.gear_location()); + Throttle(control_command.throttle()); + Acceleration(control_command.acceleration()); + Brake(control_command.brake()); + SetEpbBreak(control_command); + SetLimits(); + } + + if (driving_mode() == Chassis::COMPLETE_AUTO_DRIVE || + driving_mode() == Chassis::AUTO_STEER_ONLY) { + const double steering_rate_threshold = 1.0; + if (control_command.steering_rate() > steering_rate_threshold) { + Steer(control_command.steering_target(), control_command.steering_rate()); + } else { + Steer(control_command.steering_target()); + } + } + + if ((driving_mode() == Chassis::COMPLETE_AUTO_DRIVE || + driving_mode() == Chassis::AUTO_SPEED_ONLY || + driving_mode() == Chassis::AUTO_STEER_ONLY) && + control_command.has_signal()) { + SetHorn(control_command); + SetTurningSignal(control_command); + SetBeam(control_command); + } + + return ErrorCode::OK; +} + +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus/vehicle/vehicle_controller.h b/modules/canbus/vehicle/vehicle_controller.h index ffe7403cc86..cfdda2edb71 100644 --- a/modules/canbus/vehicle/vehicle_controller.h +++ b/modules/canbus/vehicle/vehicle_controller.h @@ -24,13 +24,12 @@ #include #include "modules/canbus/proto/canbus_conf.pb.h" - -#include "cyber/common/log.h" -#include "modules/common_msgs/basic_msgs/error_code.pb.h" #include "modules/common_msgs/chassis_msgs/chassis.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" #include "modules/common/configs/vehicle_config_helper.h" +#include "modules/common_msgs/basic_msgs/error_code.pb.h" #include "modules/drivers/canbus/can_comm/can_sender.h" #include "modules/drivers/canbus/can_comm/message_manager.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" @@ -51,7 +50,6 @@ using ::apollo::drivers::canbus::MessageManager; * @brief This is the interface class of vehicle controller. It defines pure * virtual functions, and also some implemented common functions. */ -template class VehicleController { public: virtual ~VehicleController() = default; @@ -63,8 +61,9 @@ class VehicleController { * @return error_code */ virtual common::ErrorCode Init( - const VehicleParameter ¶ms, CanSender *const can_sender, - MessageManager *const message_manager) = 0; + const VehicleParameter ¶ms, + CanSender *const can_sender, + MessageManager *const message_manager) = 0; /** * @brief start the vehicle controller. @@ -154,12 +153,6 @@ class VehicleController { virtual void SetLimits() {} - /** - * @brief Response to vehicle ID request. - * @return true if vehicle ID is successfully responsed. - */ - virtual bool VerifyID() = 0; - protected: virtual Chassis::DrivingMode driving_mode(); virtual void set_driving_mode(const Chassis::DrivingMode &driving_mode); @@ -167,162 +160,13 @@ class VehicleController { protected: canbus::VehicleParameter params_; common::VehicleParam vehicle_params_; - CanSender *can_sender_ = nullptr; - MessageManager *message_manager_ = nullptr; + CanSender *can_sender_ = nullptr; + MessageManager *message_manager_ = nullptr; bool is_initialized_ = false; // own by derviative concrete controller Chassis::DrivingMode driving_mode_ = Chassis::COMPLETE_MANUAL; bool is_reset_ = false; // reset command from control command std::mutex mode_mutex_; // only use in this base class }; -using common::ErrorCode; -using control::ControlCommand; - -template -Chassis::DrivingMode VehicleController::driving_mode() { - std::lock_guard lock(mode_mutex_); - return driving_mode_; -} - -template -void VehicleController::set_driving_mode( - const Chassis::DrivingMode &driving_mode) { - std::lock_guard lock(mode_mutex_); - driving_mode_ = driving_mode; -} - -template -ErrorCode VehicleController::SetDrivingMode( - const Chassis::DrivingMode &driving_mode) { - if (driving_mode == Chassis::EMERGENCY_MODE) { - AINFO << "Can't set vehicle to EMERGENCY_MODE driving mode."; - return ErrorCode::CANBUS_ERROR; - } - - // vehicle in emergency mode only response to manual mode to reset. - if (this->driving_mode() == Chassis::EMERGENCY_MODE && - driving_mode != Chassis::COMPLETE_MANUAL) { - AINFO - << "Vehicle in EMERGENCY_MODE, only response to COMPLETE_MANUAL mode."; - AINFO << "Only response to RESET ACTION."; - return ErrorCode::CANBUS_ERROR; - } - - // if current mode is same as previous, no need to set. - if (this->driving_mode() == driving_mode) { - return ErrorCode::OK; - } - - switch (driving_mode) { - case Chassis::COMPLETE_AUTO_DRIVE: { - if (EnableAutoMode() != ErrorCode::OK) { - AERROR << "Failed to enable auto mode."; - return ErrorCode::CANBUS_ERROR; - } - break; - } - case Chassis::COMPLETE_MANUAL: { - if (DisableAutoMode() != ErrorCode::OK) { - AERROR << "Failed to disable auto mode."; - return ErrorCode::CANBUS_ERROR; - } - break; - } - case Chassis::AUTO_STEER_ONLY: { - if (EnableSteeringOnlyMode() != ErrorCode::OK) { - AERROR << "Failed to enable steer only mode."; - return ErrorCode::CANBUS_ERROR; - } - break; - } - case Chassis::AUTO_SPEED_ONLY: { - if (EnableSpeedOnlyMode() != ErrorCode::OK) { - AERROR << "Failed to enable speed only mode"; - return ErrorCode::CANBUS_ERROR; - } - break; - } - default: - break; - } - return ErrorCode::OK; -} - -template -ErrorCode VehicleController::Update( - const ControlCommand &control_command) { - if (!is_initialized_) { - AERROR << "Controller is not initialized."; - return ErrorCode::CANBUS_ERROR; - } - - // Execute action to transform driving mode - if (control_command.has_pad_msg() && control_command.pad_msg().has_action()) { - AINFO << "Canbus received pad msg: " - << control_command.pad_msg().ShortDebugString(); - if (control_command.pad_msg().action() == control::DrivingAction::VIN_REQ) { - if (!VerifyID()) { - AINFO << "Response vid failed, please request again."; - } else { - AINFO << "Response vid success!"; - } - } else { - Chassis::DrivingMode mode = Chassis::COMPLETE_MANUAL; - switch (control_command.pad_msg().action()) { - case control::DrivingAction::START: { - mode = Chassis::COMPLETE_AUTO_DRIVE; - break; - } - case control::DrivingAction::STOP: - case control::DrivingAction::RESET: { - // In COMPLETE_MANUAL mode - break; - } - default: { - AERROR << "No response for this action."; - break; - } - } - auto error_code = SetDrivingMode(mode); - if (error_code != ErrorCode::OK) { - AERROR << "Failed to set driving mode."; - } else { - AINFO << "Set driving mode success."; - } - } - } - - if (driving_mode() == Chassis::COMPLETE_AUTO_DRIVE || - driving_mode() == Chassis::AUTO_SPEED_ONLY) { - Gear(control_command.gear_location()); - Throttle(control_command.throttle()); - Acceleration(control_command.acceleration()); - Brake(control_command.brake()); - SetEpbBreak(control_command); - SetLimits(); - } - - if (driving_mode() == Chassis::COMPLETE_AUTO_DRIVE || - driving_mode() == Chassis::AUTO_STEER_ONLY) { - const double steering_rate_threshold = 1.0; - if (control_command.steering_rate() > steering_rate_threshold) { - Steer(control_command.steering_target(), control_command.steering_rate()); - } else { - Steer(control_command.steering_target()); - } - } - - if ((driving_mode() == Chassis::COMPLETE_AUTO_DRIVE || - driving_mode() == Chassis::AUTO_SPEED_ONLY || - driving_mode() == Chassis::AUTO_STEER_ONLY) && - control_command.has_signal()) { - SetHorn(control_command); - SetTurningSignal(control_command); - SetBeam(control_command); - } - - return ErrorCode::OK; -} - } // namespace canbus } // namespace apollo diff --git a/modules/canbus/vehicle/vehicle_factory.cc b/modules/canbus/vehicle/vehicle_factory.cc new file mode 100644 index 00000000000..cfaa0614517 --- /dev/null +++ b/modules/canbus/vehicle/vehicle_factory.cc @@ -0,0 +1,81 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "modules/canbus/vehicle/vehicle_factory.h" +#include "modules/canbus/proto/vehicle_parameter.pb.h" +#include "modules/canbus/vehicle/ch/ch_vehicle_factory.h" +#include "modules/canbus/vehicle/devkit/devkit_vehicle_factory.h" +#include "modules/canbus/vehicle/ge3/ge3_vehicle_factory.h" +#include "modules/canbus/vehicle/gem/gem_vehicle_factory.h" +#include "modules/canbus/vehicle/lexus/lexus_vehicle_factory.h" +#include "modules/canbus/vehicle/lincoln/lincoln_vehicle_factory.h" +#include "modules/canbus/vehicle/neolix_edu/neolix_edu_vehicle_factory.h" +#include "modules/canbus/vehicle/transit/transit_vehicle_factory.h" +#include "modules/canbus/vehicle/wey/wey_vehicle_factory.h" +#include "modules/canbus/vehicle/zhongyun/zhongyun_vehicle_factory.h" + +namespace apollo { +namespace canbus { + +void VehicleFactory::RegisterVehicleFactory() { + Register(apollo::common::LINCOLN_MKZ, []() -> AbstractVehicleFactory * { + return new LincolnVehicleFactory(); + }); + Register(apollo::common::GEM, []() -> AbstractVehicleFactory * { + return new GemVehicleFactory(); + }); + Register(apollo::common::LEXUS, []() -> AbstractVehicleFactory * { + return new LexusVehicleFactory(); + }); + Register(apollo::common::TRANSIT, []() -> AbstractVehicleFactory * { + return new TransitVehicleFactory(); + }); + Register(apollo::common::GE3, []() -> AbstractVehicleFactory * { + return new Ge3VehicleFactory(); + }); + Register(apollo::common::WEY, []() -> AbstractVehicleFactory * { + return new WeyVehicleFactory(); + }); + Register(apollo::common::ZHONGYUN, []() -> AbstractVehicleFactory * { + return new ZhongyunVehicleFactory(); + }); + Register(apollo::common::CH, []() -> AbstractVehicleFactory * { + return new ChVehicleFactory(); + }); + Register(apollo::common::DKIT, []() -> AbstractVehicleFactory * { + return new DevkitVehicleFactory(); + }); + Register(apollo::common::NEOLIX, []() -> AbstractVehicleFactory * { + return new Neolix_eduVehicleFactory(); + }); +} + +std::unique_ptr VehicleFactory::CreateVehicle( + const VehicleParameter &vehicle_parameter) { + auto abstract_factory = CreateObject(vehicle_parameter.brand()); + if (!abstract_factory) { + AERROR << "failed to create vehicle factory with " + << vehicle_parameter.DebugString(); + } else { + abstract_factory->SetVehicleParameter(vehicle_parameter); + AINFO << "successfully created vehicle factory with " + << vehicle_parameter.DebugString(); + } + return abstract_factory; +} + +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus/vehicle/vehicle_factory.h b/modules/canbus/vehicle/vehicle_factory.h new file mode 100644 index 00000000000..b16adbdfe6b --- /dev/null +++ b/modules/canbus/vehicle/vehicle_factory.h @@ -0,0 +1,59 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + */ + +#pragma once + +#include + +#include "modules/canbus/vehicle/abstract_vehicle_factory.h" +#include "modules/common/util/factory.h" + +/** + * @namespace apollo::canbus + * @brief apollo::canbus + */ +namespace apollo { +namespace canbus { + +/** + * @class VehicleFactory + * + * @brief This class is a factory class that will generate different + * vehicle factories based on the vehicle brand. + */ +class VehicleFactory + : public common::util::Factory { + public: + /** + * @brief register supported vehicle factories. + */ + void RegisterVehicleFactory(); + + /** + * @brief Creates an AbstractVehicleFactory object based on vehicle_parameter + * @param vehicle_parameter is defined in vehicle_parameter.proto + */ + std::unique_ptr CreateVehicle( + const VehicleParameter &vehicle_parameter); +}; + +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus/vehicle/vehicle_factory_test.cc b/modules/canbus/vehicle/vehicle_factory_test.cc new file mode 100644 index 00000000000..4220417339e --- /dev/null +++ b/modules/canbus/vehicle/vehicle_factory_test.cc @@ -0,0 +1,63 @@ +/****************************************************************************** + * 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/canbus/vehicle/vehicle_factory.h" + +#include "gtest/gtest.h" + +#include "modules/canbus/proto/vehicle_parameter.pb.h" + +namespace apollo { +namespace canbus { + +class VehicleFactoryTest : public ::testing::Test { + public: + virtual void SetUp() { factory_.RegisterVehicleFactory(); } + + protected: + VehicleFactory factory_; +}; + +TEST_F(VehicleFactoryTest, CreateVehicle) { + VehicleParameter parameter; + + parameter.set_brand(apollo::common::GEM); + EXPECT_NE(factory_.CreateVehicle(parameter), nullptr); + + parameter.set_brand(apollo::common::LINCOLN_MKZ); + EXPECT_NE(factory_.CreateVehicle(parameter), nullptr); + + parameter.set_brand(apollo::common::GE3); + EXPECT_NE(factory_.CreateVehicle(parameter), nullptr); + + parameter.set_brand(apollo::common::WEY); + EXPECT_NE(factory_.CreateVehicle(parameter), nullptr); + + parameter.set_brand(apollo::common::ZHONGYUN); + EXPECT_NE(factory_.CreateVehicle(parameter), nullptr); + + parameter.set_brand(apollo::common::CH); + EXPECT_NE(factory_.CreateVehicle(parameter), nullptr); + + parameter.set_brand(apollo::common::DKIT); + EXPECT_NE(factory_.CreateVehicle(parameter), nullptr); + + parameter.set_brand(apollo::common::NEOLIX); + EXPECT_NE(factory_.CreateVehicle(parameter), nullptr); +} + +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus/vehicle/wey/BUILD b/modules/canbus/vehicle/wey/BUILD new file mode 100644 index 00000000000..4a43e18ed98 --- /dev/null +++ b/modules/canbus/vehicle/wey/BUILD @@ -0,0 +1,77 @@ +load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") +load("//tools:cpplint.bzl", "cpplint") + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "wey_vehicle_factory", + srcs = ["wey_vehicle_factory.cc"], + hdrs = ["wey_vehicle_factory.h"], + deps = [ + ":wey_controller", + ":wey_message_manager", + "//modules/canbus/vehicle:abstract_vehicle_factory", + ], +) + +cc_test( + name = "wey_vehicle_factory_test", + size = "small", + srcs = ["wey_vehicle_factory_test.cc"], + deps = [ + ":wey_vehicle_factory", + "@com_google_googletest//:gtest_main", + ], +) + +cc_library( + name = "wey_message_manager", + srcs = ["wey_message_manager.cc"], + hdrs = ["wey_message_manager.h"], + deps = [ + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_test( + name = "wey_message_manager_test", + size = "small", + srcs = ["wey_message_manager_test.cc"], + deps = [ + ":wey_message_manager", + "@com_google_googletest//:gtest_main", + ], +) + +cc_library( + name = "wey_controller", + srcs = ["wey_controller.cc"], + hdrs = ["wey_controller.h"], + deps = [ + ":wey_message_manager", + "//modules/canbus/proto:canbus_conf_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_cc_proto", + "//modules/canbus/proto:vehicle_parameter_cc_proto", + "//modules/canbus/vehicle:vehicle_controller_base", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", + "//modules/common_msgs/basic_msgs:error_code_cc_proto", + "//modules/common_msgs/control_msgs:control_cmd_cc_proto", + ], +) + +cc_test( + name = "wey_controller_test", + size = "small", + srcs = ["wey_controller_test.cc"], + data = ["//modules/canbus:test_data"], + deps = [ + ":wey_controller", + "//modules/common/util", + "@com_google_googletest//:gtest_main", + ], +) + +cpplint() diff --git a/modules/canbus_vehicle/wey/protocol/BUILD b/modules/canbus/vehicle/wey/protocol/BUILD similarity index 73% rename from modules/canbus_vehicle/wey/protocol/BUILD rename to modules/canbus/vehicle/wey/protocol/BUILD index 220af1088df..14a926c6099 100644 --- a/modules/canbus_vehicle/wey/protocol/BUILD +++ b/modules/canbus/vehicle/wey/protocol/BUILD @@ -38,7 +38,7 @@ cc_library( "vin_resp3_393.h", ], deps = [ - "//modules/canbus_vehicle/wey/proto:wey_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -49,10 +49,9 @@ cc_test( size = "small", srcs = ["ads1_111_test.cc"], deps = [ - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -60,10 +59,9 @@ cc_test( size = "small", srcs = ["ads3_38e_test.cc"], deps = [ - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -71,10 +69,9 @@ cc_test( size = "small", srcs = ["ads_eps_113_test.cc"], deps = [ - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -82,10 +79,9 @@ cc_test( size = "small", srcs = ["ads_req_vin_390_test.cc"], deps = [ - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -93,10 +89,9 @@ cc_test( size = "small", srcs = ["ads_shifter_115_test.cc"], deps = [ - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -104,10 +99,9 @@ cc_test( size = "small", srcs = ["fail_241_test.cc"], deps = [ - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -115,10 +109,9 @@ cc_test( size = "small", srcs = ["fbs1_243_test.cc"], deps = [ - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -126,10 +119,9 @@ cc_test( size = "small", srcs = ["fbs2_240_test.cc"], deps = [ - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -137,10 +129,9 @@ cc_test( size = "small", srcs = ["fbs3_237_test.cc"], deps = [ - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -148,10 +139,9 @@ cc_test( size = "small", srcs = ["fbs4_235_test.cc"], deps = [ - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -159,10 +149,9 @@ cc_test( size = "small", srcs = ["status_310_test.cc"], deps = [ - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -170,10 +159,9 @@ cc_test( size = "small", srcs = ["vin_resp1_391_test.cc"], deps = [ - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -181,10 +169,9 @@ cc_test( size = "small", srcs = ["vin_resp2_392_test.cc"], deps = [ - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_test( @@ -192,10 +179,9 @@ cc_test( size = "small", srcs = ["vin_resp3_393_test.cc"], deps = [ - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", + "//modules/canbus/vehicle/wey/protocol:canbus_wey_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cpplint() diff --git a/modules/canbus_vehicle/wey/protocol/ads1_111.cc b/modules/canbus/vehicle/wey/protocol/ads1_111.cc similarity index 99% rename from modules/canbus_vehicle/wey/protocol/ads1_111.cc rename to modules/canbus/vehicle/wey/protocol/ads1_111.cc index ac6b7b205cc..2db08d26c87 100644 --- a/modules/canbus_vehicle/wey/protocol/ads1_111.cc +++ b/modules/canbus/vehicle/wey/protocol/ads1_111.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/ads1_111.h" +#include "modules/canbus/vehicle/wey/protocol/ads1_111.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/wey/protocol/ads1_111.h b/modules/canbus/vehicle/wey/protocol/ads1_111.h similarity index 98% rename from modules/canbus_vehicle/wey/protocol/ads1_111.h rename to modules/canbus/vehicle/wey/protocol/ads1_111.h index 295f27fa1f2..e64b6c04a92 100644 --- a/modules/canbus_vehicle/wey/protocol/ads1_111.h +++ b/modules/canbus/vehicle/wey/protocol/ads1_111.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace wey { class Ads1111 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Wey> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/wey/protocol/ads1_111_test.cc b/modules/canbus/vehicle/wey/protocol/ads1_111_test.cc similarity index 96% rename from modules/canbus_vehicle/wey/protocol/ads1_111_test.cc rename to modules/canbus/vehicle/wey/protocol/ads1_111_test.cc index 201f8f3218f..57ac02d0182 100644 --- a/modules/canbus_vehicle/wey/protocol/ads1_111_test.cc +++ b/modules/canbus/vehicle/wey/protocol/ads1_111_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/ads1_111.h" +#include "modules/canbus/vehicle/wey/protocol/ads1_111.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/wey/protocol/ads3_38e.cc b/modules/canbus/vehicle/wey/protocol/ads3_38e.cc similarity index 99% rename from modules/canbus_vehicle/wey/protocol/ads3_38e.cc rename to modules/canbus/vehicle/wey/protocol/ads3_38e.cc index f99607fb58c..efd464de855 100644 --- a/modules/canbus_vehicle/wey/protocol/ads3_38e.cc +++ b/modules/canbus/vehicle/wey/protocol/ads3_38e.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/ads3_38e.h" +#include "modules/canbus/vehicle/wey/protocol/ads3_38e.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/wey/protocol/ads3_38e.h b/modules/canbus/vehicle/wey/protocol/ads3_38e.h similarity index 99% rename from modules/canbus_vehicle/wey/protocol/ads3_38e.h rename to modules/canbus/vehicle/wey/protocol/ads3_38e.h index 1145cc0d9cb..9c6a270af85 100644 --- a/modules/canbus_vehicle/wey/protocol/ads3_38e.h +++ b/modules/canbus/vehicle/wey/protocol/ads3_38e.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace wey { class Ads338e : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Wey> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/wey/protocol/ads3_38e_test.cc b/modules/canbus/vehicle/wey/protocol/ads3_38e_test.cc similarity index 96% rename from modules/canbus_vehicle/wey/protocol/ads3_38e_test.cc rename to modules/canbus/vehicle/wey/protocol/ads3_38e_test.cc index 4a38bf95653..fbaeaedab5e 100644 --- a/modules/canbus_vehicle/wey/protocol/ads3_38e_test.cc +++ b/modules/canbus/vehicle/wey/protocol/ads3_38e_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/ads3_38e.h" +#include "modules/canbus/vehicle/wey/protocol/ads3_38e.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/wey/protocol/ads_eps_113.cc b/modules/canbus/vehicle/wey/protocol/ads_eps_113.cc similarity index 98% rename from modules/canbus_vehicle/wey/protocol/ads_eps_113.cc rename to modules/canbus/vehicle/wey/protocol/ads_eps_113.cc index 300d2dc1417..248641eb8db 100644 --- a/modules/canbus_vehicle/wey/protocol/ads_eps_113.cc +++ b/modules/canbus/vehicle/wey/protocol/ads_eps_113.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/ads_eps_113.h" +#include "modules/canbus/vehicle/wey/protocol/ads_eps_113.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/wey/protocol/ads_eps_113.h b/modules/canbus/vehicle/wey/protocol/ads_eps_113.h similarity index 95% rename from modules/canbus_vehicle/wey/protocol/ads_eps_113.h rename to modules/canbus/vehicle/wey/protocol/ads_eps_113.h index e256fddf991..7c7fcf435eb 100644 --- a/modules/canbus_vehicle/wey/protocol/ads_eps_113.h +++ b/modules/canbus/vehicle/wey/protocol/ads_eps_113.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace wey { class Adseps113 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Wey> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/wey/protocol/ads_eps_113_test.cc b/modules/canbus/vehicle/wey/protocol/ads_eps_113_test.cc similarity index 96% rename from modules/canbus_vehicle/wey/protocol/ads_eps_113_test.cc rename to modules/canbus/vehicle/wey/protocol/ads_eps_113_test.cc index 84f9321ff36..ef9b04cbd0b 100644 --- a/modules/canbus_vehicle/wey/protocol/ads_eps_113_test.cc +++ b/modules/canbus/vehicle/wey/protocol/ads_eps_113_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/ads_eps_113.h" +#include "modules/canbus/vehicle/wey/protocol/ads_eps_113.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/wey/protocol/ads_req_vin_390.cc b/modules/canbus/vehicle/wey/protocol/ads_req_vin_390.cc similarity index 97% rename from modules/canbus_vehicle/wey/protocol/ads_req_vin_390.cc rename to modules/canbus/vehicle/wey/protocol/ads_req_vin_390.cc index 530f141c1e1..59ee1cb1edc 100644 --- a/modules/canbus_vehicle/wey/protocol/ads_req_vin_390.cc +++ b/modules/canbus/vehicle/wey/protocol/ads_req_vin_390.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/ads_req_vin_390.h" +#include "modules/canbus/vehicle/wey/protocol/ads_req_vin_390.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/wey/protocol/ads_req_vin_390.h b/modules/canbus/vehicle/wey/protocol/ads_req_vin_390.h similarity index 94% rename from modules/canbus_vehicle/wey/protocol/ads_req_vin_390.h rename to modules/canbus/vehicle/wey/protocol/ads_req_vin_390.h index 5bae21fba30..c04f7bdca2c 100644 --- a/modules/canbus_vehicle/wey/protocol/ads_req_vin_390.h +++ b/modules/canbus/vehicle/wey/protocol/ads_req_vin_390.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace wey { class Adsreqvin390 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Wey> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/wey/protocol/ads_req_vin_390_test.cc b/modules/canbus/vehicle/wey/protocol/ads_req_vin_390_test.cc similarity index 95% rename from modules/canbus_vehicle/wey/protocol/ads_req_vin_390_test.cc rename to modules/canbus/vehicle/wey/protocol/ads_req_vin_390_test.cc index 80e8f32b485..2e94e94e07f 100644 --- a/modules/canbus_vehicle/wey/protocol/ads_req_vin_390_test.cc +++ b/modules/canbus/vehicle/wey/protocol/ads_req_vin_390_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/ads_req_vin_390.h" +#include "modules/canbus/vehicle/wey/protocol/ads_req_vin_390.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/wey/protocol/ads_shifter_115.cc b/modules/canbus/vehicle/wey/protocol/ads_shifter_115.cc similarity index 97% rename from modules/canbus_vehicle/wey/protocol/ads_shifter_115.cc rename to modules/canbus/vehicle/wey/protocol/ads_shifter_115.cc index 448e9c15c1c..c4099fecf29 100644 --- a/modules/canbus_vehicle/wey/protocol/ads_shifter_115.cc +++ b/modules/canbus/vehicle/wey/protocol/ads_shifter_115.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/ads_shifter_115.h" +#include "modules/canbus/vehicle/wey/protocol/ads_shifter_115.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/wey/protocol/ads_shifter_115.h b/modules/canbus/vehicle/wey/protocol/ads_shifter_115.h similarity index 96% rename from modules/canbus_vehicle/wey/protocol/ads_shifter_115.h rename to modules/canbus/vehicle/wey/protocol/ads_shifter_115.h index 38b830e4128..450cb0e84ee 100644 --- a/modules/canbus_vehicle/wey/protocol/ads_shifter_115.h +++ b/modules/canbus/vehicle/wey/protocol/ads_shifter_115.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace wey { class Adsshifter115 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Wey> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/wey/protocol/ads_shifter_115_test.cc b/modules/canbus/vehicle/wey/protocol/ads_shifter_115_test.cc similarity index 95% rename from modules/canbus_vehicle/wey/protocol/ads_shifter_115_test.cc rename to modules/canbus/vehicle/wey/protocol/ads_shifter_115_test.cc index 9abe8ba00c2..8c1d95c2e12 100644 --- a/modules/canbus_vehicle/wey/protocol/ads_shifter_115_test.cc +++ b/modules/canbus/vehicle/wey/protocol/ads_shifter_115_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/ads_shifter_115.h" +#include "modules/canbus/vehicle/wey/protocol/ads_shifter_115.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/wey/protocol/fail_241.cc b/modules/canbus/vehicle/wey/protocol/fail_241.cc similarity index 91% rename from modules/canbus_vehicle/wey/protocol/fail_241.cc rename to modules/canbus/vehicle/wey/protocol/fail_241.cc index 1bf7c329b50..5016870a69e 100644 --- a/modules/canbus_vehicle/wey/protocol/fail_241.cc +++ b/modules/canbus/vehicle/wey/protocol/fail_241.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/fail_241.h" +#include "modules/canbus/vehicle/wey/protocol/fail_241.h" #include "glog/logging.h" @@ -31,16 +31,16 @@ Fail241::Fail241() {} const int32_t Fail241::ID = 0x241; void Fail241::Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const { - chassis->mutable_fail_241()->set_engfail( + ChassisDetail* chassis) const { + chassis->mutable_wey()->mutable_fail_241()->set_engfail( engfail(bytes, length)); - chassis->mutable_fail_241()->set_espfail( + chassis->mutable_wey()->mutable_fail_241()->set_espfail( espfail(bytes, length)); - chassis->mutable_fail_241()->set_epbfail( + chassis->mutable_wey()->mutable_fail_241()->set_epbfail( epbfail(bytes, length)); - chassis->mutable_fail_241()->set_shiftfail( + chassis->mutable_wey()->mutable_fail_241()->set_shiftfail( shiftfail(bytes, length)); - chassis->mutable_fail_241()->set_epsfail( + chassis->mutable_wey()->mutable_fail_241()->set_epsfail( epsfail(bytes, length)); } diff --git a/modules/canbus_vehicle/wey/protocol/fail_241.h b/modules/canbus/vehicle/wey/protocol/fail_241.h similarity index 95% rename from modules/canbus_vehicle/wey/protocol/fail_241.h rename to modules/canbus/vehicle/wey/protocol/fail_241.h index 08dc535218e..bb71daaa609 100644 --- a/modules/canbus_vehicle/wey/protocol/fail_241.h +++ b/modules/canbus/vehicle/wey/protocol/fail_241.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace wey { class Fail241 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Wey> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Fail241(); void Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'Engine Fail status', 'enum': {0: diff --git a/modules/canbus_vehicle/wey/protocol/fail_241_test.cc b/modules/canbus/vehicle/wey/protocol/fail_241_test.cc similarity index 73% rename from modules/canbus_vehicle/wey/protocol/fail_241_test.cc rename to modules/canbus/vehicle/wey/protocol/fail_241_test.cc index c7d74178b48..425d100b069 100644 --- a/modules/canbus_vehicle/wey/protocol/fail_241_test.cc +++ b/modules/canbus/vehicle/wey/protocol/fail_241_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/fail_241.h" +#include "modules/canbus/vehicle/wey/protocol/fail_241.h" #include "gtest/gtest.h" namespace apollo { @@ -29,15 +29,15 @@ class Fail241Test : public ::testing::Test { TEST_F(Fail241Test, reset) { Fail241 fail1; int32_t length = 8; - Wey chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x88, 0x44, 0x22, 0x11, 0x95, 0x12, 0x13, 0x14}; fail1.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.fail_241().engfail(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.fail_241().espfail(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.fail_241().epbfail(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.fail_241().shiftfail(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.fail_241().epsfail(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fail_241().engfail(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fail_241().espfail(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fail_241().epbfail(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fail_241().shiftfail(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fail_241().epsfail(), 1); } } // namespace wey diff --git a/modules/canbus_vehicle/wey/protocol/fbs1_243.cc b/modules/canbus/vehicle/wey/protocol/fbs1_243.cc similarity index 90% rename from modules/canbus_vehicle/wey/protocol/fbs1_243.cc rename to modules/canbus/vehicle/wey/protocol/fbs1_243.cc index 1acbd22ad00..6935ba5aed3 100644 --- a/modules/canbus_vehicle/wey/protocol/fbs1_243.cc +++ b/modules/canbus/vehicle/wey/protocol/fbs1_243.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/fbs1_243.h" +#include "modules/canbus/vehicle/wey/protocol/fbs1_243.h" #include "glog/logging.h" @@ -31,16 +31,16 @@ Fbs1243::Fbs1243() {} const int32_t Fbs1243::ID = 0x243; void Fbs1243::Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const { - chassis->mutable_fbs1_243()->set_longitudeacce( + ChassisDetail* chassis) const { + chassis->mutable_wey()->mutable_fbs1_243()->set_longitudeacce( longitudeacce(bytes, length)); - chassis->mutable_fbs1_243()->set_lateralacce( + chassis->mutable_wey()->mutable_fbs1_243()->set_lateralacce( lateralacce(bytes, length)); - chassis->mutable_fbs1_243()->set_vehdynyawrate( + chassis->mutable_wey()->mutable_fbs1_243()->set_vehdynyawrate( vehdynyawrate(bytes, length)); - chassis->mutable_fbs1_243()->set_flwheelspd( + chassis->mutable_wey()->mutable_fbs1_243()->set_flwheelspd( flwheelspd(bytes, length)); - chassis->mutable_fbs1_243()->set_frwheeldirection( + chassis->mutable_wey()->mutable_fbs1_243()->set_frwheeldirection( frwheeldirection(bytes, length)); } diff --git a/modules/canbus_vehicle/wey/protocol/fbs1_243.h b/modules/canbus/vehicle/wey/protocol/fbs1_243.h similarity index 94% rename from modules/canbus_vehicle/wey/protocol/fbs1_243.h rename to modules/canbus/vehicle/wey/protocol/fbs1_243.h index 407a94fad55..023132e28c8 100644 --- a/modules/canbus_vehicle/wey/protocol/fbs1_243.h +++ b/modules/canbus/vehicle/wey/protocol/fbs1_243.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace wey { class Fbs1243 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Wey> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Fbs1243(); void Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'Longitude acceleration', 'offset': -21.592, diff --git a/modules/canbus_vehicle/wey/protocol/fbs1_243_test.cc b/modules/canbus/vehicle/wey/protocol/fbs1_243_test.cc similarity index 71% rename from modules/canbus_vehicle/wey/protocol/fbs1_243_test.cc rename to modules/canbus/vehicle/wey/protocol/fbs1_243_test.cc index 3c4f0846ef3..265af493ec3 100644 --- a/modules/canbus_vehicle/wey/protocol/fbs1_243_test.cc +++ b/modules/canbus/vehicle/wey/protocol/fbs1_243_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/fbs1_243.h" +#include "modules/canbus/vehicle/wey/protocol/fbs1_243.h" #include "gtest/gtest.h" namespace apollo { @@ -29,15 +29,15 @@ class Fbs1243Test : public ::testing::Test { TEST_F(Fbs1243Test, reset) { Fbs1243 fbs1; int32_t length = 8; - Wey chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x88, 0x44, 0x22, 0x11, 0x11, 0x12, 0x13, 0x14}; fbs1.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.fbs1_243().longitudeacce(), 12.59432); - EXPECT_DOUBLE_EQ(chassis_detail.fbs1_243().lateralacce(), -13.04542); - EXPECT_DOUBLE_EQ(chassis_detail.fbs1_243().vehdynyawrate(), -1.0442); - EXPECT_DOUBLE_EQ(chassis_detail.fbs1_243().flwheelspd(), 34.3125); - EXPECT_DOUBLE_EQ(chassis_detail.fbs1_243().frwheeldirection(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs1_243().longitudeacce(), 12.59432); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs1_243().lateralacce(), -13.04542); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs1_243().vehdynyawrate(), -1.0442); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs1_243().flwheelspd(), 34.3125); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs1_243().frwheeldirection(), 0); } } // namespace wey diff --git a/modules/canbus_vehicle/wey/protocol/fbs2_240.cc b/modules/canbus/vehicle/wey/protocol/fbs2_240.cc similarity index 90% rename from modules/canbus_vehicle/wey/protocol/fbs2_240.cc rename to modules/canbus/vehicle/wey/protocol/fbs2_240.cc index 20950416766..596791cdbba 100644 --- a/modules/canbus_vehicle/wey/protocol/fbs2_240.cc +++ b/modules/canbus/vehicle/wey/protocol/fbs2_240.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/fbs2_240.h" +#include "modules/canbus/vehicle/wey/protocol/fbs2_240.h" #include "glog/logging.h" @@ -31,21 +31,21 @@ Fbs2240::Fbs2240() {} const int32_t Fbs2240::ID = 0x240; void Fbs2240::Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const { - chassis->mutable_fbs2_240()->set_flwheeldirection( + ChassisDetail* chassis) const { + chassis->mutable_wey()->mutable_fbs2_240()->set_flwheeldirection( flwheeldirection(bytes, length)); - chassis->mutable_fbs2_240()->set_frwheelspd( + chassis->mutable_wey()->mutable_fbs2_240()->set_frwheelspd( frwheelspd(bytes, length)); - chassis->mutable_fbs2_240()->set_rlwheeldrivedirection( + chassis->mutable_wey()->mutable_fbs2_240()->set_rlwheeldrivedirection( rlwheeldrivedirection(bytes, length)); - chassis->mutable_fbs2_240()->set_rlwheelspd( + chassis->mutable_wey()->mutable_fbs2_240()->set_rlwheelspd( rlwheelspd(bytes, length)); - chassis->mutable_fbs2_240()->set_rrwheeldirection( + chassis->mutable_wey()->mutable_fbs2_240()->set_rrwheeldirection( rrwheeldirection(bytes, length)); - chassis->mutable_fbs2_240()->set_rrwheelspd( + chassis->mutable_wey()->mutable_fbs2_240()->set_rrwheelspd( rrwheelspd(bytes, length)); // change km/h to m/s - chassis->mutable_fbs2_240()->set_vehiclespd( + chassis->mutable_wey()->mutable_fbs2_240()->set_vehiclespd( vehiclespd(bytes, length) / 3.6); } diff --git a/modules/canbus_vehicle/wey/protocol/fbs2_240.h b/modules/canbus/vehicle/wey/protocol/fbs2_240.h similarity index 96% rename from modules/canbus_vehicle/wey/protocol/fbs2_240.h rename to modules/canbus/vehicle/wey/protocol/fbs2_240.h index 9b4eea3d724..2800d1d8d5d 100644 --- a/modules/canbus_vehicle/wey/protocol/fbs2_240.h +++ b/modules/canbus/vehicle/wey/protocol/fbs2_240.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace wey { class Fbs2240 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Wey> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Fbs2240(); void Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'Front left wheel Moving direction', diff --git a/modules/canbus_vehicle/wey/protocol/fbs2_240_test.cc b/modules/canbus/vehicle/wey/protocol/fbs2_240_test.cc similarity index 68% rename from modules/canbus_vehicle/wey/protocol/fbs2_240_test.cc rename to modules/canbus/vehicle/wey/protocol/fbs2_240_test.cc index c3c19e31a58..3def6d956b0 100644 --- a/modules/canbus_vehicle/wey/protocol/fbs2_240_test.cc +++ b/modules/canbus/vehicle/wey/protocol/fbs2_240_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/fbs2_240.h" +#include "modules/canbus/vehicle/wey/protocol/fbs2_240.h" #include "gtest/gtest.h" namespace apollo { @@ -29,16 +29,16 @@ class Fbs2240Test : public ::testing::Test { TEST_F(Fbs2240Test, reset) { Fbs2240 fbs2; int32_t length = 8; - Wey chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x88, 0x44, 0x22, 0x11, 0x11, 0x12, 0x13, 0x14}; fbs2.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.fbs2_240().flwheeldirection(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.fbs2_240().frwheelspd(), 245.25); - EXPECT_DOUBLE_EQ(chassis_detail.fbs2_240().rlwheeldrivedirection(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.fbs2_240().rlwheelspd(), 61.3125); - EXPECT_DOUBLE_EQ(chassis_detail.fbs2_240().rrwheeldirection(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.fbs2_240().rrwheelspd(), 30.7125); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs2_240().flwheeldirection(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs2_240().frwheelspd(), 245.25); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs2_240().rlwheeldrivedirection(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs2_240().rlwheelspd(), 61.3125); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs2_240().rrwheeldirection(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs2_240().rrwheelspd(), 30.7125); } } // namespace wey diff --git a/modules/canbus_vehicle/wey/protocol/fbs3_237.cc b/modules/canbus/vehicle/wey/protocol/fbs3_237.cc similarity index 90% rename from modules/canbus_vehicle/wey/protocol/fbs3_237.cc rename to modules/canbus/vehicle/wey/protocol/fbs3_237.cc index 95750db04e5..57eb9030f00 100644 --- a/modules/canbus_vehicle/wey/protocol/fbs3_237.cc +++ b/modules/canbus/vehicle/wey/protocol/fbs3_237.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/fbs3_237.h" +#include "modules/canbus/vehicle/wey/protocol/fbs3_237.h" #include "glog/logging.h" @@ -31,21 +31,21 @@ Fbs3237::Fbs3237() {} const int32_t Fbs3237::ID = 0x237; void Fbs3237::Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const { - chassis->mutable_fbs3_237()->set_engspd(engspd(bytes, length)); - chassis->mutable_fbs3_237()->set_accpedalpos( + ChassisDetail* chassis) const { + chassis->mutable_wey()->mutable_fbs3_237()->set_engspd(engspd(bytes, length)); + chassis->mutable_wey()->mutable_fbs3_237()->set_accpedalpos( accpedalpos(bytes, length)); - chassis->mutable_fbs3_237()->set_epbswtichposition( + chassis->mutable_wey()->mutable_fbs3_237()->set_epbswtichposition( epbswtichposition(bytes, length)); - chassis->mutable_fbs3_237()->set_currentgear( + chassis->mutable_wey()->mutable_fbs3_237()->set_currentgear( currentgear(bytes, length)); - chassis->mutable_fbs3_237()->set_eps_streeingmode( + chassis->mutable_wey()->mutable_fbs3_237()->set_eps_streeingmode( eps_streeingmode(bytes, length)); - chassis->mutable_fbs3_237()->set_epsdrvinputtrqvalue( + chassis->mutable_wey()->mutable_fbs3_237()->set_epsdrvinputtrqvalue( epsdrvinputtrqvalue(bytes, length)); - chassis->mutable_fbs3_237()->set_epsconsumedcurrvalue( + chassis->mutable_wey()->mutable_fbs3_237()->set_epsconsumedcurrvalue( epsconsumedcurrvalue(bytes, length)); - chassis->mutable_fbs3_237()->set_epscurrmod( + chassis->mutable_wey()->mutable_fbs3_237()->set_epscurrmod( epscurrmod(bytes, length)); // Added for response check chassis->mutable_check_response()->set_is_eps_online( diff --git a/modules/canbus_vehicle/wey/protocol/fbs3_237.h b/modules/canbus/vehicle/wey/protocol/fbs3_237.h similarity index 96% rename from modules/canbus_vehicle/wey/protocol/fbs3_237.h rename to modules/canbus/vehicle/wey/protocol/fbs3_237.h index a2fd6ae04c0..7b896da6018 100644 --- a/modules/canbus_vehicle/wey/protocol/fbs3_237.h +++ b/modules/canbus/vehicle/wey/protocol/fbs3_237.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace wey { class Fbs3237 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Wey> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Fbs3237(); void Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'Engine speed', 'offset': 0.0, diff --git a/modules/canbus_vehicle/wey/protocol/fbs3_237_test.cc b/modules/canbus/vehicle/wey/protocol/fbs3_237_test.cc similarity index 64% rename from modules/canbus_vehicle/wey/protocol/fbs3_237_test.cc rename to modules/canbus/vehicle/wey/protocol/fbs3_237_test.cc index 1b6e4b1c875..2d721610a7a 100644 --- a/modules/canbus_vehicle/wey/protocol/fbs3_237_test.cc +++ b/modules/canbus/vehicle/wey/protocol/fbs3_237_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/fbs3_237.h" +#include "modules/canbus/vehicle/wey/protocol/fbs3_237.h" #include "gtest/gtest.h" namespace apollo { @@ -29,19 +29,19 @@ class Fbs3237Test : public ::testing::Test { TEST_F(Fbs3237Test, reset) { Fbs3237 fbs3; int32_t length = 8; - Wey chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x88, 0x44, 0x22, 0x11, 0x11, 0x12, 0xFE, 0x14}; fbs3.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.fbs3_237().engspd(), 4360.5); - EXPECT_DOUBLE_EQ(chassis_detail.fbs3_237().accpedalpos(), 13.3858); - EXPECT_DOUBLE_EQ(chassis_detail.fbs3_237().epbswtichposition(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.fbs3_237().currentgear(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.fbs3_237().eps_streeingmode(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.fbs3_237().epsdrvinputtrqvalue(), + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs3_237().engspd(), 4360.5); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs3_237().accpedalpos(), 13.3858); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs3_237().epbswtichposition(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs3_237().currentgear(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs3_237().eps_streeingmode(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs3_237().epsdrvinputtrqvalue(), -19.5508); - EXPECT_DOUBLE_EQ(chassis_detail.fbs3_237().epsconsumedcurrvalue(), 127); - EXPECT_DOUBLE_EQ(chassis_detail.fbs3_237().epscurrmod(), 2); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs3_237().epsconsumedcurrvalue(), 127); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs3_237().epscurrmod(), 2); } } // namespace wey diff --git a/modules/canbus_vehicle/wey/protocol/fbs4_235.cc b/modules/canbus/vehicle/wey/protocol/fbs4_235.cc similarity index 90% rename from modules/canbus_vehicle/wey/protocol/fbs4_235.cc rename to modules/canbus/vehicle/wey/protocol/fbs4_235.cc index da5314297a7..2bc2771b6e4 100644 --- a/modules/canbus_vehicle/wey/protocol/fbs4_235.cc +++ b/modules/canbus/vehicle/wey/protocol/fbs4_235.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/fbs4_235.h" +#include "modules/canbus/vehicle/wey/protocol/fbs4_235.h" #include "glog/logging.h" @@ -31,10 +31,10 @@ Fbs4235::Fbs4235() {} const int32_t Fbs4235::ID = 0x235; void Fbs4235::Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const { - chassis->mutable_fbs4_235()->set_steerwheelangle( + ChassisDetail* chassis) const { + chassis->mutable_wey()->mutable_fbs4_235()->set_steerwheelangle( steerwheelangle(bytes, length)); - chassis->mutable_fbs4_235()->set_steerwheelspd( + chassis->mutable_wey()->mutable_fbs4_235()->set_steerwheelspd( steerwheelspd(bytes, length)); } diff --git a/modules/canbus_vehicle/wey/protocol/fbs4_235.h b/modules/canbus/vehicle/wey/protocol/fbs4_235.h similarity index 91% rename from modules/canbus_vehicle/wey/protocol/fbs4_235.h rename to modules/canbus/vehicle/wey/protocol/fbs4_235.h index e19177baef3..ec5df597ef8 100644 --- a/modules/canbus_vehicle/wey/protocol/fbs4_235.h +++ b/modules/canbus/vehicle/wey/protocol/fbs4_235.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace wey { class Fbs4235 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Wey> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Fbs4235(); void Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'angle of steering wheel ', 'offset': 0.0, diff --git a/modules/canbus_vehicle/wey/protocol/fbs4_235_test.cc b/modules/canbus/vehicle/wey/protocol/fbs4_235_test.cc similarity index 83% rename from modules/canbus_vehicle/wey/protocol/fbs4_235_test.cc rename to modules/canbus/vehicle/wey/protocol/fbs4_235_test.cc index 6b7b1573247..98ca533ffe8 100644 --- a/modules/canbus_vehicle/wey/protocol/fbs4_235_test.cc +++ b/modules/canbus/vehicle/wey/protocol/fbs4_235_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/fbs4_235.h" +#include "modules/canbus/vehicle/wey/protocol/fbs4_235.h" #include "gtest/gtest.h" namespace apollo { @@ -29,12 +29,12 @@ class Fbs4235Test : public ::testing::Test { TEST_F(Fbs4235Test, reset) { Fbs4235 fbs4; int32_t length = 8; - Wey chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x04, 0x03, 0x02, 0x01, 0x11, 0x12, 0x13, 0x14}; fbs4.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.fbs4_235().steerwheelangle(), 38.5); - EXPECT_DOUBLE_EQ(chassis_detail.fbs4_235().steerwheelspd(), 218.5); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs4_235().steerwheelangle(), 38.5); + EXPECT_DOUBLE_EQ(chassis_detail.wey().fbs4_235().steerwheelspd(), 218.5); } } // namespace wey diff --git a/modules/canbus_vehicle/wey/protocol/status_310.cc b/modules/canbus/vehicle/wey/protocol/status_310.cc similarity index 90% rename from modules/canbus_vehicle/wey/protocol/status_310.cc rename to modules/canbus/vehicle/wey/protocol/status_310.cc index d112af52001..6c69a8caa2f 100644 --- a/modules/canbus_vehicle/wey/protocol/status_310.cc +++ b/modules/canbus/vehicle/wey/protocol/status_310.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/status_310.h" +#include "modules/canbus/vehicle/wey/protocol/status_310.h" #include "glog/logging.h" @@ -31,74 +31,74 @@ Status310::Status310() {} const int32_t Status310::ID = 0x310; void Status310::Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const { - chassis->mutable_status_310()->set_longitudeaccvalid( + ChassisDetail* chassis) const { + chassis->mutable_wey()->mutable_status_310()->set_longitudeaccvalid( longitudeaccvalid(bytes, length)); - chassis->mutable_status_310()->set_lateralaccevalid( + chassis->mutable_wey()->mutable_status_310()->set_lateralaccevalid( lateralaccevalid(bytes, length)); - chassis->mutable_status_310()->set_vehdynyawratevalid( + chassis->mutable_wey()->mutable_status_310()->set_vehdynyawratevalid( vehdynyawratevalid(bytes, length)); - chassis->mutable_status_310()->set_flwheelspdvalid( + chassis->mutable_wey()->mutable_status_310()->set_flwheelspdvalid( flwheelspdvalid(bytes, length)); - chassis->mutable_status_310()->set_frwheelspdvalid( + chassis->mutable_wey()->mutable_status_310()->set_frwheelspdvalid( frwheelspdvalid(bytes, length)); - chassis->mutable_status_310()->set_rlwheelspdvalid( + chassis->mutable_wey()->mutable_status_310()->set_rlwheelspdvalid( rlwheelspdvalid(bytes, length)); - chassis->mutable_status_310()->set_rrwheelspdvalid( + chassis->mutable_wey()->mutable_status_310()->set_rrwheelspdvalid( rrwheelspdvalid(bytes, length)); - chassis->mutable_status_310()->set_vehiclespdvalid( + chassis->mutable_wey()->mutable_status_310()->set_vehiclespdvalid( vehiclespdvalid(bytes, length)); - chassis->mutable_status_310()->set_longitudedrivingmode( + chassis->mutable_wey()->mutable_status_310()->set_longitudedrivingmode( longitudedrivingmode(bytes, length)); - chassis->mutable_status_310()->set_engspdvalid( + chassis->mutable_wey()->mutable_status_310()->set_engspdvalid( engspdvalid(bytes, length)); - chassis->mutable_status_310()->set_accepedaloverride( + chassis->mutable_wey()->mutable_status_310()->set_accepedaloverride( accepedaloverride(bytes, length)); - chassis->mutable_status_310()->set_brakepedalstatus( + chassis->mutable_wey()->mutable_status_310()->set_brakepedalstatus( brakepedalstatus(bytes, length)); - chassis->mutable_status_310()->set_espbrakelightsts( + chassis->mutable_wey()->mutable_status_310()->set_espbrakelightsts( espbrakelightsts(bytes, length)); - chassis->mutable_status_310()->set_epbswtpositionvalid( + chassis->mutable_wey()->mutable_status_310()->set_epbswtpositionvalid( epbswtpositionvalid(bytes, length)); - chassis->mutable_status_310()->set_epbsts( + chassis->mutable_wey()->mutable_status_310()->set_epbsts( epbsts(bytes, length)); - chassis->mutable_status_310()->set_currentgearvalid( + chassis->mutable_wey()->mutable_status_310()->set_currentgearvalid( currentgearvalid(bytes, length)); - chassis->mutable_status_310()->set_epstrqsnsrsts( + chassis->mutable_wey()->mutable_status_310()->set_epstrqsnsrsts( epstrqsnsrsts(bytes, length)); - chassis->mutable_status_310()->set_eps_interferdetdvalid( + chassis->mutable_wey()->mutable_status_310()->set_eps_interferdetdvalid( eps_interferdetdvalid(bytes, length)); - chassis->mutable_status_310()->set_epshandsdetnsts( + chassis->mutable_wey()->mutable_status_310()->set_epshandsdetnsts( epshandsdetnsts(bytes, length)); - chassis->mutable_status_310()->set_eps_handsdetnstsvalid( + chassis->mutable_wey()->mutable_status_310()->set_eps_handsdetnstsvalid( eps_handsdetnstsvalid(bytes, length)); - chassis->mutable_status_310()->set_steerwheelanglesign( + chassis->mutable_wey()->mutable_status_310()->set_steerwheelanglesign( steerwheelanglesign(bytes, length)); - chassis->mutable_status_310()->set_steerwheelspdsign( + chassis->mutable_wey()->mutable_status_310()->set_steerwheelspdsign( steerwheelspdsign(bytes, length)); - chassis->mutable_status_310()->set_driverdoorsts( + chassis->mutable_wey()->mutable_status_310()->set_driverdoorsts( driverdoorsts(bytes, length)); - chassis->mutable_status_310()->set_rldoorsts( + chassis->mutable_wey()->mutable_status_310()->set_rldoorsts( rldoorsts(bytes, length)); - chassis->mutable_status_310()->set_passengerdoorsts( + chassis->mutable_wey()->mutable_status_310()->set_passengerdoorsts( passengerdoorsts(bytes, length)); - chassis->mutable_status_310()->set_rrdoorsts( + chassis->mutable_wey()->mutable_status_310()->set_rrdoorsts( rrdoorsts(bytes, length)); - chassis->mutable_status_310()->set_frontfoglmpsts( + chassis->mutable_wey()->mutable_status_310()->set_frontfoglmpsts( frontfoglmpsts(bytes, length)); - chassis->mutable_status_310()->set_rearfoglmpsts( + chassis->mutable_wey()->mutable_status_310()->set_rearfoglmpsts( rearfoglmpsts(bytes, length)); - chassis->mutable_status_310()->set_lowbeamsts( + chassis->mutable_wey()->mutable_status_310()->set_lowbeamsts( lowbeamsts(bytes, length)); - chassis->mutable_status_310()->set_highbeamsts( + chassis->mutable_wey()->mutable_status_310()->set_highbeamsts( highbeamsts(bytes, length)); - chassis->mutable_status_310()->set_leftturnlampsts( + chassis->mutable_wey()->mutable_status_310()->set_leftturnlampsts( leftturnlampsts(bytes, length)); - chassis->mutable_status_310()->set_rightturnlampsts( + chassis->mutable_wey()->mutable_status_310()->set_rightturnlampsts( rightturnlampsts(bytes, length)); - chassis->mutable_status_310()->set_bcm_availsts( + chassis->mutable_wey()->mutable_status_310()->set_bcm_availsts( bcm_availsts(bytes, length)); - chassis->mutable_status_310()->set_brakelmpsts( + chassis->mutable_wey()->mutable_status_310()->set_brakelmpsts( brakelmpsts(bytes, length)); // Added for response check chassis->mutable_check_response()->set_is_esp_online( diff --git a/modules/canbus_vehicle/wey/protocol/status_310.h b/modules/canbus/vehicle/wey/protocol/status_310.h similarity index 99% rename from modules/canbus_vehicle/wey/protocol/status_310.h rename to modules/canbus/vehicle/wey/protocol/status_310.h index 4ec823ddaac..aa60ab77219 100644 --- a/modules/canbus_vehicle/wey/protocol/status_310.h +++ b/modules/canbus/vehicle/wey/protocol/status_310.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace wey { class Status310 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Wey> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Status310(); void Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'description': 'Longitude acceleration valid', 'enum': diff --git a/modules/canbus/vehicle/wey/protocol/status_310_test.cc b/modules/canbus/vehicle/wey/protocol/status_310_test.cc new file mode 100644 index 00000000000..9d834dfb7e2 --- /dev/null +++ b/modules/canbus/vehicle/wey/protocol/status_310_test.cc @@ -0,0 +1,75 @@ +/****************************************************************************** + * 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/canbus/vehicle/wey/protocol/status_310.h" +#include "gtest/gtest.h" + +namespace apollo { +namespace canbus { +namespace wey { + +class Status310Test : public ::testing::Test { + public: + virtual void SetUp() {} +}; + +TEST_F(Status310Test, reset) { + Status310 status; + int32_t length = 8; + ChassisDetail chassis_detail; + uint8_t bytes[8] = {0x88, 0x44, 0x22, 0x11, 0x11, 0x12, 0x13, 0x14}; + + status.Parse(bytes, length, &chassis_detail); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().longitudeaccvalid(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().lateralaccevalid(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().vehdynyawratevalid(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().flwheelspdvalid(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().frwheelspdvalid(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().rlwheelspdvalid(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().rrwheelspdvalid(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().vehiclespdvalid(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().longitudedrivingmode(), 2); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().engspdvalid(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().accepedaloverride(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().brakepedalstatus(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().espbrakelightsts(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().epbswtpositionvalid(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().epbsts(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().currentgearvalid(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().epstrqsnsrsts(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().eps_interferdetdvalid(), + 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().epshandsdetnsts(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().eps_handsdetnstsvalid(), + 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().steerwheelanglesign(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().steerwheelspdsign(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().driverdoorsts(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().rldoorsts(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().rrdoorsts(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().frontfoglmpsts(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().rearfoglmpsts(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().lowbeamsts(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().highbeamsts(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().leftturnlampsts(), 0); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().rightturnlampsts(), 1); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().bcm_availsts(), 2); + EXPECT_DOUBLE_EQ(chassis_detail.wey().status_310().brakelmpsts(), 0); +} + +} // namespace wey +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/wey/protocol/vin_resp1_391.cc b/modules/canbus/vehicle/wey/protocol/vin_resp1_391.cc similarity index 87% rename from modules/canbus_vehicle/wey/protocol/vin_resp1_391.cc rename to modules/canbus/vehicle/wey/protocol/vin_resp1_391.cc index 4beab1588b1..89cda153fe4 100644 --- a/modules/canbus_vehicle/wey/protocol/vin_resp1_391.cc +++ b/modules/canbus/vehicle/wey/protocol/vin_resp1_391.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/vin_resp1_391.h" +#include "modules/canbus/vehicle/wey/protocol/vin_resp1_391.h" #include "glog/logging.h" @@ -31,22 +31,22 @@ Vinresp1391::Vinresp1391() {} const int32_t Vinresp1391::ID = 0x391; void Vinresp1391::Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const { - chassis->mutable_vin_resp1_391()->set_vin07( + ChassisDetail* chassis) const { + chassis->mutable_wey()->mutable_vin_resp1_391()->set_vin07( vin07(bytes, length)); - chassis->mutable_vin_resp1_391()->set_vin06( + chassis->mutable_wey()->mutable_vin_resp1_391()->set_vin06( vin06(bytes, length)); - chassis->mutable_vin_resp1_391()->set_vin05( + chassis->mutable_wey()->mutable_vin_resp1_391()->set_vin05( vin05(bytes, length)); - chassis->mutable_vin_resp1_391()->set_vin04( + chassis->mutable_wey()->mutable_vin_resp1_391()->set_vin04( vin04(bytes, length)); - chassis->mutable_vin_resp1_391()->set_vin03( + chassis->mutable_wey()->mutable_vin_resp1_391()->set_vin03( vin03(bytes, length)); - chassis->mutable_vin_resp1_391()->set_vin02( + chassis->mutable_wey()->mutable_vin_resp1_391()->set_vin02( vin02(bytes, length)); - chassis->mutable_vin_resp1_391()->set_vin00( + chassis->mutable_wey()->mutable_vin_resp1_391()->set_vin00( vin00(bytes, length)); - chassis->mutable_vin_resp1_391()->set_vin01( + chassis->mutable_wey()->mutable_vin_resp1_391()->set_vin01( vin01(bytes, length)); } diff --git a/modules/canbus_vehicle/wey/protocol/vin_resp1_391.h b/modules/canbus/vehicle/wey/protocol/vin_resp1_391.h similarity index 95% rename from modules/canbus_vehicle/wey/protocol/vin_resp1_391.h rename to modules/canbus/vehicle/wey/protocol/vin_resp1_391.h index 41b91a2098c..b467be2bbfc 100644 --- a/modules/canbus_vehicle/wey/protocol/vin_resp1_391.h +++ b/modules/canbus/vehicle/wey/protocol/vin_resp1_391.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace wey { class Vinresp1391 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Wey> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vinresp1391(); void Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VIN07', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/wey/protocol/vin_resp1_391_test.cc b/modules/canbus/vehicle/wey/protocol/vin_resp1_391_test.cc similarity index 64% rename from modules/canbus_vehicle/wey/protocol/vin_resp1_391_test.cc rename to modules/canbus/vehicle/wey/protocol/vin_resp1_391_test.cc index 6c25ed221bb..3c4e63afe25 100644 --- a/modules/canbus_vehicle/wey/protocol/vin_resp1_391_test.cc +++ b/modules/canbus/vehicle/wey/protocol/vin_resp1_391_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/vin_resp1_391.h" +#include "modules/canbus/vehicle/wey/protocol/vin_resp1_391.h" #include "gtest/gtest.h" namespace apollo { @@ -29,18 +29,18 @@ class Vinresp1391Test : public ::testing::Test { TEST_F(Vinresp1391Test, reset) { Vinresp1391 vin1; int32_t length = 8; - Wey chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x88, 0x44, 0x22, 0x11, 0x11, 0x12, 0x13, 0x14}; vin1.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp1_391().vin07(), 136); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp1_391().vin06(), 68); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp1_391().vin05(), 34); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp1_391().vin04(), 17); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp1_391().vin03(), 17); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp1_391().vin02(), 18); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp1_391().vin01(), 19); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp1_391().vin00(), 20); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp1_391().vin07(), 136); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp1_391().vin06(), 68); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp1_391().vin05(), 34); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp1_391().vin04(), 17); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp1_391().vin03(), 17); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp1_391().vin02(), 18); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp1_391().vin01(), 19); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp1_391().vin00(), 20); } } // namespace wey diff --git a/modules/canbus_vehicle/wey/protocol/vin_resp2_392.cc b/modules/canbus/vehicle/wey/protocol/vin_resp2_392.cc similarity index 87% rename from modules/canbus_vehicle/wey/protocol/vin_resp2_392.cc rename to modules/canbus/vehicle/wey/protocol/vin_resp2_392.cc index 07cf35b1cec..83e1daf284b 100644 --- a/modules/canbus_vehicle/wey/protocol/vin_resp2_392.cc +++ b/modules/canbus/vehicle/wey/protocol/vin_resp2_392.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/vin_resp2_392.h" +#include "modules/canbus/vehicle/wey/protocol/vin_resp2_392.h" #include "glog/logging.h" @@ -31,22 +31,22 @@ Vinresp2392::Vinresp2392() {} const int32_t Vinresp2392::ID = 0x392; void Vinresp2392::Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const { - chassis->mutable_vin_resp2_392()->set_vin15( + ChassisDetail* chassis) const { + chassis->mutable_wey()->mutable_vin_resp2_392()->set_vin15( vin15(bytes, length)); - chassis->mutable_vin_resp2_392()->set_vin14( + chassis->mutable_wey()->mutable_vin_resp2_392()->set_vin14( vin14(bytes, length)); - chassis->mutable_vin_resp2_392()->set_vin13( + chassis->mutable_wey()->mutable_vin_resp2_392()->set_vin13( vin13(bytes, length)); - chassis->mutable_vin_resp2_392()->set_vin12( + chassis->mutable_wey()->mutable_vin_resp2_392()->set_vin12( vin12(bytes, length)); - chassis->mutable_vin_resp2_392()->set_vin11( + chassis->mutable_wey()->mutable_vin_resp2_392()->set_vin11( vin11(bytes, length)); - chassis->mutable_vin_resp2_392()->set_vin10( + chassis->mutable_wey()->mutable_vin_resp2_392()->set_vin10( vin10(bytes, length)); - chassis->mutable_vin_resp2_392()->set_vin09( + chassis->mutable_wey()->mutable_vin_resp2_392()->set_vin09( vin09(bytes, length)); - chassis->mutable_vin_resp2_392()->set_vin08( + chassis->mutable_wey()->mutable_vin_resp2_392()->set_vin08( vin08(bytes, length)); } diff --git a/modules/canbus_vehicle/wey/protocol/vin_resp2_392.h b/modules/canbus/vehicle/wey/protocol/vin_resp2_392.h similarity index 95% rename from modules/canbus_vehicle/wey/protocol/vin_resp2_392.h rename to modules/canbus/vehicle/wey/protocol/vin_resp2_392.h index e551ecf794f..0813fc9c192 100644 --- a/modules/canbus_vehicle/wey/protocol/vin_resp2_392.h +++ b/modules/canbus/vehicle/wey/protocol/vin_resp2_392.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace wey { class Vinresp2392 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Wey> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vinresp2392(); void Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VIN15', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/wey/protocol/vin_resp2_392_test.cc b/modules/canbus/vehicle/wey/protocol/vin_resp2_392_test.cc similarity index 64% rename from modules/canbus_vehicle/wey/protocol/vin_resp2_392_test.cc rename to modules/canbus/vehicle/wey/protocol/vin_resp2_392_test.cc index d69926afad8..9cfe95271ed 100644 --- a/modules/canbus_vehicle/wey/protocol/vin_resp2_392_test.cc +++ b/modules/canbus/vehicle/wey/protocol/vin_resp2_392_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/vin_resp2_392.h" +#include "modules/canbus/vehicle/wey/protocol/vin_resp2_392.h" #include "gtest/gtest.h" namespace apollo { @@ -29,18 +29,18 @@ class Vinresp2392Test : public ::testing::Test { TEST_F(Vinresp2392Test, reset) { Vinresp2392 vin2; int32_t length = 8; - Wey chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x88, 0x44, 0x22, 0x11, 0x11, 0x12, 0x13, 0x14}; vin2.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp2_392().vin15(), 136); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp2_392().vin14(), 68); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp2_392().vin13(), 34); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp2_392().vin12(), 17); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp2_392().vin11(), 17); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp2_392().vin10(), 18); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp2_392().vin09(), 19); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp2_392().vin08(), 20); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp2_392().vin15(), 136); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp2_392().vin14(), 68); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp2_392().vin13(), 34); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp2_392().vin12(), 17); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp2_392().vin11(), 17); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp2_392().vin10(), 18); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp2_392().vin09(), 19); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp2_392().vin08(), 20); } } // namespace wey diff --git a/modules/canbus_vehicle/wey/protocol/vin_resp3_393.cc b/modules/canbus/vehicle/wey/protocol/vin_resp3_393.cc similarity index 89% rename from modules/canbus_vehicle/wey/protocol/vin_resp3_393.cc rename to modules/canbus/vehicle/wey/protocol/vin_resp3_393.cc index 6d6a63590ce..61f7b315bd7 100644 --- a/modules/canbus_vehicle/wey/protocol/vin_resp3_393.cc +++ b/modules/canbus/vehicle/wey/protocol/vin_resp3_393.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/vin_resp3_393.h" +#include "modules/canbus/vehicle/wey/protocol/vin_resp3_393.h" #include "glog/logging.h" @@ -31,8 +31,8 @@ Vinresp3393::Vinresp3393() {} const int32_t Vinresp3393::ID = 0x393; void Vinresp3393::Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const { - chassis->mutable_vin_resp3_393()->set_vin16( + ChassisDetail* chassis) const { + chassis->mutable_wey()->mutable_vin_resp3_393()->set_vin16( vin16(bytes, length)); } diff --git a/modules/canbus_vehicle/wey/protocol/vin_resp3_393.h b/modules/canbus/vehicle/wey/protocol/vin_resp3_393.h similarity index 89% rename from modules/canbus_vehicle/wey/protocol/vin_resp3_393.h rename to modules/canbus/vehicle/wey/protocol/vin_resp3_393.h index 3190248aa3a..d47da580d10 100644 --- a/modules/canbus_vehicle/wey/protocol/vin_resp3_393.h +++ b/modules/canbus/vehicle/wey/protocol/vin_resp3_393.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace wey { class Vinresp3393 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Wey> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vinresp3393(); void Parse(const std::uint8_t* bytes, int32_t length, - Wey* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'VIN16', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/wey/protocol/vin_resp3_393_test.cc b/modules/canbus/vehicle/wey/protocol/vin_resp3_393_test.cc similarity index 87% rename from modules/canbus_vehicle/wey/protocol/vin_resp3_393_test.cc rename to modules/canbus/vehicle/wey/protocol/vin_resp3_393_test.cc index 3a5b6e6ddb1..6be3aeb3ada 100644 --- a/modules/canbus_vehicle/wey/protocol/vin_resp3_393_test.cc +++ b/modules/canbus/vehicle/wey/protocol/vin_resp3_393_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/protocol/vin_resp3_393.h" +#include "modules/canbus/vehicle/wey/protocol/vin_resp3_393.h" #include "gtest/gtest.h" namespace apollo { @@ -29,11 +29,11 @@ class Vinresp3393Test : public ::testing::Test { TEST_F(Vinresp3393Test, reset) { Vinresp3393 vin3; int32_t length = 8; - Wey chassis_detail; + ChassisDetail chassis_detail; uint8_t bytes[8] = {0x88, 0x44, 0x22, 0x11, 0x11, 0x12, 0x13, 0x14}; vin3.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.vin_resp3_393().vin16(), 136); + EXPECT_DOUBLE_EQ(chassis_detail.wey().vin_resp3_393().vin16(), 136); } } // namespace wey diff --git a/modules/canbus_vehicle/wey/wey_controller.cc b/modules/canbus/vehicle/wey/wey_controller.cc similarity index 85% rename from modules/canbus_vehicle/wey/wey_controller.cc rename to modules/canbus/vehicle/wey/wey_controller.cc index ace7e756567..59c8241e65f 100644 --- a/modules/canbus_vehicle/wey/wey_controller.cc +++ b/modules/canbus/vehicle/wey/wey_controller.cc @@ -14,13 +14,11 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/wey_controller.h" - -#include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" - +#include "modules/canbus/vehicle/wey/wey_controller.h" #include "cyber/time/time.h" #include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/canbus_vehicle/wey/wey_message_manager.h" +#include "modules/canbus/vehicle/wey/wey_message_manager.h" +#include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "modules/drivers/canbus/can_comm/can_sender.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" @@ -42,8 +40,8 @@ double angle_init = 0; ErrorCode WeyController::Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Wey>* const can_sender, - MessageManager<::apollo::canbus::Wey>* const message_manager) { + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) { if (is_initialized_) { AINFO << "WeyController has already been initialized."; return ErrorCode::CANBUS_ERROR; @@ -146,35 +144,39 @@ void WeyController::Stop() { Chassis WeyController::chassis() { chassis_.Clear(); - Wey chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); // 21, 22, previously 1, 2 - // if (driving_mode() == Chassis::EMERGENCY_MODE) { - // set_chassis_error_code(Chassis::NO_ERROR); - // } + if (driving_mode() == Chassis::EMERGENCY_MODE) { + set_chassis_error_code(Chassis::NO_ERROR); + } chassis_.set_driving_mode(driving_mode()); chassis_.set_error_code(chassis_error_code()); // 3 chassis_.set_engine_started(true); + // if there is not wey, no chassis detail can be retrieved and return + if (!chassis_detail.has_wey()) { + AERROR << "NO WEY chassis information!"; + return chassis_; + } + Wey wey = chassis_detail.wey(); // 4 engine_rpm - if (chassis_detail.has_fbs3_237() && chassis_detail.fbs3_237().has_engspd()) { - chassis_.set_engine_rpm( - static_cast(chassis_detail.fbs3_237().engspd())); + if (wey.has_fbs3_237() && wey.fbs3_237().has_engspd()) { + chassis_.set_engine_rpm(static_cast(wey.fbs3_237().engspd())); } else { chassis_.set_engine_rpm(0); } // 5 6 - if (chassis_detail.has_fbs2_240() && - chassis_detail.fbs2_240().has_vehiclespd() && - chassis_detail.has_fbs1_243() && chassis_detail.has_status_310()) { - Fbs2_240 fbs2_240 = chassis_detail.fbs2_240(); - Fbs1_243 fbs1_243 = chassis_detail.fbs1_243(); - Status_310 status_310 = chassis_detail.status_310(); + if (wey.has_fbs2_240() && wey.fbs2_240().has_vehiclespd() && + wey.has_fbs1_243() && wey.has_status_310()) { + Fbs2_240 fbs2_240 = wey.fbs2_240(); + Fbs1_243 fbs1_243 = wey.fbs1_243(); + Status_310 status_310 = wey.status_310(); // speed_mps chassis_.set_speed_mps(static_cast(fbs2_240.vehiclespd())); // rr @@ -257,17 +259,15 @@ Chassis WeyController::chassis() { // 7 chassis_.set_fuel_range_m(0); // 8 - if (chassis_detail.has_fbs3_237() && - chassis_detail.fbs3_237().has_accpedalpos()) { + if (wey.has_fbs3_237() && wey.fbs3_237().has_accpedalpos()) { chassis_.set_throttle_percentage( - static_cast(chassis_detail.fbs3_237().accpedalpos())); + static_cast(wey.fbs3_237().accpedalpos())); } else { chassis_.set_throttle_percentage(0); } // 23, previously 10 gear position - if (chassis_detail.has_fbs3_237() && - chassis_detail.fbs3_237().has_currentgear()) { - switch (chassis_detail.fbs3_237().currentgear()) { + if (wey.has_fbs3_237() && wey.fbs3_237().has_currentgear()) { + switch (wey.fbs3_237().currentgear()) { case Fbs3_237::CURRENTGEAR_D: { chassis_.set_gear_location(Chassis::GEAR_DRIVE); } break; @@ -288,22 +288,20 @@ Chassis WeyController::chassis() { chassis_.set_gear_location(Chassis::GEAR_NONE); } // 11 - if (chassis_detail.has_fbs4_235() && - chassis_detail.fbs4_235().has_steerwheelangle() && - chassis_detail.has_status_310() && - chassis_detail.status_310().has_steerwheelanglesign()) { - if (chassis_detail.status_310().steerwheelanglesign() == + if (wey.has_fbs4_235() && wey.fbs4_235().has_steerwheelangle() && + wey.has_status_310() && wey.status_310().has_steerwheelanglesign()) { + if (wey.status_310().steerwheelanglesign() == Status_310::STEERWHEELANGLESIGN_LEFT_POSITIVE) { - chassis_.set_steering_percentage(static_cast( - chassis_detail.fbs4_235().steerwheelangle() * 100.0 / - vehicle_params_.max_steer_angle() * M_PI / 180)); - angle_init = chassis_detail.fbs4_235().steerwheelangle(); - } else if (chassis_detail.status_310().steerwheelanglesign() == + chassis_.set_steering_percentage( + static_cast(wey.fbs4_235().steerwheelangle() * 100.0 / + vehicle_params_.max_steer_angle() * M_PI / 180)); + angle_init = wey.fbs4_235().steerwheelangle(); + } else if (wey.status_310().steerwheelanglesign() == Status_310::STEERWHEELANGLESIGN_RIGHT_NEGATIVE) { - chassis_.set_steering_percentage(static_cast( - chassis_detail.fbs4_235().steerwheelangle() * (-1) * 100.0 / - vehicle_params_.max_steer_angle() * M_PI / 180)); - angle_init = chassis_detail.fbs4_235().steerwheelangle() * (-1); + chassis_.set_steering_percentage( + static_cast(wey.fbs4_235().steerwheelangle() * (-1) * 100.0 / + vehicle_params_.max_steer_angle() * M_PI / 180)); + angle_init = wey.fbs4_235().steerwheelangle() * (-1); } else { chassis_.set_steering_percentage(0); } @@ -312,38 +310,34 @@ Chassis WeyController::chassis() { } // 12 - if (chassis_detail.has_fbs3_237() && - chassis_detail.fbs3_237().has_epsdrvinputtrqvalue()) { + if (wey.has_fbs3_237() && wey.fbs3_237().has_epsdrvinputtrqvalue()) { chassis_.set_steering_torque_nm( - static_cast(chassis_detail.fbs3_237().epsdrvinputtrqvalue())); + static_cast(wey.fbs3_237().epsdrvinputtrqvalue())); } else { chassis_.set_steering_torque_nm(0); } // 13 - if (chassis_detail.has_status_310() && - chassis_detail.status_310().has_epbsts()) { - chassis_.set_parking_brake(chassis_detail.status_310().epbsts() == + if (wey.has_status_310() && wey.status_310().has_epbsts()) { + chassis_.set_parking_brake(wey.status_310().epbsts() == Status_310::EPBSTS_CLOSED); } else { chassis_.set_parking_brake(false); } // 14, 15 - if (chassis_detail.has_status_310() && - chassis_detail.status_310().has_lowbeamsts() && - chassis_detail.status_310().lowbeamsts() == Status_310::LOWBEAMSTS_ON) { + if (wey.has_status_310() && wey.status_310().has_lowbeamsts() && + wey.status_310().lowbeamsts() == Status_310::LOWBEAMSTS_ON) { chassis_.mutable_signal()->set_low_beam(true); } else { chassis_.mutable_signal()->set_low_beam(false); } // 16, 17 - if (chassis_detail.has_status_310()) { - if (chassis_detail.status_310().has_leftturnlampsts() && - chassis_detail.status_310().leftturnlampsts() == - Status_310::LEFTTURNLAMPSTS_ON) { + if (wey.has_status_310()) { + if (wey.status_310().has_leftturnlampsts() && + wey.status_310().leftturnlampsts() == Status_310::LEFTTURNLAMPSTS_ON) { chassis_.mutable_signal()->set_turn_signal( common::VehicleSignal::TURN_LEFT); - } else if (chassis_detail.status_310().has_rightturnlampsts() && - chassis_detail.status_310().rightturnlampsts() == + } else if (wey.status_310().has_rightturnlampsts() && + wey.status_310().rightturnlampsts() == Status_310::RIGHTTURNLAMPSTS_ON) { chassis_.mutable_signal()->set_turn_signal( common::VehicleSignal::TURN_RIGHT); @@ -356,12 +350,11 @@ Chassis WeyController::chassis() { common::VehicleSignal::TURN_NONE); } // 18 - if (chassis_detail.has_vin_resp1_391() && - chassis_detail.has_vin_resp2_392() && - chassis_detail.has_vin_resp3_393()) { - Vin_resp1_391 vin_resp1_391 = chassis_detail.vin_resp1_391(); - Vin_resp2_392 vin_resp2_392 = chassis_detail.vin_resp2_392(); - Vin_resp3_393 vin_resp3_393 = chassis_detail.vin_resp3_393(); + if (wey.has_vin_resp1_391() && wey.has_vin_resp2_392() && + wey.has_vin_resp3_393()) { + Vin_resp1_391 vin_resp1_391 = wey.vin_resp1_391(); + Vin_resp2_392 vin_resp2_392 = wey.vin_resp2_392(); + Vin_resp3_393 vin_resp3_393 = wey.vin_resp3_393(); if (vin_resp1_391.has_vin00() && vin_resp1_391.has_vin01() && vin_resp1_391.has_vin02() && vin_resp1_391.has_vin03() && vin_resp1_391.has_vin04() && vin_resp1_391.has_vin05() && @@ -408,27 +401,12 @@ Chassis WeyController::chassis() { } else { chassis_.mutable_engage_advice()->set_advice( apollo::common::EngageAdvice::DISALLOW_ENGAGE); + chassis_.mutable_engage_advice()->set_reason( + "CANBUS not ready, epb is not released or firmware error!"); } - - // 19 add checkresponse signal - if (chassis_detail.has_fbs3_237() && - chassis_detail.fbs3_237().has_eps_streeingmode()) { - chassis_.mutable_check_response()->set_is_eps_online( - chassis_detail.fbs3_237().eps_streeingmode() == 1); - } - if (chassis_detail.has_status_310() && - chassis_detail.status_310().has_longitudedrivingmode()) { - chassis_.mutable_check_response()->set_is_esp_online( - chassis_detail.status_310().longitudedrivingmode() == 1); - chassis_.mutable_check_response()->set_is_vcu_online( - chassis_detail.status_310().longitudedrivingmode() == 1); - } - return chassis_; } -bool WeyController::VerifyID() { return true; } - void WeyController::Emergency() { set_driving_mode(Chassis::EMERGENCY_MODE); ResetProtocol(); @@ -457,8 +435,7 @@ ErrorCode WeyController::EnableAutoMode() { const int32_t flag = CHECK_RESPONSE_STEER_UNIT_FLAG | CHECK_RESPONSE_SPEED_UNIT_FLAG; if (!CheckResponse(flag, true)) { - AERROR << "Failed to switch to COMPLETE_AUTO_DRIVE mode. Please check the " - "emergency button or chassis."; + AERROR << "Failed to switch to COMPLETE_AUTO_DRIVE mode."; Emergency(); set_chassis_error_code(Chassis::CHASSIS_ERROR); return ErrorCode::CANBUS_ERROR; @@ -684,42 +661,42 @@ void WeyController::SetTurningSignal(const ControlCommand& command) { void WeyController::ResetProtocol() { message_manager_->ResetSendMessages(); } bool WeyController::CheckChassisError() { - Wey chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); - if (!chassis_detail.has_check_response()) { + if (!chassis_detail.has_wey()) { AERROR_EVERY(100) << "ChassisDetail has NO wey vehicle info." << chassis_detail.DebugString(); return false; } - + Wey wey = chassis_detail.wey(); // check steer error - if (chassis_detail.has_fail_241()) { - if (chassis_detail.fail_241().epsfail() == Fail_241::EPSFAIL_FAULT) { + if (wey.has_fail_241()) { + if (wey.fail_241().epsfail() == Fail_241::EPSFAIL_FAULT) { return true; } } // check ems error - if (chassis_detail.has_fail_241()) { - if (chassis_detail.fail_241().engfail() == Fail_241::ENGFAIL_FAIL) { + if (wey.has_fail_241()) { + if (wey.fail_241().engfail() == Fail_241::ENGFAIL_FAIL) { return true; } } // check braking error - if (chassis_detail.has_fail_241()) { - if (chassis_detail.fail_241().espfail() == Fail_241::ESPFAIL_FAILURE) { + if (wey.has_fail_241()) { + if (wey.fail_241().espfail() == Fail_241::ESPFAIL_FAILURE) { return true; } } // check gear error question - if (chassis_detail.has_fail_241()) { - if (chassis_detail.fail_241().shiftfail() == + if (wey.has_fail_241()) { + if (wey.fail_241().shiftfail() == Fail_241::SHIFTFAIL_TRANSMISSION_P_ENGAGEMENT_FAULT) { return true; } } // check parking error - if (chassis_detail.has_fail_241()) { - if (chassis_detail.fail_241().epbfail() == Fail_241::EPBFAIL_ERROR) { + if (wey.has_fail_241()) { + if (wey.fail_241().epbfail() == Fail_241::EPBFAIL_ERROR) { return true; } } @@ -793,7 +770,7 @@ void WeyController::SecurityDogThreadFunc() { } bool WeyController::CheckResponse(const int32_t flags, bool need_wait) { - Wey chassis_detail; + ChassisDetail chassis_detail; bool is_eps_online = false; bool is_vcu_online = false; bool is_esp_online = false; diff --git a/modules/canbus_vehicle/wey/wey_controller.h b/modules/canbus/vehicle/wey/wey_controller.h similarity index 88% rename from modules/canbus_vehicle/wey/wey_controller.h rename to modules/canbus/vehicle/wey/wey_controller.h index a6f1b0eeae2..9b2f081327d 100644 --- a/modules/canbus_vehicle/wey/wey_controller.h +++ b/modules/canbus/vehicle/wey/wey_controller.h @@ -19,24 +19,25 @@ #include #include +#include "modules/canbus/vehicle/vehicle_controller.h" + #include "modules/canbus/proto/canbus_conf.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" #include "modules/common_msgs/basic_msgs/error_code.pb.h" -#include "modules/common_msgs/chassis_msgs/chassis.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" -#include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/canbus_vehicle/wey/protocol/ads1_111.h" -#include "modules/canbus_vehicle/wey/protocol/ads3_38e.h" -#include "modules/canbus_vehicle/wey/protocol/ads_eps_113.h" -#include "modules/canbus_vehicle/wey/protocol/ads_req_vin_390.h" -#include "modules/canbus_vehicle/wey/protocol/ads_shifter_115.h" +#include "modules/canbus/vehicle/wey/protocol/ads1_111.h" +#include "modules/canbus/vehicle/wey/protocol/ads3_38e.h" +#include "modules/canbus/vehicle/wey/protocol/ads_eps_113.h" +#include "modules/canbus/vehicle/wey/protocol/ads_req_vin_390.h" +#include "modules/canbus/vehicle/wey/protocol/ads_shifter_115.h" namespace apollo { namespace canbus { namespace wey { -class WeyController final : public VehicleController<::apollo::canbus::Wey> { +class WeyController final : public VehicleController { public: WeyController() {} @@ -44,8 +45,9 @@ class WeyController final : public VehicleController<::apollo::canbus::Wey> { ::apollo::common::ErrorCode Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Wey>* const can_sender, - MessageManager<::apollo::canbus::Wey>* const message_manager) override; + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) + override; bool Start() override; @@ -103,7 +105,6 @@ class WeyController final : public VehicleController<::apollo::canbus::Wey> { void SetTurningSignal( const ::apollo::control::ControlCommand& command) override; - bool VerifyID() override; void ResetProtocol(); bool CheckChassisError(); diff --git a/modules/canbus_vehicle/wey/wey_controller_test.cc b/modules/canbus/vehicle/wey/wey_controller_test.cc similarity index 93% rename from modules/canbus_vehicle/wey/wey_controller_test.cc rename to modules/canbus/vehicle/wey/wey_controller_test.cc index 79e2b42bd3f..cbf203ba5a8 100644 --- a/modules/canbus_vehicle/wey/wey_controller_test.cc +++ b/modules/canbus/vehicle/wey/wey_controller_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/wey_controller.h" +#include "modules/canbus/vehicle/wey/wey_controller.h" #include @@ -23,8 +23,7 @@ #include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" -#include "modules/canbus_vehicle/wey/wey_message_manager.h" +#include "modules/canbus/vehicle/wey/wey_message_manager.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" #include "modules/drivers/canbus/can_comm/can_sender.h" @@ -46,7 +45,7 @@ class WeyControllerTest : public ::testing::Test { protected: WeyController controller_; - CanSender<::apollo::canbus::Wey> sender_; + CanSender<::apollo::canbus::ChassisDetail> sender_; CanbusConf canbus_conf_; VehicleParameter params_; WeyMessageManager msg_manager_; diff --git a/modules/canbus_vehicle/wey/wey_message_manager.cc b/modules/canbus/vehicle/wey/wey_message_manager.cc similarity index 62% rename from modules/canbus_vehicle/wey/wey_message_manager.cc rename to modules/canbus/vehicle/wey/wey_message_manager.cc index 534c46882a7..9b655ced14a 100644 --- a/modules/canbus_vehicle/wey/wey_message_manager.cc +++ b/modules/canbus/vehicle/wey/wey_message_manager.cc @@ -13,23 +13,23 @@ See the License for the specific language governing permissions and limitations under the License. ==============================================================================*/ -#include "modules/canbus_vehicle/wey/wey_message_manager.h" - -#include "modules/canbus_vehicle/wey/protocol/ads1_111.h" -#include "modules/canbus_vehicle/wey/protocol/ads3_38e.h" -#include "modules/canbus_vehicle/wey/protocol/ads_eps_113.h" -#include "modules/canbus_vehicle/wey/protocol/ads_req_vin_390.h" -#include "modules/canbus_vehicle/wey/protocol/ads_shifter_115.h" - -#include "modules/canbus_vehicle/wey/protocol/fail_241.h" -#include "modules/canbus_vehicle/wey/protocol/fbs1_243.h" -#include "modules/canbus_vehicle/wey/protocol/fbs2_240.h" -#include "modules/canbus_vehicle/wey/protocol/fbs3_237.h" -#include "modules/canbus_vehicle/wey/protocol/fbs4_235.h" -#include "modules/canbus_vehicle/wey/protocol/status_310.h" -#include "modules/canbus_vehicle/wey/protocol/vin_resp1_391.h" -#include "modules/canbus_vehicle/wey/protocol/vin_resp2_392.h" -#include "modules/canbus_vehicle/wey/protocol/vin_resp3_393.h" +#include "modules/canbus/vehicle/wey/wey_message_manager.h" + +#include "modules/canbus/vehicle/wey/protocol/ads1_111.h" +#include "modules/canbus/vehicle/wey/protocol/ads3_38e.h" +#include "modules/canbus/vehicle/wey/protocol/ads_eps_113.h" +#include "modules/canbus/vehicle/wey/protocol/ads_req_vin_390.h" +#include "modules/canbus/vehicle/wey/protocol/ads_shifter_115.h" + +#include "modules/canbus/vehicle/wey/protocol/fail_241.h" +#include "modules/canbus/vehicle/wey/protocol/fbs1_243.h" +#include "modules/canbus/vehicle/wey/protocol/fbs2_240.h" +#include "modules/canbus/vehicle/wey/protocol/fbs3_237.h" +#include "modules/canbus/vehicle/wey/protocol/fbs4_235.h" +#include "modules/canbus/vehicle/wey/protocol/status_310.h" +#include "modules/canbus/vehicle/wey/protocol/vin_resp1_391.h" +#include "modules/canbus/vehicle/wey/protocol/vin_resp2_392.h" +#include "modules/canbus/vehicle/wey/protocol/vin_resp3_393.h" namespace apollo { namespace canbus { diff --git a/modules/canbus_vehicle/wey/wey_message_manager.h b/modules/canbus/vehicle/wey/wey_message_manager.h similarity index 88% rename from modules/canbus_vehicle/wey/wey_message_manager.h rename to modules/canbus/vehicle/wey/wey_message_manager.h index 32ce4c68b96..46a05c2a413 100644 --- a/modules/canbus_vehicle/wey/wey_message_manager.h +++ b/modules/canbus/vehicle/wey/wey_message_manager.h @@ -15,7 +15,7 @@ limitations under the License. #pragma once -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/message_manager.h" namespace apollo { @@ -25,7 +25,7 @@ namespace wey { using ::apollo::drivers::canbus::MessageManager; class WeyMessageManager - : public MessageManager<::apollo::canbus::Wey> { + : public MessageManager<::apollo::canbus::ChassisDetail> { public: WeyMessageManager(); virtual ~WeyMessageManager(); diff --git a/modules/canbus_vehicle/wey/wey_message_manager_test.cc b/modules/canbus/vehicle/wey/wey_message_manager_test.cc similarity index 71% rename from modules/canbus_vehicle/wey/wey_message_manager_test.cc rename to modules/canbus/vehicle/wey/wey_message_manager_test.cc index 45f7bb9f7e2..8c57560d2cd 100644 --- a/modules/canbus_vehicle/wey/wey_message_manager_test.cc +++ b/modules/canbus/vehicle/wey/wey_message_manager_test.cc @@ -14,23 +14,23 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/wey_message_manager.h" +#include "modules/canbus/vehicle/wey/wey_message_manager.h" #include "gtest/gtest.h" -#include "modules/canbus_vehicle/wey/protocol/ads1_111.h" -#include "modules/canbus_vehicle/wey/protocol/ads3_38e.h" -#include "modules/canbus_vehicle/wey/protocol/ads_eps_113.h" -#include "modules/canbus_vehicle/wey/protocol/ads_req_vin_390.h" -#include "modules/canbus_vehicle/wey/protocol/ads_shifter_115.h" +#include "modules/canbus/vehicle/wey/protocol/ads1_111.h" +#include "modules/canbus/vehicle/wey/protocol/ads3_38e.h" +#include "modules/canbus/vehicle/wey/protocol/ads_eps_113.h" +#include "modules/canbus/vehicle/wey/protocol/ads_req_vin_390.h" +#include "modules/canbus/vehicle/wey/protocol/ads_shifter_115.h" -#include "modules/canbus_vehicle/wey/protocol/fail_241.h" -#include "modules/canbus_vehicle/wey/protocol/fbs1_243.h" -#include "modules/canbus_vehicle/wey/protocol/fbs2_240.h" -#include "modules/canbus_vehicle/wey/protocol/fbs3_237.h" -#include "modules/canbus_vehicle/wey/protocol/fbs4_235.h" -#include "modules/canbus_vehicle/wey/protocol/status_310.h" -#include "modules/canbus_vehicle/wey/protocol/vin_resp1_391.h" -#include "modules/canbus_vehicle/wey/protocol/vin_resp2_392.h" -#include "modules/canbus_vehicle/wey/protocol/vin_resp3_393.h" +#include "modules/canbus/vehicle/wey/protocol/fail_241.h" +#include "modules/canbus/vehicle/wey/protocol/fbs1_243.h" +#include "modules/canbus/vehicle/wey/protocol/fbs2_240.h" +#include "modules/canbus/vehicle/wey/protocol/fbs3_237.h" +#include "modules/canbus/vehicle/wey/protocol/fbs4_235.h" +#include "modules/canbus/vehicle/wey/protocol/status_310.h" +#include "modules/canbus/vehicle/wey/protocol/vin_resp1_391.h" +#include "modules/canbus/vehicle/wey/protocol/vin_resp2_392.h" +#include "modules/canbus/vehicle/wey/protocol/vin_resp3_393.h" namespace apollo { namespace canbus { diff --git a/modules/tools/gen_vehicle_protocol/template/message_manager.cc.tpl b/modules/canbus/vehicle/wey/wey_vehicle_factory.cc similarity index 59% rename from modules/tools/gen_vehicle_protocol/template/message_manager.cc.tpl rename to modules/canbus/vehicle/wey/wey_vehicle_factory.cc index 12f15b9c60e..5d03f717967 100644 --- a/modules/tools/gen_vehicle_protocol/template/message_manager.cc.tpl +++ b/modules/canbus/vehicle/wey/wey_vehicle_factory.cc @@ -14,26 +14,24 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus/vehicle/%(car_type_lower)s/%(car_type_lower)s_message_manager.h" - -%(control_header_list)s - -%(report_header_list)s +#include "modules/canbus/vehicle/wey/wey_vehicle_factory.h" +#include "modules/canbus/vehicle/wey/wey_controller.h" +#include "modules/canbus/vehicle/wey/wey_message_manager.h" +#include "modules/common/util/util.h" namespace apollo { namespace canbus { -namespace %(car_type_lower)s { -%(car_type_cap)sMessageManager::%(car_type_cap)sMessageManager() { - // Control Messages -%(control_add_list)s - - // Report Messages -%(report_add_list)s +std::unique_ptr +WeyVehicleFactory::CreateVehicleController() { + return std::unique_ptr(new wey::WeyController()); } -%(car_type_cap)sMessageManager::~%(car_type_cap)sMessageManager() {} +std::unique_ptr> +WeyVehicleFactory::CreateMessageManager() { + return std::unique_ptr>( + new wey::WeyMessageManager()); +} -} // namespace %(car_type_lower)s } // namespace canbus } // namespace apollo diff --git a/modules/canbus/vehicle/wey/wey_vehicle_factory.h b/modules/canbus/vehicle/wey/wey_vehicle_factory.h new file mode 100644 index 00000000000..f5412c0e4d8 --- /dev/null +++ b/modules/canbus/vehicle/wey/wey_vehicle_factory.h @@ -0,0 +1,65 @@ +/****************************************************************************** + * 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. + *****************************************************************************/ + +/** + * @file wey_vehicle_factory.h + */ + +#pragma once + +#include + +#include "modules/canbus/proto/vehicle_parameter.pb.h" +#include "modules/canbus/vehicle/abstract_vehicle_factory.h" +#include "modules/canbus/vehicle/vehicle_controller.h" +#include "modules/drivers/canbus/can_comm/message_manager.h" + +/** + * @namespace apollo::canbus + * @brief apollo::canbus + */ +namespace apollo { +namespace canbus { + +/** + * @class WeyVehicleFactory + * + * @brief this class is inherited from AbstractVehicleFactory. It can be used + * to create controller and message manager for wey vehicle. + */ +class WeyVehicleFactory : public AbstractVehicleFactory { + public: + /** + * @brief destructor + */ + virtual ~WeyVehicleFactory() = default; + + /** + * @brief create wey vehicle controller + * @returns a unique_ptr that points to the created controller + */ + std::unique_ptr CreateVehicleController() override; + + /** + * @brief create wey message manager + * @returns a unique_ptr that points to the created message manager + */ + std::unique_ptr> + CreateMessageManager() override; +}; + +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/wey/wey_vehicle_factory_test.cc b/modules/canbus/vehicle/wey/wey_vehicle_factory_test.cc similarity index 62% rename from modules/canbus_vehicle/wey/wey_vehicle_factory_test.cc rename to modules/canbus/vehicle/wey/wey_vehicle_factory_test.cc index 95477ce479f..06d6d5dc14a 100644 --- a/modules/canbus_vehicle/wey/wey_vehicle_factory_test.cc +++ b/modules/canbus/vehicle/wey/wey_vehicle_factory_test.cc @@ -14,40 +14,32 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/wey/wey_vehicle_factory.h" - +#include "modules/canbus/vehicle/wey/wey_vehicle_factory.h" #include "gtest/gtest.h" - -#include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "cyber/common/file.h" - namespace apollo { namespace canbus { class WeyVehicleFactoryTest : public ::testing::Test { public: virtual void SetUp() { - std::string canbus_conf_file = - "/apollo/modules/canbus_vehicle/wey/testdata/" - "wey_canbus_conf_test.pb.txt"; - cyber::common::GetProtoFromFile(canbus_conf_file, &canbus_conf_); - params_ = canbus_conf_.vehicle_parameter(); - params_.set_brand(apollo::common::WEY); - wey_factory_.SetVehicleParameter(params_); + VehicleParameter parameter; + parameter.set_brand(apollo::common::WEY); + wey_factory_.SetVehicleParameter(parameter); } virtual void TearDown() {} protected: WeyVehicleFactory wey_factory_; - CanbusConf canbus_conf_; - VehicleParameter params_; }; -TEST_F(WeyVehicleFactoryTest, Init) { - apollo::cyber::Init("vehicle_factory_test"); - EXPECT_EQ(wey_factory_.Init(&canbus_conf_), true); +TEST_F(WeyVehicleFactoryTest, InitVehicleController) { + EXPECT_NE(wey_factory_.CreateVehicleController(), nullptr); +} + +TEST_F(WeyVehicleFactoryTest, InitMessageManager) { + EXPECT_NE(wey_factory_.CreateMessageManager(), nullptr); } } // namespace canbus diff --git a/modules/canbus/vehicle/zhongyun/BUILD b/modules/canbus/vehicle/zhongyun/BUILD new file mode 100644 index 00000000000..d9c5907809f --- /dev/null +++ b/modules/canbus/vehicle/zhongyun/BUILD @@ -0,0 +1,78 @@ +load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") +load("//tools:cpplint.bzl", "cpplint") + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "zhongyun_vehicle_factory", + srcs = ["zhongyun_vehicle_factory.cc"], + hdrs = ["zhongyun_vehicle_factory.h"], + deps = [ + ":zhongyun_controller", + ":zhongyun_message_manager", + "//modules/canbus/vehicle:abstract_vehicle_factory", + ], +) + +cc_library( + name = "zhongyun_message_manager", + srcs = ["zhongyun_message_manager.cc"], + hdrs = ["zhongyun_message_manager.h"], + deps = [ + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle/zhongyun/protocol:canbus_zhongyun_protocol", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_library( + name = "zhongyun_controller", + srcs = ["zhongyun_controller.cc"], + hdrs = ["zhongyun_controller.h"], + deps = [ + ":zhongyun_message_manager", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", + "//modules/canbus/vehicle:vehicle_controller_base", + "//modules/canbus/vehicle/zhongyun/protocol:canbus_zhongyun_protocol", + "//modules/drivers/canbus/can_comm:can_sender", + "//modules/drivers/canbus/can_comm:message_manager_base", + "//modules/drivers/canbus/common:canbus_common", + ], +) + +cc_test( + name = "zhongyun_message_manager_test", + size = "small", + srcs = ["zhongyun_message_manager_test.cc"], + data = ["//modules/canbus:test_data"], + deps = [ + ":zhongyun_message_manager", + "@com_google_googletest//:gtest_main", + ], +) + +cc_test( + name = "zhongyun_vehicle_factory_test", + size = "small", + srcs = ["zhongyun_vehicle_factory_test.cc"], + data = ["//modules/canbus:test_data"], + deps = [ + ":zhongyun_vehicle_factory", + "@com_google_googletest//:gtest_main", + ], +) + +cc_test( + name = "zhongyun_controller_test", + size = "small", + srcs = ["zhongyun_controller_test.cc"], + data = ["//modules/canbus:test_data"], + deps = [ + ":zhongyun_controller", + "//modules/common/util", + "@com_google_googletest//:gtest_main", + ], +) + +cpplint() diff --git a/modules/canbus_vehicle/zhongyun/protocol/BUILD b/modules/canbus/vehicle/zhongyun/protocol/BUILD similarity index 88% rename from modules/canbus_vehicle/zhongyun/protocol/BUILD rename to modules/canbus/vehicle/zhongyun/protocol/BUILD index 28560e61845..50ef51ca4be 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/BUILD +++ b/modules/canbus/vehicle/zhongyun/protocol/BUILD @@ -26,7 +26,7 @@ cc_library( hdrs = ["brake_control_a4.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/zhongyun/proto:zhongyun_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -48,7 +48,7 @@ cc_library( hdrs = ["enable_state_feedback_c3.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/zhongyun/proto:zhongyun_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -62,7 +62,6 @@ cc_test( ":canbus_zhongyun_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_library( @@ -71,7 +70,7 @@ cc_library( hdrs = ["error_state_e1.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/zhongyun/proto:zhongyun_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -93,7 +92,7 @@ cc_library( hdrs = ["gear_control_a1.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/zhongyun/proto:zhongyun_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -115,7 +114,7 @@ cc_library( hdrs = ["parking_control_a5.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/zhongyun/proto:zhongyun_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -137,7 +136,7 @@ cc_library( hdrs = ["steering_control_a2.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/zhongyun/proto:zhongyun_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -159,7 +158,7 @@ cc_library( hdrs = ["torque_control_a3.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/zhongyun/proto:zhongyun_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -181,7 +180,7 @@ cc_library( hdrs = ["vehicle_state_feedback_2_c4.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/zhongyun/proto:zhongyun_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -195,7 +194,6 @@ cc_test( ":canbus_zhongyun_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cc_library( @@ -204,7 +202,7 @@ cc_library( hdrs = ["vehicle_state_feedback_c1.h"], copts = CANBUS_COPTS, deps = [ - "//modules/canbus_vehicle/zhongyun/proto:zhongyun_cc_proto", + "//modules/common_msgs/chassis_msgs:chassis_detail_cc_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "//modules/drivers/canbus/common:canbus_common", ], @@ -218,7 +216,6 @@ cc_test( ":canbus_zhongyun_protocol", "@com_google_googletest//:gtest_main", ], - linkstatic = True, ) cpplint() diff --git a/modules/canbus_vehicle/zhongyun/protocol/brake_control_a4.cc b/modules/canbus/vehicle/zhongyun/protocol/brake_control_a4.cc similarity index 97% rename from modules/canbus_vehicle/zhongyun/protocol/brake_control_a4.cc rename to modules/canbus/vehicle/zhongyun/protocol/brake_control_a4.cc index fbf624624ce..e909d44e490 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/brake_control_a4.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/brake_control_a4.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/brake_control_a4.h" +#include "modules/canbus/vehicle/zhongyun/protocol/brake_control_a4.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/zhongyun/protocol/brake_control_a4.h b/modules/canbus/vehicle/zhongyun/protocol/brake_control_a4.h similarity index 95% rename from modules/canbus_vehicle/zhongyun/protocol/brake_control_a4.h rename to modules/canbus/vehicle/zhongyun/protocol/brake_control_a4.h index 4e51db54b3a..f07a7cfbbd1 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/brake_control_a4.h +++ b/modules/canbus/vehicle/zhongyun/protocol/brake_control_a4.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/zhongyun/proto/zhongyun.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace zhongyun { class Brakecontrola4 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Zhongyun> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/zhongyun/protocol/brake_control_a4_test.cc b/modules/canbus/vehicle/zhongyun/protocol/brake_control_a4_test.cc similarity index 95% rename from modules/canbus_vehicle/zhongyun/protocol/brake_control_a4_test.cc rename to modules/canbus/vehicle/zhongyun/protocol/brake_control_a4_test.cc index 76ab7338585..3a3d8b4e6a1 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/brake_control_a4_test.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/brake_control_a4_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/brake_control_a4.h" +#include "modules/canbus/vehicle/zhongyun/protocol/brake_control_a4.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/zhongyun/protocol/enable_state_feedback_c3.cc b/modules/canbus/vehicle/zhongyun/protocol/enable_state_feedback_c3.cc similarity index 86% rename from modules/canbus_vehicle/zhongyun/protocol/enable_state_feedback_c3.cc rename to modules/canbus/vehicle/zhongyun/protocol/enable_state_feedback_c3.cc index 2d6efd1f7ab..b07b8f8bb1f 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/enable_state_feedback_c3.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/enable_state_feedback_c3.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/enable_state_feedback_c3.h" +#include "modules/canbus/vehicle/zhongyun/protocol/enable_state_feedback_c3.h" #include "glog/logging.h" @@ -31,17 +31,22 @@ Enablestatefeedbackc3::Enablestatefeedbackc3() {} const int32_t Enablestatefeedbackc3::ID = 0xC3; void Enablestatefeedbackc3::Parse(const std::uint8_t* bytes, int32_t length, - Zhongyun* chassis) const { - chassis->mutable_enable_state_feedback_c3()->set_parking_enable_state( - parking_enable_state(bytes, length)); - chassis->mutable_enable_state_feedback_c3()->set_steering_enable_state( - steering_enable_state(bytes, length)); - chassis->mutable_enable_state_feedback_c3()->set_gear_enable_actual( - gear_enable_actual(bytes, length)); - chassis->mutable_enable_state_feedback_c3()->set_driven_enable_state( - driven_enable_state(bytes, length)); - chassis->mutable_enable_state_feedback_c3()->set_brake_enable_state( - brake_enable_state(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_zhongyun() + ->mutable_enable_state_feedback_c3() + ->set_parking_enable_state(parking_enable_state(bytes, length)); + chassis->mutable_zhongyun() + ->mutable_enable_state_feedback_c3() + ->set_steering_enable_state(steering_enable_state(bytes, length)); + chassis->mutable_zhongyun() + ->mutable_enable_state_feedback_c3() + ->set_gear_enable_actual(gear_enable_actual(bytes, length)); + chassis->mutable_zhongyun() + ->mutable_enable_state_feedback_c3() + ->set_driven_enable_state(driven_enable_state(bytes, length)); + chassis->mutable_zhongyun() + ->mutable_enable_state_feedback_c3() + ->set_brake_enable_state(brake_enable_state(bytes, length)); // Added for response check chassis->mutable_check_response()->set_is_esp_online( brake_enable_state(bytes, length) == 1); diff --git a/modules/canbus_vehicle/zhongyun/protocol/enable_state_feedback_c3.h b/modules/canbus/vehicle/zhongyun/protocol/enable_state_feedback_c3.h similarity index 95% rename from modules/canbus_vehicle/zhongyun/protocol/enable_state_feedback_c3.h rename to modules/canbus/vehicle/zhongyun/protocol/enable_state_feedback_c3.h index b982024c472..e937b6eb59e 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/enable_state_feedback_c3.h +++ b/modules/canbus/vehicle/zhongyun/protocol/enable_state_feedback_c3.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/zhongyun/proto/zhongyun.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace zhongyun { class Enablestatefeedbackc3 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Zhongyun> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Enablestatefeedbackc3(); void Parse(const std::uint8_t* bytes, int32_t length, - Zhongyun* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'Parking_enable_state', 'enum': {0: diff --git a/modules/canbus_vehicle/zhongyun/protocol/enable_state_feedback_c3_test.cc b/modules/canbus/vehicle/zhongyun/protocol/enable_state_feedback_c3_test.cc similarity index 91% rename from modules/canbus_vehicle/zhongyun/protocol/enable_state_feedback_c3_test.cc rename to modules/canbus/vehicle/zhongyun/protocol/enable_state_feedback_c3_test.cc index 4c100dc3baa..297ef039817 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/enable_state_feedback_c3_test.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/enable_state_feedback_c3_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/enable_state_feedback_c3.h" +#include "modules/canbus/vehicle/zhongyun/protocol/enable_state_feedback_c3.h" #include "gtest/gtest.h" namespace apollo { @@ -29,11 +29,11 @@ class Enablestatefeedbackc3Test : public ::testing::Test { TEST_F(Enablestatefeedbackc3Test, reset) { Enablestatefeedbackc3 feedback_; int32_t length = 8; - Zhongyun cd; + ChassisDetail cd; uint8_t bytes[8] = {0x01, 0x02, 0x01, 0x02, 0x01, 0x12, 0x13, 0x14}; feedback_.Parse(bytes, length, &cd); - auto &feedbackinfo = cd.enable_state_feedback_c3(); + auto &feedbackinfo = cd.zhongyun().enable_state_feedback_c3(); EXPECT_DOUBLE_EQ(feedbackinfo.parking_enable_state(), 1); EXPECT_DOUBLE_EQ(feedbackinfo.steering_enable_state(), 2); EXPECT_DOUBLE_EQ(feedbackinfo.gear_enable_actual(), 1); diff --git a/modules/canbus_vehicle/zhongyun/protocol/error_state_e1.cc b/modules/canbus/vehicle/zhongyun/protocol/error_state_e1.cc similarity index 88% rename from modules/canbus_vehicle/zhongyun/protocol/error_state_e1.cc rename to modules/canbus/vehicle/zhongyun/protocol/error_state_e1.cc index c281bf7b6d4..05262daeb24 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/error_state_e1.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/error_state_e1.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/error_state_e1.h" +#include "modules/canbus/vehicle/zhongyun/protocol/error_state_e1.h" #include "glog/logging.h" @@ -31,16 +31,17 @@ Errorstatee1::Errorstatee1() {} const int32_t Errorstatee1::ID = 0xE1; void Errorstatee1::Parse(const std::uint8_t* bytes, int32_t length, - Zhongyun* chassis) const { - chassis->mutable_error_state_e1()->set_brake_error_code( + ChassisDetail* chassis) const { + chassis->mutable_zhongyun()->mutable_error_state_e1()->set_brake_error_code( brake_error_code(bytes, length)); - chassis->mutable_error_state_e1()->set_driven_error_code( + chassis->mutable_zhongyun()->mutable_error_state_e1()->set_driven_error_code( driven_error_code(bytes, length)); - chassis->mutable_error_state_e1()->set_steering_error_code( - steering_error_code(bytes, length)); - chassis->mutable_error_state_e1()->set_parking_error_code( + chassis->mutable_zhongyun() + ->mutable_error_state_e1() + ->set_steering_error_code(steering_error_code(bytes, length)); + chassis->mutable_zhongyun()->mutable_error_state_e1()->set_parking_error_code( parking_error_code(bytes, length)); - chassis->mutable_error_state_e1()->set_gear_error_msg( + chassis->mutable_zhongyun()->mutable_error_state_e1()->set_gear_error_msg( gear_error_msg(bytes, length)); } diff --git a/modules/canbus_vehicle/zhongyun/protocol/error_state_e1.h b/modules/canbus/vehicle/zhongyun/protocol/error_state_e1.h similarity index 94% rename from modules/canbus_vehicle/zhongyun/protocol/error_state_e1.h rename to modules/canbus/vehicle/zhongyun/protocol/error_state_e1.h index d137f63661e..e39e64e8c9e 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/error_state_e1.h +++ b/modules/canbus/vehicle/zhongyun/protocol/error_state_e1.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/zhongyun/proto/zhongyun.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace zhongyun { class Errorstatee1 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Zhongyun> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Errorstatee1(); void Parse(const std::uint8_t* bytes, int32_t length, - Zhongyun* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'brake_error_code', 'enum': {0: diff --git a/modules/canbus_vehicle/zhongyun/protocol/error_state_e1_test.cc b/modules/canbus/vehicle/zhongyun/protocol/error_state_e1_test.cc similarity index 91% rename from modules/canbus_vehicle/zhongyun/protocol/error_state_e1_test.cc rename to modules/canbus/vehicle/zhongyun/protocol/error_state_e1_test.cc index 0dcae9b2207..c5ebba50bd7 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/error_state_e1_test.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/error_state_e1_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/error_state_e1.h" +#include "modules/canbus/vehicle/zhongyun/protocol/error_state_e1.h" #include "gtest/gtest.h" namespace apollo { @@ -29,11 +29,11 @@ class Errorstatee1Test : public ::testing::Test { TEST_F(Errorstatee1Test, reset) { Errorstatee1 error_state_; int32_t length = 8; - Zhongyun cd; + ChassisDetail cd; uint8_t bytes[8] = {0x01, 0x01, 0x01, 0x01, 0x01, 0x12, 0x13, 0x14}; error_state_.Parse(bytes, length, &cd); - auto &error_state_info = cd.error_state_e1(); + auto &error_state_info = cd.zhongyun().error_state_e1(); EXPECT_DOUBLE_EQ(error_state_info.brake_error_code(), 1); EXPECT_DOUBLE_EQ(error_state_info.driven_error_code(), 1); EXPECT_DOUBLE_EQ(error_state_info.steering_error_code(), 1); diff --git a/modules/canbus_vehicle/zhongyun/protocol/gear_control_a1.cc b/modules/canbus/vehicle/zhongyun/protocol/gear_control_a1.cc similarity index 98% rename from modules/canbus_vehicle/zhongyun/protocol/gear_control_a1.cc rename to modules/canbus/vehicle/zhongyun/protocol/gear_control_a1.cc index 5d9bf8842ee..a3e5d5346fc 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/gear_control_a1.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/gear_control_a1.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/gear_control_a1.h" +#include "modules/canbus/vehicle/zhongyun/protocol/gear_control_a1.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/zhongyun/protocol/gear_control_a1.h b/modules/canbus/vehicle/zhongyun/protocol/gear_control_a1.h similarity index 96% rename from modules/canbus_vehicle/zhongyun/protocol/gear_control_a1.h rename to modules/canbus/vehicle/zhongyun/protocol/gear_control_a1.h index fad3c1b2659..22af504d8ad 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/gear_control_a1.h +++ b/modules/canbus/vehicle/zhongyun/protocol/gear_control_a1.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/zhongyun/proto/zhongyun.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace zhongyun { class Gearcontrola1 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Zhongyun> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/zhongyun/protocol/gear_control_a1_test.cc b/modules/canbus/vehicle/zhongyun/protocol/gear_control_a1_test.cc similarity index 95% rename from modules/canbus_vehicle/zhongyun/protocol/gear_control_a1_test.cc rename to modules/canbus/vehicle/zhongyun/protocol/gear_control_a1_test.cc index 62167a8d2b2..231a98a94d0 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/gear_control_a1_test.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/gear_control_a1_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/gear_control_a1.h" +#include "modules/canbus/vehicle/zhongyun/protocol/gear_control_a1.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/zhongyun/protocol/parking_control_a5.cc b/modules/canbus/vehicle/zhongyun/protocol/parking_control_a5.cc similarity index 98% rename from modules/canbus_vehicle/zhongyun/protocol/parking_control_a5.cc rename to modules/canbus/vehicle/zhongyun/protocol/parking_control_a5.cc index d59b103b92b..b0680ce110d 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/parking_control_a5.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/parking_control_a5.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/parking_control_a5.h" +#include "modules/canbus/vehicle/zhongyun/protocol/parking_control_a5.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/zhongyun/protocol/parking_control_a5.h b/modules/canbus/vehicle/zhongyun/protocol/parking_control_a5.h similarity index 96% rename from modules/canbus_vehicle/zhongyun/protocol/parking_control_a5.h rename to modules/canbus/vehicle/zhongyun/protocol/parking_control_a5.h index 9229993b3d4..dd4856ac375 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/parking_control_a5.h +++ b/modules/canbus/vehicle/zhongyun/protocol/parking_control_a5.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/zhongyun/proto/zhongyun.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace zhongyun { class Parkingcontrola5 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Zhongyun> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/zhongyun/protocol/parking_control_a5_test.cc b/modules/canbus/vehicle/zhongyun/protocol/parking_control_a5_test.cc similarity index 95% rename from modules/canbus_vehicle/zhongyun/protocol/parking_control_a5_test.cc rename to modules/canbus/vehicle/zhongyun/protocol/parking_control_a5_test.cc index b5c2751cb9a..35d88e2520f 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/parking_control_a5_test.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/parking_control_a5_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/parking_control_a5.h" +#include "modules/canbus/vehicle/zhongyun/protocol/parking_control_a5.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/zhongyun/protocol/steering_control_a2.cc b/modules/canbus/vehicle/zhongyun/protocol/steering_control_a2.cc similarity index 98% rename from modules/canbus_vehicle/zhongyun/protocol/steering_control_a2.cc rename to modules/canbus/vehicle/zhongyun/protocol/steering_control_a2.cc index fd3311c0af6..cb904e8bd85 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/steering_control_a2.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/steering_control_a2.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/steering_control_a2.h" +#include "modules/canbus/vehicle/zhongyun/protocol/steering_control_a2.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/zhongyun/protocol/steering_control_a2.h b/modules/canbus/vehicle/zhongyun/protocol/steering_control_a2.h similarity index 95% rename from modules/canbus_vehicle/zhongyun/protocol/steering_control_a2.h rename to modules/canbus/vehicle/zhongyun/protocol/steering_control_a2.h index 3616e648b56..97296e5909f 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/steering_control_a2.h +++ b/modules/canbus/vehicle/zhongyun/protocol/steering_control_a2.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/zhongyun/proto/zhongyun.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace zhongyun { class Steeringcontrola2 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Zhongyun> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/zhongyun/protocol/steering_control_a2_test.cc b/modules/canbus/vehicle/zhongyun/protocol/steering_control_a2_test.cc similarity index 95% rename from modules/canbus_vehicle/zhongyun/protocol/steering_control_a2_test.cc rename to modules/canbus/vehicle/zhongyun/protocol/steering_control_a2_test.cc index 4720d12f658..43a0f26d6fc 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/steering_control_a2_test.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/steering_control_a2_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/steering_control_a2.h" +#include "modules/canbus/vehicle/zhongyun/protocol/steering_control_a2.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/zhongyun/protocol/torque_control_a3.cc b/modules/canbus/vehicle/zhongyun/protocol/torque_control_a3.cc similarity index 98% rename from modules/canbus_vehicle/zhongyun/protocol/torque_control_a3.cc rename to modules/canbus/vehicle/zhongyun/protocol/torque_control_a3.cc index 9dfb59c021c..e07b5d0bd3a 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/torque_control_a3.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/torque_control_a3.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/torque_control_a3.h" +#include "modules/canbus/vehicle/zhongyun/protocol/torque_control_a3.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/canbus_vehicle/zhongyun/protocol/torque_control_a3.h b/modules/canbus/vehicle/zhongyun/protocol/torque_control_a3.h similarity index 95% rename from modules/canbus_vehicle/zhongyun/protocol/torque_control_a3.h rename to modules/canbus/vehicle/zhongyun/protocol/torque_control_a3.h index 3427df6cf20..0c6f9db91ef 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/torque_control_a3.h +++ b/modules/canbus/vehicle/zhongyun/protocol/torque_control_a3.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/zhongyun/proto/zhongyun.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,7 +24,7 @@ namespace canbus { namespace zhongyun { class Torquecontrola3 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Zhongyun> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; diff --git a/modules/canbus_vehicle/zhongyun/protocol/torque_control_a3_test.cc b/modules/canbus/vehicle/zhongyun/protocol/torque_control_a3_test.cc similarity index 95% rename from modules/canbus_vehicle/zhongyun/protocol/torque_control_a3_test.cc rename to modules/canbus/vehicle/zhongyun/protocol/torque_control_a3_test.cc index 04f16548e89..4f11c4e7d62 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/torque_control_a3_test.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/torque_control_a3_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/torque_control_a3.h" +#include "modules/canbus/vehicle/zhongyun/protocol/torque_control_a3.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.cc b/modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.cc similarity index 85% rename from modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.cc rename to modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.cc index a35d2c0d96c..8e2d3b53b0e 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.h" +#include "modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.h" #include "glog/logging.h" @@ -31,11 +31,13 @@ Vehiclestatefeedback2c4::Vehiclestatefeedback2c4() {} const int32_t Vehiclestatefeedback2c4::ID = 0xC4; void Vehiclestatefeedback2c4::Parse(const std::uint8_t* bytes, int32_t length, - Zhongyun* chassis) const { - chassis->mutable_vehicle_state_feedback_2_c4()->set_motor_speed( - motor_speed(bytes, length)); - chassis->mutable_vehicle_state_feedback_2_c4()->set_driven_torque_feedback( - driven_torque_feedback(bytes, length)); + ChassisDetail* chassis) const { + chassis->mutable_zhongyun() + ->mutable_vehicle_state_feedback_2_c4() + ->set_motor_speed(motor_speed(bytes, length)); + chassis->mutable_zhongyun() + ->mutable_vehicle_state_feedback_2_c4() + ->set_driven_torque_feedback(driven_torque_feedback(bytes, length)); } // config detail: {'name': 'motor_speed', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.h b/modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.h similarity index 90% rename from modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.h rename to modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.h index e0cbddd3bf5..1943ac0d909 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.h +++ b/modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/zhongyun/proto/zhongyun.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace zhongyun { class Vehiclestatefeedback2c4 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Zhongyun> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vehiclestatefeedback2c4(); void Parse(const std::uint8_t* bytes, int32_t length, - Zhongyun* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'motor_speed', 'offset': 0.0, 'precision': 1.0, diff --git a/modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4_test.cc b/modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4_test.cc similarity index 90% rename from modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4_test.cc rename to modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4_test.cc index 1d0bcc7902a..7f67da00507 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4_test.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.h" +#include "modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.h" #include "gtest/gtest.h" namespace apollo { @@ -29,11 +29,11 @@ class Vehiclestatefeedback2c4Test : public ::testing::Test { TEST_F(Vehiclestatefeedback2c4Test, reset) { Vehiclestatefeedback2c4 feedback_; int32_t length = 8; - Zhongyun cd; + ChassisDetail cd; uint8_t bytes[8] = {0x88, 0x44, 0x22, 0x11, 0x11, 0x12, 0x13, 0x14}; feedback_.Parse(bytes, length, &cd); - auto &feedbackinfo = cd.vehicle_state_feedback_2_c4(); + auto &feedbackinfo = cd.zhongyun().vehicle_state_feedback_2_c4(); EXPECT_DOUBLE_EQ(feedbackinfo.motor_speed(), 17544); EXPECT_DOUBLE_EQ(feedbackinfo.driven_torque_feedback(), 219.3); } diff --git a/modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_c1.cc b/modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_c1.cc similarity index 85% rename from modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_c1.cc rename to modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_c1.cc index c274b6a15e5..ec50544ecf9 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_c1.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_c1.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_c1.h" +#include "modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_c1.h" #include "glog/logging.h" @@ -31,16 +31,20 @@ Vehiclestatefeedbackc1::Vehiclestatefeedbackc1() {} const int32_t Vehiclestatefeedbackc1::ID = 0xC1; void Vehiclestatefeedbackc1::Parse(const std::uint8_t* bytes, int32_t length, - Zhongyun* chassis) const { - chassis->mutable_vehicle_state_feedback_c1()->set_parking_actual( - parking_actual(bytes, length)); - chassis->mutable_vehicle_state_feedback_c1()->set_brake_torque_feedback( - brake_torque_feedback(bytes, length)); - chassis->mutable_vehicle_state_feedback_c1()->set_gear_state_actual( - gear_state_actual(bytes, length)); - chassis->mutable_vehicle_state_feedback_c1()->set_steering_actual( - steering_actual(bytes, length)); - chassis->mutable_vehicle_state_feedback_c1()->set_speed( + ChassisDetail* chassis) const { + chassis->mutable_zhongyun() + ->mutable_vehicle_state_feedback_c1() + ->set_parking_actual(parking_actual(bytes, length)); + chassis->mutable_zhongyun() + ->mutable_vehicle_state_feedback_c1() + ->set_brake_torque_feedback(brake_torque_feedback(bytes, length)); + chassis->mutable_zhongyun() + ->mutable_vehicle_state_feedback_c1() + ->set_gear_state_actual(gear_state_actual(bytes, length)); + chassis->mutable_zhongyun() + ->mutable_vehicle_state_feedback_c1() + ->set_steering_actual(steering_actual(bytes, length)); + chassis->mutable_zhongyun()->mutable_vehicle_state_feedback_c1()->set_speed( speed(bytes, length) / 3.6); } diff --git a/modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_c1.h b/modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_c1.h similarity index 94% rename from modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_c1.h rename to modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_c1.h index 7db41acb3d7..f13e25f586f 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_c1.h +++ b/modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_c1.h @@ -16,7 +16,7 @@ #pragma once -#include "modules/canbus_vehicle/zhongyun/proto/zhongyun.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" namespace apollo { @@ -24,12 +24,12 @@ namespace canbus { namespace zhongyun { class Vehiclestatefeedbackc1 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Zhongyun> { + ::apollo::canbus::ChassisDetail> { public: static const int32_t ID; Vehiclestatefeedbackc1(); void Parse(const std::uint8_t* bytes, int32_t length, - Zhongyun* chassis) const override; + ChassisDetail* chassis) const override; private: // config detail: {'name': 'Parking_actual', 'enum': {0: diff --git a/modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_c1_test.cc b/modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_c1_test.cc similarity index 91% rename from modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_c1_test.cc rename to modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_c1_test.cc index eaa0c029c97..0da61640fe9 100644 --- a/modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_c1_test.cc +++ b/modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_c1_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_c1.h" +#include "modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_c1.h" #include "gtest/gtest.h" namespace apollo { @@ -29,12 +29,12 @@ class Vehiclestatefeedbackc1Test : public ::testing::Test { TEST_F(Vehiclestatefeedbackc1Test, reset) { Vehiclestatefeedbackc1 feedback_; int32_t length = 8; - Zhongyun cd; + ChassisDetail cd; uint8_t bytes[8] = {0x88, 0x44, 0x22, 0x11, 0x03, 0x12, 0x13, 0x01}; feedback_.Parse(bytes, length, &cd); - auto &feedbackinfo = cd.vehicle_state_feedback_c1(); + auto &feedbackinfo = cd.zhongyun().vehicle_state_feedback_c1(); EXPECT_DOUBLE_EQ(feedbackinfo.parking_actual(), 1); EXPECT_DOUBLE_EQ(feedbackinfo.brake_torque_feedback(), 244.1); EXPECT_DOUBLE_EQ(feedbackinfo.gear_state_actual(), 3); diff --git a/modules/canbus_vehicle/zhongyun/zhongyun_controller.cc b/modules/canbus/vehicle/zhongyun/zhongyun_controller.cc similarity index 83% rename from modules/canbus_vehicle/zhongyun/zhongyun_controller.cc rename to modules/canbus/vehicle/zhongyun/zhongyun_controller.cc index a23727a47d4..8c5c47ce802 100644 --- a/modules/canbus_vehicle/zhongyun/zhongyun_controller.cc +++ b/modules/canbus/vehicle/zhongyun/zhongyun_controller.cc @@ -13,14 +13,14 @@ See the License for the specific language governing permissions and limitations under the License. ==============================================================================*/ -#include "modules/canbus_vehicle/zhongyun/zhongyun_controller.h" +#include "modules/canbus/vehicle/zhongyun/zhongyun_controller.h" #include "modules/common_msgs/basic_msgs/vehicle_signal.pb.h" #include "cyber/common/log.h" #include "cyber/time/time.h" #include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/canbus_vehicle/zhongyun/zhongyun_message_manager.h" +#include "modules/canbus/vehicle/zhongyun/zhongyun_message_manager.h" #include "modules/drivers/canbus/can_comm/can_sender.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" @@ -41,8 +41,8 @@ const int32_t CHECK_RESPONSE_SPEED_UNIT_FLAG = 2; ErrorCode ZhongyunController::Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Zhongyun>* const can_sender, - MessageManager<::apollo::canbus::Zhongyun>* const message_manager) { + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) { if (is_initialized_) { AINFO << "ZhongyunController has already been initialized."; return ErrorCode::CANBUS_ERROR; @@ -145,33 +145,39 @@ void ZhongyunController::Stop() { Chassis ZhongyunController::chassis() { chassis_.Clear(); - Zhongyun chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); // 1, 2 - // if (driving_mode() == Chassis::EMERGENCY_MODE) { - // set_chassis_error_code(Chassis::NO_ERROR); - // } + if (driving_mode() == Chassis::EMERGENCY_MODE) { + set_chassis_error_code(Chassis::NO_ERROR); + } chassis_.set_driving_mode(driving_mode()); chassis_.set_error_code(chassis_error_code()); // 3 chassis_.set_engine_started(true); + // if there is not zhongyun, no chassis detail can be retrieved and return + if (!chassis_detail.has_zhongyun()) { + AERROR << "NO ZHONGYUN chassis information!"; + return chassis_; + } + Zhongyun zhy = chassis_detail.zhongyun(); // 4 engine_rpm - if (chassis_detail.has_vehicle_state_feedback_2_c4() && - chassis_detail.vehicle_state_feedback_2_c4().has_motor_speed()) { - chassis_.set_engine_rpm(static_cast( - chassis_detail.vehicle_state_feedback_2_c4().motor_speed())); + if (zhy.has_vehicle_state_feedback_2_c4() && + zhy.vehicle_state_feedback_2_c4().has_motor_speed()) { + chassis_.set_engine_rpm( + static_cast(zhy.vehicle_state_feedback_2_c4().motor_speed())); } else { chassis_.set_engine_rpm(0); } // 5 speed_mps - if (chassis_detail.has_vehicle_state_feedback_c1() && - chassis_detail.vehicle_state_feedback_c1().has_speed()) { + if (zhy.has_vehicle_state_feedback_c1() && + zhy.vehicle_state_feedback_c1().has_speed()) { chassis_.set_speed_mps( - static_cast(chassis_detail.vehicle_state_feedback_c1().speed())); + static_cast(zhy.vehicle_state_feedback_c1().speed())); } else { chassis_.set_speed_mps(0); } @@ -179,26 +185,25 @@ Chassis ZhongyunController::chassis() { chassis_.set_fuel_range_m(0); // 7 acc_pedal - if (chassis_detail.has_vehicle_state_feedback_2_c4() && - chassis_detail.vehicle_state_feedback_2_c4() - .has_driven_torque_feedback()) { + if (zhy.has_vehicle_state_feedback_2_c4() && + zhy.vehicle_state_feedback_2_c4().has_driven_torque_feedback()) { chassis_.set_throttle_percentage(static_cast( - chassis_detail.vehicle_state_feedback_2_c4().driven_torque_feedback())); + zhy.vehicle_state_feedback_2_c4().driven_torque_feedback())); } else { chassis_.set_throttle_percentage(0); } // 8 brake_pedal - if (chassis_detail.has_vehicle_state_feedback_c1() && - chassis_detail.vehicle_state_feedback_c1().has_brake_torque_feedback()) { + if (zhy.has_vehicle_state_feedback_c1() && + zhy.vehicle_state_feedback_c1().has_brake_torque_feedback()) { chassis_.set_brake_percentage(static_cast( - chassis_detail.vehicle_state_feedback_c1().brake_torque_feedback())); + zhy.vehicle_state_feedback_c1().brake_torque_feedback())); } else { chassis_.set_brake_percentage(0); } // 9 gear position - if (chassis_detail.has_vehicle_state_feedback_c1() && - chassis_detail.vehicle_state_feedback_c1().has_gear_state_actual()) { - switch (chassis_detail.vehicle_state_feedback_c1().gear_state_actual()) { + if (zhy.has_vehicle_state_feedback_c1() && + zhy.vehicle_state_feedback_c1().has_gear_state_actual()) { + switch (zhy.vehicle_state_feedback_c1().gear_state_actual()) { case Vehicle_state_feedback_c1::GEAR_STATE_ACTUAL_D: { chassis_.set_gear_location(Chassis::GEAR_DRIVE); } break; @@ -219,19 +224,19 @@ Chassis ZhongyunController::chassis() { chassis_.set_gear_location(Chassis::GEAR_NONE); } // 11 steering_percentage - if (chassis_detail.has_vehicle_state_feedback_c1() && - chassis_detail.vehicle_state_feedback_c1().has_steering_actual()) { + if (zhy.has_vehicle_state_feedback_c1() && + zhy.vehicle_state_feedback_c1().has_steering_actual()) { chassis_.set_steering_percentage(static_cast( - chassis_detail.vehicle_state_feedback_c1().steering_actual() * 100.0 / + zhy.vehicle_state_feedback_c1().steering_actual() * 100.0 / vehicle_params_.max_steer_angle() * M_PI / 180)); } else { chassis_.set_steering_percentage(0); } // 12 epb - if (chassis_detail.has_vehicle_state_feedback_c1() && - chassis_detail.vehicle_state_feedback_c1().has_parking_actual()) { + if (zhy.has_vehicle_state_feedback_c1() && + zhy.vehicle_state_feedback_c1().has_parking_actual()) { chassis_.set_parking_brake( - chassis_detail.vehicle_state_feedback_c1().parking_actual() == + zhy.vehicle_state_feedback_c1().parking_actual() == Vehicle_state_feedback_c1::PARKING_ACTUAL_PARKING_TRIGGER); } else { chassis_.set_parking_brake(false); @@ -250,33 +255,9 @@ Chassis ZhongyunController::chassis() { chassis_.mutable_engage_advice()->set_reason( "CANBUS not ready, epb is not released or firmware error!"); } - - // 14 add checkresponse signal - if (chassis_detail.has_enable_state_feedback_c3()) { - if (chassis_detail.enable_state_feedback_c3().has_brake_enable_state()) { - chassis_.mutable_check_response()->set_is_esp_online( - chassis_detail.enable_state_feedback_c3().brake_enable_state() == 1); - } - if (chassis_detail.enable_state_feedback_c3().has_driven_enable_state() && - chassis_detail.enable_state_feedback_c3().has_gear_enable_actual()) { - chassis_.mutable_check_response()->set_is_vcu_online( - ((chassis_detail.enable_state_feedback_c3().driven_enable_state() == - 1) && - (chassis_detail.enable_state_feedback_c3().gear_enable_actual() == - 1)) == 1); - } - if (chassis_detail.enable_state_feedback_c3().has_steering_enable_state()) { - chassis_.mutable_check_response()->set_is_eps_online( - chassis_detail.enable_state_feedback_c3().steering_enable_state() == - 1); - } - } - return chassis_; } -bool ZhongyunController::VerifyID() { return true; } - void ZhongyunController::Emergency() { set_driving_mode(Chassis::EMERGENCY_MODE); ResetProtocol(); @@ -343,8 +324,7 @@ ErrorCode ZhongyunController::EnableSteeringOnlyMode() { const int32_t flag = CHECK_RESPONSE_STEER_UNIT_FLAG | CHECK_RESPONSE_SPEED_UNIT_FLAG; if (!CheckResponse(flag, true)) { - AERROR << "Failed to switch to COMPLETE_AUTO_DRIVE mode. Please check the " - "emergency button or chassis."; + AERROR << "Failed to switch to COMPLETE_AUTO_DRIVE mode."; Emergency(); set_chassis_error_code(Chassis::CHASSIS_ERROR); return ErrorCode::CANBUS_ERROR; @@ -529,50 +509,48 @@ void ZhongyunController::ResetProtocol() { } bool ZhongyunController::CheckChassisError() { - Zhongyun chassis_detail; + ChassisDetail chassis_detail; message_manager_->GetSensorData(&chassis_detail); - if (!chassis_detail.has_check_response()) { + if (!chassis_detail.has_zhongyun()) { AERROR_EVERY(100) << "ChassisDetail has NO zhongyun vehicle info." << chassis_detail.DebugString(); return false; } - + Zhongyun zhy = chassis_detail.zhongyun(); // check steer error - if (chassis_detail.has_error_state_e1() && - chassis_detail.error_state_e1().has_steering_error_code()) { - if (chassis_detail.error_state_e1().steering_error_code() == + if (zhy.has_error_state_e1() && + zhy.error_state_e1().has_steering_error_code()) { + if (zhy.error_state_e1().steering_error_code() == Error_state_e1::STEERING_ERROR_CODE_ERROR) { return true; } } // check ems error - if (chassis_detail.has_error_state_e1() && - chassis_detail.error_state_e1().has_driven_error_code()) { - if (chassis_detail.error_state_e1().driven_error_code() == + if (zhy.has_error_state_e1() && + zhy.error_state_e1().has_driven_error_code()) { + if (zhy.error_state_e1().driven_error_code() == Error_state_e1::DRIVEN_ERROR_CODE_ERROR) { return true; } } // check eps error - if (chassis_detail.has_error_state_e1() && - chassis_detail.error_state_e1().has_brake_error_code()) { - if (chassis_detail.error_state_e1().brake_error_code() == + if (zhy.has_error_state_e1() && zhy.error_state_e1().has_brake_error_code()) { + if (zhy.error_state_e1().brake_error_code() == Error_state_e1::BRAKE_ERROR_CODE_ERROR) { return true; } } // check gear error - if (chassis_detail.has_error_state_e1() && - chassis_detail.error_state_e1().has_gear_error_msg()) { - if (chassis_detail.error_state_e1().gear_error_msg() == + if (zhy.has_error_state_e1() && zhy.error_state_e1().has_gear_error_msg()) { + if (zhy.error_state_e1().gear_error_msg() == Error_state_e1::GEAR_ERROR_MSG_ERROR) { return true; } } // check parking error - if (chassis_detail.has_error_state_e1() && - chassis_detail.error_state_e1().has_parking_error_code()) { - if (chassis_detail.error_state_e1().parking_error_code() == + if (zhy.has_error_state_e1() && + zhy.error_state_e1().has_parking_error_code()) { + if (zhy.error_state_e1().parking_error_code() == Error_state_e1::PARKING_ERROR_CODE_ERROR) { return true; } @@ -608,7 +586,6 @@ void ZhongyunController::SecurityDogThreadFunc() { ++horizontal_ctrl_fail; if (horizontal_ctrl_fail >= kMaxFailAttempt) { emergency_mode = true; - AINFO << "Driving_mode is into emergency by steer manual intervention"; set_chassis_error_code(Chassis::MANUAL_INTERVENTION); } } else { @@ -622,7 +599,6 @@ void ZhongyunController::SecurityDogThreadFunc() { ++vertical_ctrl_fail; if (vertical_ctrl_fail >= kMaxFailAttempt) { emergency_mode = true; - AINFO << "Driving_mode is into emergency by speed manual intervention"; set_chassis_error_code(Chassis::MANUAL_INTERVENTION); } } else { @@ -636,7 +612,6 @@ void ZhongyunController::SecurityDogThreadFunc() { if (emergency_mode && mode != Chassis::EMERGENCY_MODE) { set_driving_mode(Chassis::EMERGENCY_MODE); message_manager_->ResetSendMessages(); - can_sender_->Update(); } end = ::apollo::cyber::Time::Now().ToMicrosecond(); std::chrono::duration elapsed{end - start}; @@ -654,7 +629,7 @@ bool ZhongyunController::CheckResponse(const int32_t flags, bool need_wait) { // for Zhongyun, CheckResponse commonly takes 300ms. We leave a 100ms buffer // for it. int32_t retry_num = 20; - Zhongyun chassis_detail; + ChassisDetail chassis_detail; bool is_eps_online = false; bool is_vcu_online = false; bool is_esp_online = false; diff --git a/modules/canbus_vehicle/zhongyun/zhongyun_controller.h b/modules/canbus/vehicle/zhongyun/zhongyun_controller.h similarity index 88% rename from modules/canbus_vehicle/zhongyun/zhongyun_controller.h rename to modules/canbus/vehicle/zhongyun/zhongyun_controller.h index 2536dae20d8..e57ebf82215 100644 --- a/modules/canbus_vehicle/zhongyun/zhongyun_controller.h +++ b/modules/canbus/vehicle/zhongyun/zhongyun_controller.h @@ -19,25 +19,25 @@ #include #include +#include "modules/canbus/vehicle/vehicle_controller.h" + #include "modules/canbus/proto/canbus_conf.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" #include "modules/common_msgs/basic_msgs/error_code.pb.h" -#include "modules/common_msgs/chassis_msgs/chassis.pb.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" -#include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/canbus_vehicle/zhongyun/protocol/brake_control_a4.h" -#include "modules/canbus_vehicle/zhongyun/protocol/gear_control_a1.h" -#include "modules/canbus_vehicle/zhongyun/protocol/parking_control_a5.h" -#include "modules/canbus_vehicle/zhongyun/protocol/steering_control_a2.h" -#include "modules/canbus_vehicle/zhongyun/protocol/torque_control_a3.h" +#include "modules/canbus/vehicle/zhongyun/protocol/brake_control_a4.h" +#include "modules/canbus/vehicle/zhongyun/protocol/gear_control_a1.h" +#include "modules/canbus/vehicle/zhongyun/protocol/parking_control_a5.h" +#include "modules/canbus/vehicle/zhongyun/protocol/steering_control_a2.h" +#include "modules/canbus/vehicle/zhongyun/protocol/torque_control_a3.h" namespace apollo { namespace canbus { namespace zhongyun { -class ZhongyunController final - : public VehicleController<::apollo::canbus::Zhongyun> { +class ZhongyunController final : public VehicleController { public: ZhongyunController() {} @@ -45,8 +45,8 @@ class ZhongyunController final ::apollo::common::ErrorCode Init( const VehicleParameter& params, - CanSender<::apollo::canbus::Zhongyun>* const can_sender, - MessageManager<::apollo::canbus::Zhongyun>* const message_manager) + CanSender<::apollo::canbus::ChassisDetail>* const can_sender, + MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) override; bool Start() override; @@ -105,7 +105,6 @@ class ZhongyunController final void SetTurningSignal( const ::apollo::control::ControlCommand& command) override; - bool VerifyID() override; void ResetProtocol(); bool CheckChassisError(); diff --git a/modules/canbus_vehicle/zhongyun/zhongyun_controller_test.cc b/modules/canbus/vehicle/zhongyun/zhongyun_controller_test.cc similarity index 93% rename from modules/canbus_vehicle/zhongyun/zhongyun_controller_test.cc rename to modules/canbus/vehicle/zhongyun/zhongyun_controller_test.cc index 350688f7088..1238eacf746 100644 --- a/modules/canbus_vehicle/zhongyun/zhongyun_controller_test.cc +++ b/modules/canbus/vehicle/zhongyun/zhongyun_controller_test.cc @@ -21,9 +21,8 @@ #include "cyber/common/file.h" #include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/canbus_vehicle/zhongyun/proto/zhongyun.pb.h" -#include "modules/canbus_vehicle/zhongyun/zhongyun_controller.h" -#include "modules/canbus_vehicle/zhongyun/zhongyun_message_manager.h" +#include "modules/canbus/vehicle/zhongyun/zhongyun_controller.h" +#include "modules/canbus/vehicle/zhongyun/zhongyun_message_manager.h" #include "modules/common_msgs/control_msgs/control_cmd.pb.h" #include "modules/drivers/canbus/can_comm/can_sender.h" @@ -45,7 +44,7 @@ class ZhongyunControllerTest : public ::testing::Test { protected: ZhongyunController controller_; - CanSender sender_; + CanSender sender_; CanbusConf canbus_conf_; VehicleParameter params_; ZhongyunMessageManager msg_manager_; diff --git a/modules/canbus_vehicle/zhongyun/zhongyun_message_manager.cc b/modules/canbus/vehicle/zhongyun/zhongyun_message_manager.cc similarity index 70% rename from modules/canbus_vehicle/zhongyun/zhongyun_message_manager.cc rename to modules/canbus/vehicle/zhongyun/zhongyun_message_manager.cc index a808fceb4b7..4cc72571c65 100644 --- a/modules/canbus_vehicle/zhongyun/zhongyun_message_manager.cc +++ b/modules/canbus/vehicle/zhongyun/zhongyun_message_manager.cc @@ -13,18 +13,18 @@ See the License for the specific language governing permissions and limitations under the License. ==============================================================================*/ -#include "modules/canbus_vehicle/zhongyun/zhongyun_message_manager.h" - -#include "modules/canbus_vehicle/zhongyun/protocol/brake_control_a4.h" -#include "modules/canbus_vehicle/zhongyun/protocol/gear_control_a1.h" -#include "modules/canbus_vehicle/zhongyun/protocol/parking_control_a5.h" -#include "modules/canbus_vehicle/zhongyun/protocol/steering_control_a2.h" -#include "modules/canbus_vehicle/zhongyun/protocol/torque_control_a3.h" - -#include "modules/canbus_vehicle/zhongyun/protocol/enable_state_feedback_c3.h" -#include "modules/canbus_vehicle/zhongyun/protocol/error_state_e1.h" -#include "modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.h" -#include "modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_c1.h" +#include "modules/canbus/vehicle/zhongyun/zhongyun_message_manager.h" + +#include "modules/canbus/vehicle/zhongyun/protocol/brake_control_a4.h" +#include "modules/canbus/vehicle/zhongyun/protocol/gear_control_a1.h" +#include "modules/canbus/vehicle/zhongyun/protocol/parking_control_a5.h" +#include "modules/canbus/vehicle/zhongyun/protocol/steering_control_a2.h" +#include "modules/canbus/vehicle/zhongyun/protocol/torque_control_a3.h" + +#include "modules/canbus/vehicle/zhongyun/protocol/enable_state_feedback_c3.h" +#include "modules/canbus/vehicle/zhongyun/protocol/error_state_e1.h" +#include "modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.h" +#include "modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_c1.h" namespace apollo { namespace canbus { diff --git a/modules/canbus_vehicle/zhongyun/zhongyun_message_manager.h b/modules/canbus/vehicle/zhongyun/zhongyun_message_manager.h similarity index 89% rename from modules/canbus_vehicle/zhongyun/zhongyun_message_manager.h rename to modules/canbus/vehicle/zhongyun/zhongyun_message_manager.h index 13ae081fcf8..46ef6319e48 100644 --- a/modules/canbus_vehicle/zhongyun/zhongyun_message_manager.h +++ b/modules/canbus/vehicle/zhongyun/zhongyun_message_manager.h @@ -15,7 +15,7 @@ limitations under the License. #pragma once -#include "modules/canbus_vehicle/zhongyun/proto/zhongyun.pb.h" +#include "modules/common_msgs/chassis_msgs/chassis_detail.pb.h" #include "modules/drivers/canbus/can_comm/message_manager.h" namespace apollo { @@ -25,7 +25,7 @@ namespace zhongyun { using ::apollo::drivers::canbus::MessageManager; class ZhongyunMessageManager - : public MessageManager<::apollo::canbus::Zhongyun> { + : public MessageManager<::apollo::canbus::ChassisDetail> { public: ZhongyunMessageManager(); virtual ~ZhongyunMessageManager(); diff --git a/modules/canbus_vehicle/zhongyun/zhongyun_message_manager_test.cc b/modules/canbus/vehicle/zhongyun/zhongyun_message_manager_test.cc similarity index 76% rename from modules/canbus_vehicle/zhongyun/zhongyun_message_manager_test.cc rename to modules/canbus/vehicle/zhongyun/zhongyun_message_manager_test.cc index 3b42113aded..7a4be10511d 100644 --- a/modules/canbus_vehicle/zhongyun/zhongyun_message_manager_test.cc +++ b/modules/canbus/vehicle/zhongyun/zhongyun_message_manager_test.cc @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/zhongyun_message_manager.h" +#include "modules/canbus/vehicle/zhongyun/zhongyun_message_manager.h" #include "gtest/gtest.h" -#include "modules/canbus_vehicle/zhongyun/protocol/brake_control_a4.h" -#include "modules/canbus_vehicle/zhongyun/protocol/enable_state_feedback_c3.h" -#include "modules/canbus_vehicle/zhongyun/protocol/error_state_e1.h" -#include "modules/canbus_vehicle/zhongyun/protocol/gear_control_a1.h" -#include "modules/canbus_vehicle/zhongyun/protocol/parking_control_a5.h" -#include "modules/canbus_vehicle/zhongyun/protocol/steering_control_a2.h" -#include "modules/canbus_vehicle/zhongyun/protocol/torque_control_a3.h" -#include "modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.h" -#include "modules/canbus_vehicle/zhongyun/protocol/vehicle_state_feedback_c1.h" +#include "modules/canbus/vehicle/zhongyun/protocol/brake_control_a4.h" +#include "modules/canbus/vehicle/zhongyun/protocol/enable_state_feedback_c3.h" +#include "modules/canbus/vehicle/zhongyun/protocol/error_state_e1.h" +#include "modules/canbus/vehicle/zhongyun/protocol/gear_control_a1.h" +#include "modules/canbus/vehicle/zhongyun/protocol/parking_control_a5.h" +#include "modules/canbus/vehicle/zhongyun/protocol/steering_control_a2.h" +#include "modules/canbus/vehicle/zhongyun/protocol/torque_control_a3.h" +#include "modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_2_c4.h" +#include "modules/canbus/vehicle/zhongyun/protocol/vehicle_state_feedback_c1.h" namespace apollo { namespace canbus { diff --git a/modules/tools/gen_vehicle_protocol/template/vehicle_factory.cc.tpl b/modules/canbus/vehicle/zhongyun/zhongyun_vehicle_factory.cc similarity index 67% rename from modules/tools/gen_vehicle_protocol/template/vehicle_factory.cc.tpl rename to modules/canbus/vehicle/zhongyun/zhongyun_vehicle_factory.cc index 19b1e8d3e92..036c85a060e 100644 --- a/modules/tools/gen_vehicle_protocol/template/vehicle_factory.cc.tpl +++ b/modules/canbus/vehicle/zhongyun/zhongyun_vehicle_factory.cc @@ -14,25 +14,25 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus/vehicle/%(car_type_lower)s/%(car_type_lower)s_vehicle_factory.h" +#include "modules/canbus/vehicle/zhongyun/zhongyun_vehicle_factory.h" -#include "modules/canbus/vehicle/%(car_type_lower)s/%(car_type_lower)s_controller.h" -#include "modules/canbus/vehicle/%(car_type_lower)s/%(car_type_lower)s_message_manager.h" #include "cyber/common/log.h" +#include "modules/canbus/vehicle/zhongyun/zhongyun_controller.h" +#include "modules/canbus/vehicle/zhongyun/zhongyun_message_manager.h" #include "modules/common/util/util.h" namespace apollo { namespace canbus { std::unique_ptr -%(car_type_cap)sVehicleFactory::CreateVehicleController() { - return std::unique_ptr(new %(car_type_lower)s::%(car_type_cap)sController()); +ZhongyunVehicleFactory::CreateVehicleController() { + return std::unique_ptr(new zhongyun::ZhongyunController()); } std::unique_ptr> -%(car_type_cap)sVehicleFactory::CreateMessageManager() { +ZhongyunVehicleFactory::CreateMessageManager() { return std::unique_ptr>( - new %(car_type_lower)s::%(car_type_cap)sMessageManager()); + new zhongyun::ZhongyunMessageManager()); } } // namespace canbus diff --git a/modules/canbus/vehicle/zhongyun/zhongyun_vehicle_factory.h b/modules/canbus/vehicle/zhongyun/zhongyun_vehicle_factory.h new file mode 100644 index 00000000000..2dede5a110d --- /dev/null +++ b/modules/canbus/vehicle/zhongyun/zhongyun_vehicle_factory.h @@ -0,0 +1,65 @@ +/****************************************************************************** + * 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. + *****************************************************************************/ + +/** + * @file zhongyun_vehicle_factory.h + */ + +#pragma once + +#include + +#include "modules/canbus/proto/vehicle_parameter.pb.h" +#include "modules/canbus/vehicle/abstract_vehicle_factory.h" +#include "modules/canbus/vehicle/vehicle_controller.h" +#include "modules/drivers/canbus/can_comm/message_manager.h" + +/** + * @namespace apollo::canbus + * @brief apollo::canbus + */ +namespace apollo { +namespace canbus { + +/** + * @class ZhongyunVehicleFactory + * + * @brief this class is inherited from AbstractVehicleFactory. It can be used to + * create controller and message manager for zhongyun vehicle. + */ +class ZhongyunVehicleFactory : public AbstractVehicleFactory { + public: + /** + * @brief destructor + */ + virtual ~ZhongyunVehicleFactory() = default; + + /** + * @brief create zhongyun vehicle controller + * @returns a unique_ptr that points to the created controller + */ + std::unique_ptr CreateVehicleController() override; + + /** + * @brief create zhongyun message manager + * @returns a unique_ptr that points to the created message manager + */ + std::unique_ptr> + CreateMessageManager() override; +}; + +} // namespace canbus +} // namespace apollo diff --git a/modules/canbus_vehicle/zhongyun/zhongyun_vehicle_factory_test.cc b/modules/canbus/vehicle/zhongyun/zhongyun_vehicle_factory_test.cc similarity index 60% rename from modules/canbus_vehicle/zhongyun/zhongyun_vehicle_factory_test.cc rename to modules/canbus/vehicle/zhongyun/zhongyun_vehicle_factory_test.cc index ef7fdcc3e73..3425f017e0d 100644 --- a/modules/canbus_vehicle/zhongyun/zhongyun_vehicle_factory_test.cc +++ b/modules/canbus/vehicle/zhongyun/zhongyun_vehicle_factory_test.cc @@ -14,40 +14,31 @@ * limitations under the License. *****************************************************************************/ -#include "modules/canbus_vehicle/zhongyun/zhongyun_vehicle_factory.h" - +#include "modules/canbus/vehicle/zhongyun/zhongyun_vehicle_factory.h" #include "gtest/gtest.h" - -#include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "cyber/common/file.h" - namespace apollo { namespace canbus { class ZhongyunVehicleFactoryTest : public ::testing::Test { public: virtual void SetUp() { - std::string canbus_conf_file = - "/apollo/modules/canbus_vehicle/zhongyun/testdata/" - "zhongyun_canbus_conf_test.pb.txt"; - cyber::common::GetProtoFromFile(canbus_conf_file, &canbus_conf_); - params_ = canbus_conf_.vehicle_parameter(); - params_.set_brand(apollo::common::ZHONGYUN); - zhongyun_factory_.SetVehicleParameter(params_); + VehicleParameter parameter; + parameter.set_brand(apollo::common::ZHONGYUN); + zhongyun_factory_.SetVehicleParameter(parameter); } - virtual void TearDown() {} protected: ZhongyunVehicleFactory zhongyun_factory_; - CanbusConf canbus_conf_; - VehicleParameter params_; }; -TEST_F(ZhongyunVehicleFactoryTest, Init) { - apollo::cyber::Init("vehicle_factory_test"); - EXPECT_EQ(zhongyun_factory_.Init(&canbus_conf_), true); +TEST_F(ZhongyunVehicleFactoryTest, InitVehicleController) { + EXPECT_NE(zhongyun_factory_.CreateVehicleController(), nullptr); +} + +TEST_F(ZhongyunVehicleFactoryTest, InitMessageManager) { + EXPECT_NE(zhongyun_factory_.CreateMessageManager(), nullptr); } } // namespace canbus diff --git a/modules/canbus_vehicle/BUILD b/modules/canbus_vehicle/BUILD deleted file mode 100644 index d72f4431702..00000000000 --- a/modules/canbus_vehicle/BUILD +++ /dev/null @@ -1,35 +0,0 @@ -load("//tools/install:install.bzl", "install", "install_src_files") - -package(default_visibility = ["//visibility:public"]) - -install( - name = "install", - deps = [ - "//modules/canbus_vehicle/ch:install", - "//modules/canbus_vehicle/devkit:install", - "//modules/canbus_vehicle/ge3:install", - "//modules/canbus_vehicle/gem:install", - "//modules/canbus_vehicle/lexus:install", - "//modules/canbus_vehicle/lincoln:install", - "//modules/canbus_vehicle/neolix_edu:install", - "//modules/canbus_vehicle/transit:install", - "//modules/canbus_vehicle/wey:install", - "//modules/canbus_vehicle/zhongyun:install", - ], -) - -install_src_files( - name = "install_src", - deps = [ - "//modules/canbus_vehicle/ch:install_src", - "//modules/canbus_vehicle/devkit:install_src", - "//modules/canbus_vehicle/ge3:install_src", - "//modules/canbus_vehicle/gem:install_src", - "//modules/canbus_vehicle/lexus:install_src", - "//modules/canbus_vehicle/lincoln:install_src", - "//modules/canbus_vehicle/neolix_edu:install_src", - "//modules/canbus_vehicle/transit:install_src", - "//modules/canbus_vehicle/wey:install_src", - "//modules/canbus_vehicle/zhongyun:install_src", - ], -) diff --git a/modules/canbus_vehicle/ch/BUILD b/modules/canbus_vehicle/ch/BUILD deleted file mode 100644 index 5ab57bbcaec..00000000000 --- a/modules/canbus_vehicle/ch/BUILD +++ /dev/null @@ -1,159 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "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"]) - -CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] - -cc_library( - name = "ch_vehicle_factory", - srcs = ["ch_vehicle_factory.cc"], - hdrs = ["ch_vehicle_factory.h"], - copts = CANBUS_COPTS, - alwayslink = True, - deps = [ - ":ch_controller", - ":ch_message_manager", - "//modules/canbus/common:canbus_gflags", - "//modules/common/adapters:adapter_gflags", - "//modules/common/status", - "//modules/canbus/vehicle:abstract_vehicle_factory", - "//modules/drivers/canbus:sensor_canbus_lib", - ], -) - -cc_binary( - name = "libch_vehicle_factory_lib.so", - linkshared = True, - linkstatic = True, - deps = [":ch_vehicle_factory"], -) - -cc_library( - name = "ch_message_manager", - srcs = ["ch_message_manager.cc"], - hdrs = ["ch_message_manager.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_library( - name = "ch_controller", - srcs = ["ch_controller.cc"], - hdrs = ["ch_controller.h"], - copts = CANBUS_COPTS, - deps = [ - ":ch_message_manager", - "//modules/canbus/proto:canbus_conf_cc_proto", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/canbus/proto:vehicle_parameter_cc_proto", - "//modules/canbus/vehicle:vehicle_controller_base", - "//modules/canbus_vehicle/ch/protocol:canbus_ch_protocol", - "//modules/common_msgs/basic_msgs:error_code_cc_proto", - "//modules/common_msgs/control_msgs:control_cmd_cc_proto", - ], -) - -cc_test( - name = "ch_controller_test", - size = "small", - srcs = ["ch_controller_test.cc"], - data = ["//modules/canbus:test_data"], - deps = [ - ":ch_controller", - "@com_google_googletest//:gtest_main", - ], -) - -cc_test( - name = "ch_message_manager_test", - size = "small", - srcs = ["ch_message_manager_test.cc"], - deps = [ - ":ch_message_manager", - "@com_google_googletest//:gtest_main", - ], -) - -cc_test( - name = "ch_vehicle_factory_test", - size = "small", - srcs = ["ch_vehicle_factory_test.cc"], - data = ["//modules/canbus:test_data"], - linkstatic = True, - deps = [ - ":ch_vehicle_factory", - "@com_google_googletest//:gtest_main", - ], -) - -install( - name = "install", - library_dest = "canbus-vehicle-ch/lib", - data_dest = "canbus-vehicle-ch", - data = [ - ":runtime_data", - ":cyberfile.xml", - ":canbus-vehicle-ch.BUILD", - ], - targets = [ - ":libch_vehicle_factory_lib.so", - ], - deps = [ - ":pb_ch", - ":pb_hdrs", - ], -) - -install( - name = "pb_hdrs", - data_dest = "canbus-vehicle-ch/include", - data = [ - "//modules/canbus_vehicle/ch/proto:ch_cc_proto", - ], -) - -install_files( - name = "pb_ch", - dest = "canbus-vehicle-ch", - files = [ - "//modules/canbus_vehicle/ch/proto:ch_py_pb2", - ], -) - -filegroup( - name = "runtime_data", - srcs = glob([ - "testdata/**", - ]), -) - -install_src_files( - name = "install_src", - deps = [ - ":install_ch_src", - ":install_ch_hdrs" - ], -) - -install_src_files( - name = "install_ch_src", - src_dir = ["."], - dest = "canbus-vehicle-ch/src", - filter = "*", -) - -install_src_files( - name = "install_ch_hdrs", - src_dir = ["."], - dest = "canbus-vehicle-ch/include", - filter = "*.h", -) - -cpplint() diff --git a/modules/canbus_vehicle/ch/canbus-vehicle-ch.BUILD b/modules/canbus_vehicle/ch/canbus-vehicle-ch.BUILD deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/modules/canbus_vehicle/ch/ch_vehicle_factory.cc b/modules/canbus_vehicle/ch/ch_vehicle_factory.cc deleted file mode 100644 index 0ffd389857d..00000000000 --- a/modules/canbus_vehicle/ch/ch_vehicle_factory.cc +++ /dev/null @@ -1,165 +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/canbus_vehicle/ch/ch_vehicle_factory.h" - -#include "cyber/common/log.h" -#include "modules/canbus/common/canbus_gflags.h" -#include "modules/canbus_vehicle/ch/ch_controller.h" -#include "modules/canbus_vehicle/ch/ch_message_manager.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common/util/util.h" -#include "modules/drivers/canbus/can_client/can_client_factory.h" - -using apollo::common::ErrorCode; -using apollo::control::ControlCommand; -using apollo::drivers::canbus::CanClientFactory; - -namespace apollo { -namespace canbus { - -bool ChVehicleFactory::Init(const CanbusConf *canbus_conf) { - // Init can client - auto can_factory = CanClientFactory::Instance(); - can_factory->RegisterCanClients(); - can_client_ = can_factory->CreateCANClient(canbus_conf->can_card_parameter()); - if (!can_client_) { - AERROR << "Failed to create can client."; - return false; - } - AINFO << "Can client is successfully created."; - - message_manager_ = this->CreateMessageManager(); - if (message_manager_ == nullptr) { - AERROR << "Failed to create message manager."; - return false; - } - AINFO << "Message manager is successfully created."; - - if (can_receiver_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_receiver_log()) != ErrorCode::OK) { - AERROR << "Failed to init can receiver."; - return false; - } - AINFO << "The can receiver is successfully initialized."; - - if (can_sender_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_sender_log()) != ErrorCode::OK) { - AERROR << "Failed to init can sender."; - return false; - } - AINFO << "The can sender is successfully initialized."; - - vehicle_controller_ = CreateVehicleController(); - if (vehicle_controller_ == nullptr) { - AERROR << "Failed to create vehicle controller."; - return false; - } - AINFO << "The vehicle controller is successfully created."; - - if (vehicle_controller_->Init(canbus_conf->vehicle_parameter(), &can_sender_, - message_manager_.get()) != ErrorCode::OK) { - AERROR << "Failed to init vehicle controller."; - return false; - } - - AINFO << "The vehicle controller is successfully" - << " initialized with canbus conf as : " - << canbus_conf->vehicle_parameter().ShortDebugString(); - - node_ = ::apollo::cyber::CreateNode("chassis_detail"); - - chassis_detail_writer_ = - node_->CreateWriter<::apollo::canbus::Ch>(FLAGS_chassis_detail_topic); - - return true; -} - -bool ChVehicleFactory::Start() { - // 1. init and start the can card hardware - if (can_client_->Start() != ErrorCode::OK) { - AERROR << "Failed to start can client"; - return false; - } - AINFO << "Can client is started."; - - // 2. start receive first then send - if (can_receiver_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can receiver."; - return false; - } - AINFO << "Can receiver is started."; - - // 3. start send - if (can_sender_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can sender."; - return false; - } - - // 4. start controller - if (!vehicle_controller_->Start()) { - AERROR << "Failed to start vehicle controller."; - return false; - } - - return true; -} - -void ChVehicleFactory::Stop() { - can_sender_.Stop(); - can_receiver_.Stop(); - can_client_->Stop(); - vehicle_controller_->Stop(); - AINFO << "Cleanup cansender, canreceiver, canclient, vehicle controller."; -} - -void ChVehicleFactory::UpdateCommand( - const apollo::control::ControlCommand *control_command) { - if (vehicle_controller_->Update(*control_command) != ErrorCode::OK) { - AERROR << "Failed to process callback function OnControlCommand because " - "vehicle_controller_->Update error."; - return; - } - can_sender_.Update(); -} - -Chassis ChVehicleFactory::publish_chassis() { - Chassis chassis = vehicle_controller_->chassis(); - ADEBUG << chassis.ShortDebugString(); - return chassis; -} - -void ChVehicleFactory::PublishChassisDetail() { - Ch chassis_detail; - message_manager_->GetSensorData(&chassis_detail); - ADEBUG << chassis_detail.ShortDebugString(); - chassis_detail_writer_->Write(chassis_detail); -} - -std::unique_ptr> -ChVehicleFactory::CreateVehicleController() { - return std::unique_ptr>( - new ch::ChController()); -} - -std::unique_ptr> -ChVehicleFactory::CreateMessageManager() { - return std::unique_ptr>( - new ch::ChMessageManager()); -} - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/ch_vehicle_factory.h b/modules/canbus_vehicle/ch/ch_vehicle_factory.h deleted file mode 100644 index 79b376647b7..00000000000 --- a/modules/canbus_vehicle/ch/ch_vehicle_factory.h +++ /dev/null @@ -1,120 +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. - *****************************************************************************/ - -/** - * @file ch_vehicle_factory.h - */ - -#pragma once - -#include - -#include "modules/canbus/proto/canbus_conf.pb.h" -#include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "modules/canbus_vehicle/ch/proto/ch.pb.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -#include "cyber/cyber.h" -#include "modules/canbus/vehicle/abstract_vehicle_factory.h" -#include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/common/status/status.h" -#include "modules/drivers/canbus/can_client/can_client.h" -#include "modules/drivers/canbus/can_comm/can_receiver.h" -#include "modules/drivers/canbus/can_comm/can_sender.h" -#include "modules/drivers/canbus/can_comm/message_manager.h" - -/** - * @namespace apollo::canbus - * @brief apollo::canbus - */ -namespace apollo { -namespace canbus { - -/** - * @class ChVehicleFactory - * - * @brief this class is inherited from AbstractVehicleFactory. It can be used to - * create controller and message manager for ch vehicle. - */ -class ChVehicleFactory : public AbstractVehicleFactory { - public: - /** - * @brief destructor - */ - virtual ~ChVehicleFactory() = default; - - /** - * @brief init vehicle factory - * @returns true if successfully initialized - */ - bool Init(const CanbusConf *canbus_conf) override; - - /** - * @brief start canclient, cansender, canreceiver, vehicle controller - * @returns true if successfully started - */ - bool Start() override; - - /** - * @brief stop canclient, cansender, canreceiver, vehicle controller - */ - void Stop() override; - - /** - * @brief update control command - */ - void UpdateCommand( - const apollo::control::ControlCommand *control_command) override; - - /** - * @brief publish chassis messages - */ - Chassis publish_chassis() override; - - /** - * @brief publish chassis for vehicle messages - */ - void PublishChassisDetail() override; - - private: - /** - * @brief create ch vehicle controller - * @returns a unique_ptr that points to the created controller - */ - std::unique_ptr> - CreateVehicleController(); - - /** - * @brief create ch message manager - * @returns a unique_ptr that points to the created message manager - */ - std::unique_ptr> CreateMessageManager(); - - std::unique_ptr<::apollo::cyber::Node> node_ = nullptr; - std::unique_ptr can_client_; - CanSender<::apollo::canbus::Ch> can_sender_; - apollo::drivers::canbus::CanReceiver<::apollo::canbus::Ch> can_receiver_; - std::unique_ptr> message_manager_; - std::unique_ptr> vehicle_controller_; - - std::shared_ptr<::apollo::cyber::Writer<::apollo::canbus::Ch>> - chassis_detail_writer_; -}; - -CYBER_REGISTER_VEHICLEFACTORY(ChVehicleFactory) - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/cyberfile.xml b/modules/canbus_vehicle/ch/cyberfile.xml deleted file mode 100644 index 774272031bd..00000000000 --- a/modules/canbus_vehicle/ch/cyberfile.xml +++ /dev/null @@ -1,24 +0,0 @@ - - canbus-vehicle-ch - local - - Dynamic loading for canbus ch vehicle module - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/canbus_vehicle/ch - - cyber-dev - common-dev - canbus-dev - common-msgs-dev - drivers-dev - 3rd-gtest-dev - - \ No newline at end of file diff --git a/modules/canbus_vehicle/ch/proto/BUILD b/modules/canbus_vehicle/ch/proto/BUILD deleted file mode 100644 index cc49e048bea..00000000000 --- a/modules/canbus_vehicle/ch/proto/BUILD +++ /dev/null @@ -1,25 +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") - -package(default_visibility = ["//visibility:public"]) - -cc_proto_library( - name = "ch_cc_proto", - deps = [ - ":ch_proto", - ], -) - -proto_library( - name = "ch_proto", - srcs = ["ch.proto"], -) - -py_proto_library( - name = "ch_py_pb2", - deps = [ - ":ch_proto", - ], -) diff --git a/modules/canbus_vehicle/ch/protocol/brake_status__511.h b/modules/canbus_vehicle/ch/protocol/brake_status__511.h deleted file mode 100644 index 940abcad5ae..00000000000 --- a/modules/canbus_vehicle/ch/protocol/brake_status__511.h +++ /dev/null @@ -1,98 +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 "modules/canbus_vehicle/ch/proto/ch.pb.h" -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace ch { - -class Brakestatus511 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { - public: - static const int32_t ID; - Brakestatus511(); - void Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const override; - - private: - // config detail: {'bit': 48, 'enum': {0: 'OVERSPD_ENV_NOENV', 1: - // 'OVERSPD_ENV_OVERSPEED_ENV'}, 'is_signed_var': False, 'len': 8, 'name': - // 'OVERSPD_ENV', 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|1]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Brake_status__511::Overspd_envType overspd_env(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 0, 'description': 'brake pedal enable bit(Status)', - // 'enum': {0: 'BRAKE_PEDAL_EN_STS_DISABLE', 1: 'BRAKE_PEDAL_EN_STS_ENABLE', - // 2: 'BRAKE_PEDAL_EN_STS_TAKEOVER'}, 'is_signed_var': False, 'len': 8, - // 'name': 'BRAKE_PEDAL_EN_STS', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|2]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - Brake_status__511::Brake_pedal_en_stsType brake_pedal_en_sts( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 8, 'description': 'Percentage of brake - // pedal(Status)', 'is_signed_var': False, 'len': 8, 'name': - // 'BRAKE_PEDAL_STS', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|100]', 'physical_unit': '%', 'precision': 1.0, 'type': 'int'} - int brake_pedal_sts(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 16, 'enum': {0: 'BRAKE_ERR_NOERR', 1: - // 'BRAKE_ERR_BRAKE_SYSTEM_ERR'}, 'is_signed_var': False, 'len': 8, 'name': - // 'BRAKE_ERR', 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|1]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Brake_status__511::Brake_errType brake_err(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 24, 'enum': {0: 'EMERGENCY_BTN_ENV_NOENV', 1: - // 'EMERGENCY_BTN_ENV_EMERGENCY_BUTTON_ENV'}, 'is_signed_var': False, 'len': - // 8, 'name': 'EMERGENCY_BTN_ENV', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - Brake_status__511::Emergency_btn_envType emergency_btn_env( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 32, 'enum': {0: 'FRONT_BUMP_ENV_NOENV', 1: - // 'FRONT_BUMP_ENV_FRONT_BUMPER_ENV'}, 'is_signed_var': False, 'len': 8, - // 'name': 'FRONT_BUMP_ENV', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - Brake_status__511::Front_bump_envType front_bump_env( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 40, 'enum': {0: 'BACK_BUMP_ENV_NOENV', 1: - // 'BACK_BUMP_ENV_BACK_BUMPER_ENV'}, 'is_signed_var': False, 'len': 8, 'name': - // 'BACK_BUMP_ENV', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Brake_status__511::Back_bump_envType back_bump_env( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 56, 'enum': {0: 'BRAKE_LIGHT_ACTUAL_BRAKELIGHT_OFF', - // 1: 'BRAKE_LIGHT_ACTUAL_BRAKELIGHT_ON'}, 'is_signed_var': False, 'len': 1, - // 'name': 'Brake_Light_Actual', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - Brake_status__511::Brake_light_actualType brake_light_actual( - const std::uint8_t* bytes, const int32_t length) const; -}; - -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/ecu_status_1_515.cc b/modules/canbus_vehicle/ch/protocol/ecu_status_1_515.cc deleted file mode 100644 index 0cf750c97e6..00000000000 --- a/modules/canbus_vehicle/ch/protocol/ecu_status_1_515.cc +++ /dev/null @@ -1,279 +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/canbus_vehicle/ch/protocol/ecu_status_1_515.h" -#include "glog/logging.h" -#include "modules/drivers/canbus/common/byte.h" -#include "modules/drivers/canbus/common/canbus_consts.h" - -namespace apollo { -namespace canbus { -namespace ch { - -using ::apollo::drivers::canbus::Byte; - -Ecustatus1515::Ecustatus1515() {} -const int32_t Ecustatus1515::ID = 0x515; - -void Ecustatus1515::Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const { - chassis->mutable_ecu_status_1_515()->set_chassis_mcu_err( - chassis_mcu_err(bytes, length)); - chassis->mutable_ecu_status_1_515()->set_chassis_mcu_can( - chassis_mcu_can(bytes, length)); - chassis->mutable_ecu_status_1_515()->set_chassis_hw_lost( - chassis_hw_lost(bytes, length)); - chassis->mutable_ecu_status_1_515()->set_chassis_eps_err( - chassis_eps_err(bytes, length)); - chassis->mutable_ecu_status_1_515()->set_chassis_eps_can( - chassis_eps_can(bytes, length)); - chassis->mutable_ecu_status_1_515()->set_chassis_ehb_err( - chassis_ehb_err(bytes, length)); - chassis->mutable_ecu_status_1_515()->set_chassis_ehb_can( - chassis_ehb_can(bytes, length)); - chassis->mutable_ecu_status_1_515()->set_chassis_bms_can( - chassis_bms_can(bytes, length)); - chassis->mutable_ecu_status_1_515()->set_speed( - speed(bytes, length)); - chassis->mutable_ecu_status_1_515()->set_acc_speed( - acc_speed(bytes, length)); - chassis->mutable_ecu_status_1_515()->set_ctrl_sts( - ctrl_sts(bytes, length)); - chassis->mutable_ecu_status_1_515()->set_chassis_sts( - chassis_sts(bytes, length)); - chassis->mutable_ecu_status_1_515()->set_chassis_err( - chassis_err(bytes, length)); - chassis->mutable_ecu_status_1_515()->set_chassis_ads_err( - chassis_ads_err(bytes, length)); -} - -// config detail: {'bit': 0, 'description': 'Current speed (Steering status)', -// 'is_signed_var': True, 'len': 16, 'name': 'speed', 'offset': 0.0, 'order': -// 'intel', 'physical_range': '[-327.68|327.67]', 'physical_unit': 'm/s', -// 'precision': 0.01, 'type': 'double'} -double Ecustatus1515::speed(const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 0); - int32_t t = t1.get_byte(0, 8); - x <<= 8; - x |= t; - - x <<= 16; - x >>= 16; - - double ret = x * 0.010000; - return ret; -} - -// config detail: {'bit': 16, 'description': 'Current acceleration (Steering -// status)', 'is_signed_var': True, 'len': 16, 'name': 'acc_speed', 'offset': -// 0.0, 'order': 'intel', 'physical_range': '[0|0]', 'physical_unit': 'm/s^2', -// 'precision': 0.001, 'type': 'double'} -double Ecustatus1515::acc_speed(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 3); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 2); - int32_t t = t1.get_byte(0, 8); - x <<= 8; - x |= t; - - x <<= 16; - x >>= 16; - - double ret = x * 0.001000; - return ret; -} - -// config detail: {'bit': 32, 'description': 'Current Auto-mode state (Chassis -// status)', 'enum': {0: 'CTRL_STS_OUT_OF_CONTROL', 1: -// 'CTRL_STS_UNDER_CONTROL'}, 'is_signed_var': False, 'len': 8, 'name': -// 'ctrl_sts', 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|1]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Ecu_status_1_515::Ctrl_stsType Ecustatus1515::ctrl_sts( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 4); - int32_t x = t0.get_byte(0, 8); - - Ecu_status_1_515::Ctrl_stsType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 40, 'description': 'Current chassis state (Chassis -// status)', 'is_signed_var': False, 'len': 8, 'name': 'chassis_sts', 'offset': -// 0.0, 'order': 'intel', 'physical_range': '[0|255]', 'physical_unit': '', -// 'precision': 1.0, 'type': 'int'} -int Ecustatus1515::chassis_sts(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 5); - int32_t x = t0.get_byte(0, 8); - - int ret = x; - return ret; -} - -// config detail: {'bit': 48, 'description': 'Chassis error code (Chassis -// status)', 'is_signed_var': False, 'len': 16, 'name': 'chassis_err', 'offset': -// 0.0, 'order': 'intel', 'physical_range': '[0|65535]', 'physical_unit': '', -// 'precision': 1.0, 'type': 'int'} -int Ecustatus1515::chassis_err(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 6); - int32_t t = t1.get_byte(0, 8); - x <<= 8; - x |= t; - - int ret = x; - return ret; -} - -// config detail: {'bit': 48, 'description': 'Chassis error code (Chassis -// status)', 'enum': {0: 'CHASSIS_ADS_ERR_NOMAL', 1: -// 'CHASSIS_ADS_ERR_ADS_CAN_LOST', 2: 'CHASSIS_ADS_ERR_ADS_CAN_RECOVERY'}, -// 'is_signed_var': False, 'len': 2, 'name': 'chassis_ads_err', 'offset': 0.0, -// 'order': 'intel', 'physical_range': '[0|2]', 'physical_unit': '', -// 'precision': 1.0, 'type': 'enum'} -Ecu_status_1_515::Chassis_ads_errType Ecustatus1515::chassis_ads_err( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(0, 2); - - Ecu_status_1_515::Chassis_ads_errType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 50, 'enum': {0: 'CHASSIS_BMS_CAN_NORMAL', 1: -// 'CHASSIS_BMS_CAN_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': -// 'chassis_bms_can', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Ecu_status_1_515::Chassis_bms_canType Ecustatus1515::chassis_bms_can( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(2, 1); - - Ecu_status_1_515::Chassis_bms_canType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 51, 'enum': {0: 'CHASSIS_EHB_CAN_NORMAL', 1: -// 'CHASSIS_EHB_CAN_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': -// 'chassis_ehb_can', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Ecu_status_1_515::Chassis_ehb_canType Ecustatus1515::chassis_ehb_can( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(3, 1); - - Ecu_status_1_515::Chassis_ehb_canType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 52, 'enum': {0: 'CHASSIS_EHB_ERR_NORMAL', 1: -// 'CHASSIS_EHB_ERR_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': -// 'chassis_ehb_err', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Ecu_status_1_515::Chassis_ehb_errType Ecustatus1515::chassis_ehb_err( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(4, 1); - - Ecu_status_1_515::Chassis_ehb_errType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 53, 'enum': {0: 'CHASSIS_EPS_CAN_NORMAL', 1: -// 'CHASSIS_EPS_CAN_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': -// 'chassis_eps_can', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Ecu_status_1_515::Chassis_eps_canType Ecustatus1515::chassis_eps_can( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(5, 1); - - Ecu_status_1_515::Chassis_eps_canType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 54, 'enum': {0: 'CHASSIS_EPS_ERR_NORMAL', 1: -// 'CHASSIS_EPS_ERR_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': -// 'chassis_eps_err', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Ecu_status_1_515::Chassis_eps_errType Ecustatus1515::chassis_eps_err( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(6, 1); - - Ecu_status_1_515::Chassis_eps_errType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 55, 'enum': {0: 'CHASSIS_HW_LOST_NORMAL', 1: -// 'CHASSIS_HW_LOST_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': -// 'chassis_hw_lost', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Ecu_status_1_515::Chassis_hw_lostType Ecustatus1515::chassis_hw_lost( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(7, 1); - - Ecu_status_1_515::Chassis_hw_lostType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 56, 'enum': {0: 'CHASSIS_MCU_CAN_NORMAL', 1: -// 'CHASSIS_MCU_CAN_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': -// 'chassis_mcu_can', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Ecu_status_1_515::Chassis_mcu_canType Ecustatus1515::chassis_mcu_can( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 1); - - Ecu_status_1_515::Chassis_mcu_canType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 57, 'enum': {0: 'CHASSIS_MCU_ERR_NORMAL', 1: -// 'CHASSIS_MCU_ERR_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': -// 'chassis_mcu_err', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Ecu_status_1_515::Chassis_mcu_errType Ecustatus1515::chassis_mcu_err( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(1, 1); - - Ecu_status_1_515::Chassis_mcu_errType ret = - static_cast(x); - return ret; -} -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/ecu_status_1_515.h b/modules/canbus_vehicle/ch/protocol/ecu_status_1_515.h deleted file mode 100644 index e522cc65d59..00000000000 --- a/modules/canbus_vehicle/ch/protocol/ecu_status_1_515.h +++ /dev/null @@ -1,135 +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 "modules/canbus_vehicle/ch/proto/ch.pb.h" -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace ch { - -class Ecustatus1515 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { - public: - static const int32_t ID; - Ecustatus1515(); - void Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const override; - - private: - // config detail: {'bit': 0, 'description': 'Current speed (Steering status)', - // 'is_signed_var': True, 'len': 16, 'name': 'SPEED', 'offset': 0.0, 'order': - // 'intel', 'physical_range': '[-327.68|327.67]', 'physical_unit': 'm/s', - // 'precision': 0.01, 'type': 'double'} - double speed(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 16, 'description': 'Current acceleration (Steering - // status)', 'is_signed_var': True, 'len': 16, 'name': 'ACC_SPEED', 'offset': - // 0.0, 'order': 'intel', 'physical_range': '[0|0]', 'physical_unit': 'm/s^2', - // 'precision': 0.001, 'type': 'double'} - double acc_speed(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 32, 'description': 'Current Auto-mode state (Chassis - // status)', 'enum': {0: 'CTRL_STS_OUT_OF_CONTROL', 1: - // 'CTRL_STS_UNDER_CONTROL'}, 'is_signed_var': False, 'len': 8, 'name': - // 'CTRL_STS', 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|1]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Ecu_status_1_515::Ctrl_stsType ctrl_sts(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 40, 'description': 'Current chassis state (Chassis - // status)', 'is_signed_var': False, 'len': 8, 'name': 'CHASSIS_STS', - // 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - int chassis_sts(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 48, 'description': 'Chassis error code (Chassis - // status)', 'is_signed_var': False, 'len': 16, 'name': 'CHASSIS_ERR', - // 'offset': 0.0, 'order': 'intel', 'physical_range': '[0|65535]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - int chassis_err(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 48, 'description': 'Chassis error code (Chassis - // status)', 'enum': {0: 'CHASSIS_ADS_ERR_NOMAL', 1: - // 'CHASSIS_ADS_ERR_ADS_CAN_LOST', 2: 'CHASSIS_ADS_ERR_ADS_CAN_RECOVERY'}, - // 'is_signed_var': False, 'len': 2, 'name': 'CHASSIS_ADS_ERR', 'offset': 0.0, - // 'order': 'intel', 'physical_range': '[0|2]', 'physical_unit': '', - // 'precision': 1.0, 'type': 'enum'} - Ecu_status_1_515::Chassis_ads_errType chassis_ads_err( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 50, 'enum': {0: 'CHASSIS_BMS_CAN_NORMAL', 1: - // 'CHASSIS_BMS_CAN_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': - // 'CHASSIS_BMS_CAN', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Ecu_status_1_515::Chassis_bms_canType chassis_bms_can( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 51, 'enum': {0: 'CHASSIS_EHB_CAN_NORMAL', 1: - // 'CHASSIS_EHB_CAN_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': - // 'CHASSIS_EHB_CAN', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Ecu_status_1_515::Chassis_ehb_canType chassis_ehb_can( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 52, 'enum': {0: 'CHASSIS_EHB_ERR_NORMAL', 1: - // 'CHASSIS_EHB_ERR_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': - // 'CHASSIS_EHB_ERR', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Ecu_status_1_515::Chassis_ehb_errType chassis_ehb_err( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 53, 'enum': {0: 'CHASSIS_EPS_CAN_NORMAL', 1: - // 'CHASSIS_EPS_CAN_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': - // 'CHASSIS_EPS_CAN', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Ecu_status_1_515::Chassis_eps_canType chassis_eps_can( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 54, 'enum': {0: 'CHASSIS_EPS_ERR_NORMAL', 1: - // 'CHASSIS_EPS_ERR_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': - // 'CHASSIS_EPS_ERR', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Ecu_status_1_515::Chassis_eps_errType chassis_eps_err( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 55, 'enum': {0: 'CHASSIS_HW_LOST_NORMAL', 1: - // 'CHASSIS_HW_LOST_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': - // 'CHASSIS_HW_Lost', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Ecu_status_1_515::Chassis_hw_lostType chassis_hw_lost( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 56, 'enum': {0: 'CHASSIS_MCU_CAN_NORMAL', 1: - // 'CHASSIS_MCU_CAN_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': - // 'CHASSIS_MCU_CAN', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Ecu_status_1_515::Chassis_mcu_canType chassis_mcu_can( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 57, 'enum': {0: 'CHASSIS_MCU_ERR_NORMAL', 1: - // 'CHASSIS_MCU_ERR_ERROR'}, 'is_signed_var': False, 'len': 1, 'name': - // 'CHASSIS_MCU_ERR', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Ecu_status_1_515::Chassis_mcu_errType chassis_mcu_err( - const std::uint8_t* bytes, const int32_t length) const; -}; - -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/ecu_status_3_517.cc b/modules/canbus_vehicle/ch/protocol/ecu_status_3_517.cc deleted file mode 100644 index 0bb29c90e76..00000000000 --- a/modules/canbus_vehicle/ch/protocol/ecu_status_3_517.cc +++ /dev/null @@ -1,156 +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/canbus_vehicle/ch/protocol/ecu_status_3_517.h" -#include "glog/logging.h" -#include "modules/drivers/canbus/common/byte.h" -#include "modules/drivers/canbus/common/canbus_consts.h" - -namespace apollo { -namespace canbus { -namespace ch { - -using ::apollo::drivers::canbus::Byte; - -Ecustatus3517::Ecustatus3517() {} -const int32_t Ecustatus3517::ID = 0x517; - -void Ecustatus3517::Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const { - chassis->mutable_ecu_status_3_517()->set_ultrasound_dist_1( - ultrasound_dist_1(bytes, length)); - chassis->mutable_ecu_status_3_517()->set_ultrasound_dist_2( - ultrasound_dist_2(bytes, length)); - chassis->mutable_ecu_status_3_517()->set_ultrasound_dist_3( - ultrasound_dist_3(bytes, length)); - chassis->mutable_ecu_status_3_517()->set_ultrasound_dist_4( - ultrasound_dist_4(bytes, length)); - chassis->mutable_ecu_status_3_517()->set_ultrasound_dist_5( - ultrasound_dist_5(bytes, length)); - chassis->mutable_ecu_status_3_517()->set_ultrasound_dist_6( - ultrasound_dist_6(bytes, length)); - chassis->mutable_ecu_status_3_517()->set_ultrasound_dist_7( - ultrasound_dist_7(bytes, length)); - chassis->mutable_ecu_status_3_517()->set_ultrasound_dist_8( - ultrasound_dist_8(bytes, length)); -} - -// config detail: {'bit': 0, 'description': 'Ultrasonic detection distance 1 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_1', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus3517::ultrasound_dist_1(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} - -// config detail: {'bit': 8, 'description': 'Ultrasonic detection distance 2 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_2', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus3517::ultrasound_dist_2(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} - -// config detail: {'bit': 16, 'description': 'Ultrasonic detection distance 3 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_3', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus3517::ultrasound_dist_3(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 2); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} - -// config detail: {'bit': 24, 'description': 'Ultrasonic detection distance 4 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_4', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus3517::ultrasound_dist_4(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 3); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} - -// config detail: {'bit': 32, 'description': 'Ultrasonic detection distance 5 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_5', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus3517::ultrasound_dist_5(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 4); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} - -// config detail: {'bit': 40, 'description': 'Ultrasonic detection distance 6 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_6', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus3517::ultrasound_dist_6(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 5); - int32_t x = t0.get_byte(0, 8); - - int ret = x; - return ret; -} - -// config detail: {'bit': 48, 'description': 'Ultrasonic detection distance 7 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_7', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus3517::ultrasound_dist_7(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} - -// config detail: {'bit': 56, 'description': 'Ultrasonic detection distance 8 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_8', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus3517::ultrasound_dist_8(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/ecu_status_3_517.h b/modules/canbus_vehicle/ch/protocol/ecu_status_3_517.h deleted file mode 100644 index 74a1ef64372..00000000000 --- a/modules/canbus_vehicle/ch/protocol/ecu_status_3_517.h +++ /dev/null @@ -1,94 +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 "modules/canbus_vehicle/ch/proto/ch.pb.h" -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace ch { - -class Ecustatus3517 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { - public: - static const int32_t ID; - Ecustatus3517(); - void Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const override; - - private: - // config detail: {'bit': 0, 'description': 'Ultrasonic detection distance 1 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_1', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_1(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 8, 'description': 'Ultrasonic detection distance 2 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_2', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_2(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 16, 'description': 'Ultrasonic detection distance 3 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_3', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_3(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 24, 'description': 'Ultrasonic detection distance 4 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_4', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_4(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 32, 'description': 'Ultrasonic detection distance 5 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_5', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_5(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 40, 'description': 'Ultrasonic detection distance 6 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_6', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_6(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 48, 'description': 'Ultrasonic detection distance 7 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_7', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_7(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 56, 'description': 'Ultrasonic detection distance 8 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_8', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_8(const std::uint8_t* bytes, - const int32_t length) const; -}; - -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/ecu_status_4_518.cc b/modules/canbus_vehicle/ch/protocol/ecu_status_4_518.cc deleted file mode 100644 index a10904c1ded..00000000000 --- a/modules/canbus_vehicle/ch/protocol/ecu_status_4_518.cc +++ /dev/null @@ -1,158 +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/canbus_vehicle/ch/protocol/ecu_status_4_518.h" - -#include "glog/logging.h" - -#include "modules/drivers/canbus/common/byte.h" -#include "modules/drivers/canbus/common/canbus_consts.h" - -namespace apollo { -namespace canbus { -namespace ch { - -using ::apollo::drivers::canbus::Byte; - -Ecustatus4518::Ecustatus4518() {} -const int32_t Ecustatus4518::ID = 0x518; - -void Ecustatus4518::Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const { - chassis->mutable_ecu_status_4_518()->set_ultrasound_dist_9( - ultrasound_dist_9(bytes, length)); - chassis->mutable_ecu_status_4_518()->set_ultrasound_dist_10( - ultrasound_dist_10(bytes, length)); - chassis->mutable_ecu_status_4_518()->set_ultrasound_dist_11( - ultrasound_dist_11(bytes, length)); - chassis->mutable_ecu_status_4_518()->set_ultrasound_dist_12( - ultrasound_dist_12(bytes, length)); - chassis->mutable_ecu_status_4_518()->set_ultrasound_dist_13( - ultrasound_dist_13(bytes, length)); - chassis->mutable_ecu_status_4_518()->set_ultrasound_dist_14( - ultrasound_dist_14(bytes, length)); - chassis->mutable_ecu_status_4_518()->set_ultrasound_dist_15( - ultrasound_dist_15(bytes, length)); - chassis->mutable_ecu_status_4_518()->set_ultrasound_dist_16( - ultrasound_dist_16(bytes, length)); -} - -// config detail: {'bit': 0, 'description': 'Ultrasonic detection distance 9 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_9', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus4518::ultrasound_dist_9(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} - -// config detail: {'bit': 8, 'description': 'Ultrasonic detection distance 10 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_10', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus4518::ultrasound_dist_10(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} - -// config detail: {'bit': 16, 'description': 'Ultrasonic detection distance 11 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_11', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus4518::ultrasound_dist_11(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 2); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} - -// config detail: {'bit': 24, 'description': 'Ultrasonic detection distance 12 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_12', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus4518::ultrasound_dist_12(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 3); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} - -// config detail: {'bit': 32, 'description': 'Ultrasonic detection distance 13 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_13', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus4518::ultrasound_dist_13(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 4); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} - -// config detail: {'bit': 40, 'description': 'Ultrasonic detection distance 14 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_14', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus4518::ultrasound_dist_14(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 5); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} - -// config detail: {'bit': 48, 'description': 'Ultrasonic detection distance 15 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_15', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus4518::ultrasound_dist_15(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} - -// config detail: {'bit': 56, 'description': 'Ultrasonic detection distance 16 -// (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': -// 'ultrasound_dist_16', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} -double Ecustatus4518::ultrasound_dist_16(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 8); - - double ret = x * 2.000000; - return ret; -} -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/ecu_status_4_518.h b/modules/canbus_vehicle/ch/protocol/ecu_status_4_518.h deleted file mode 100644 index 6a67c9abc72..00000000000 --- a/modules/canbus_vehicle/ch/protocol/ecu_status_4_518.h +++ /dev/null @@ -1,94 +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 "modules/canbus_vehicle/ch/proto/ch.pb.h" -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace ch { - -class Ecustatus4518 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { - public: - static const int32_t ID; - Ecustatus4518(); - void Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const override; - - private: - // config detail: {'bit': 0, 'description': 'Ultrasonic detection distance 9 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_9', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_9(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 8, 'description': 'Ultrasonic detection distance 10 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_10', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_10(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 16, 'description': 'Ultrasonic detection distance 11 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_11', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_11(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 24, 'description': 'Ultrasonic detection distance 12 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_12', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_12(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 32, 'description': 'Ultrasonic detection distance 13 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_13', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_13(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 40, 'description': 'Ultrasonic detection distance 14 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_14', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_14(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 48, 'description': 'Ultrasonic detection distance 15 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_15', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_15(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 56, 'description': 'Ultrasonic detection distance 16 - // (Ultrasound status)', 'is_signed_var': False, 'len': 8, 'name': - // 'ULTRASOUND_DIST_16', 'offset': 0.0, 'order': 'intel', 'physical_range': - // '[0|500]', 'physical_unit': 'cm', 'precision': 2.0, 'type': 'double'} - double ultrasound_dist_16(const std::uint8_t* bytes, - const int32_t length) const; -}; - -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/turnsignal_command_113.h b/modules/canbus_vehicle/ch/protocol/turnsignal_command_113.h deleted file mode 100644 index e56908c4f88..00000000000 --- a/modules/canbus_vehicle/ch/protocol/turnsignal_command_113.h +++ /dev/null @@ -1,82 +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 "modules/canbus_vehicle/ch/proto/ch.pb.h" -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace ch { - -class Turnsignalcommand113 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { - public: - static const int32_t ID; - - Turnsignalcommand113(); - - uint32_t GetPeriod() const override; - - void UpdateData(uint8_t* data) override; - - void Reset() override; - - // config detail: {'bit': 8, 'description': 'Lighting control(Command)', - // 'enum': {0: 'LOW_BEAM_CMD_OFF', 1: 'LOW_BEAM_CMD_ON'}, 'is_signed_var': - // False, 'len': 2, 'name': 'LOW_BEAM_CMD', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|2]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - Turnsignalcommand113* set_low_beam_cmd( - Turnsignal_command_113::Low_beam_cmdType low_beam_cmd); - - // config detail: {'bit': 0, 'description': 'Lighting control(Command)', - // 'enum': {0: 'TURN_SIGNAL_CMD_NONE', 1: 'TURN_SIGNAL_CMD_LEFT', 2: - // 'TURN_SIGNAL_CMD_RIGHT', 3: 'TURN_SIGNAL_CMD_HAZARD_WARNING_LAMPSTS'}, - // 'is_signed_var': False, 'len': 8, 'name': 'TURN_SIGNAL_CMD', 'offset': 0.0, - // 'order': 'intel', 'physical_range': '[0|2]', 'physical_unit': '', - // 'precision': 1.0, 'type': 'enum'} - Turnsignalcommand113* set_turn_signal_cmd( - Turnsignal_command_113::Turn_signal_cmdType turn_signal_cmd); - - private: - // config detail: {'bit': 8, 'description': 'Lighting control(Command)', - // 'enum': {0: 'LOW_BEAM_CMD_OFF', 1: 'LOW_BEAM_CMD_ON'}, 'is_signed_var': - // False, 'len': 2, 'name': 'LOW_BEAM_CMD', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|2]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - void set_p_low_beam_cmd( - uint8_t* data, Turnsignal_command_113::Low_beam_cmdType low_beam_cmd); - - // config detail: {'bit': 0, 'description': 'Lighting control(Command)', - // 'enum': {0: 'TURN_SIGNAL_CMD_NONE', 1: 'TURN_SIGNAL_CMD_LEFT', 2: - // 'TURN_SIGNAL_CMD_RIGHT', 3: 'TURN_SIGNAL_CMD_HAZARD_WARNING_LAMPSTS'}, - // 'is_signed_var': False, 'len': 8, 'name': 'TURN_SIGNAL_CMD', 'offset': 0.0, - // 'order': 'intel', 'physical_range': '[0|2]', 'physical_unit': '', - // 'precision': 1.0, 'type': 'enum'} - void set_p_turn_signal_cmd( - uint8_t* data, - Turnsignal_command_113::Turn_signal_cmdType turn_signal_cmd); - - private: - Turnsignal_command_113::Turn_signal_cmdType turn_signal_cmd_; - Turnsignal_command_113::Low_beam_cmdType low_beam_cmd_; -}; - -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/turnsignal_status__513.cc b/modules/canbus_vehicle/ch/protocol/turnsignal_status__513.cc deleted file mode 100644 index 92e13efcdc8..00000000000 --- a/modules/canbus_vehicle/ch/protocol/turnsignal_status__513.cc +++ /dev/null @@ -1,72 +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/canbus_vehicle/ch/protocol/turnsignal_status__513.h" - -#include "modules/drivers/canbus/common/byte.h" -#include "modules/drivers/canbus/common/canbus_consts.h" - -namespace apollo { -namespace canbus { -namespace ch { - -using ::apollo::drivers::canbus::Byte; - -Turnsignalstatus513::Turnsignalstatus513() {} -const int32_t Turnsignalstatus513::ID = 0x513; - -void Turnsignalstatus513::Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const { - chassis->mutable_turnsignal_status__513()->set_turn_signal_sts( - turn_signal_sts(bytes, length)); - chassis->mutable_turnsignal_status__513()->set_low_beam_sts( - low_beam_sts(bytes, length)); -} - -// config detail: {'bit': 0, 'description': 'Lighting control(Status)', 'enum': -// {0: 'TURN_SIGNAL_STS_NONE', 1: 'TURN_SIGNAL_STS_LEFT', 2: -// 'TURN_SIGNAL_STS_RIGHT', 3: 'TURN_SIGNAL_STS_HAZARD_WARNING_LAMPSTS_ON'}, -// 'is_signed_var': False, 'len': 8, 'name': 'turn_signal_sts', 'offset': 0.0, -// 'order': 'intel', 'physical_range': '[0|2]', 'physical_unit': '', -// 'precision': 1.0, 'type': 'enum'} -Turnsignal_status__513::Turn_signal_stsType -Turnsignalstatus513::turn_signal_sts(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 8); - - Turnsignal_status__513::Turn_signal_stsType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 8, 'description': 'Lighting control(Status)', 'enum': -// {0: 'LOW_BEAM_STS_ON', 1: 'LOW_BEAM_STS_OFF'}, 'is_signed_var': False, 'len': -// 2, 'name': 'low_beam_sts', 'offset': 0.0, 'order': 'intel', 'physical_range': -// '[0|2]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Turnsignal_status__513::Low_beam_stsType Turnsignalstatus513::low_beam_sts( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 2); - - Turnsignal_status__513::Low_beam_stsType ret = - static_cast(x); - return ret; -} - -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/turnsignal_status__513.h b/modules/canbus_vehicle/ch/protocol/turnsignal_status__513.h deleted file mode 100644 index 1a9568e1084..00000000000 --- a/modules/canbus_vehicle/ch/protocol/turnsignal_status__513.h +++ /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. - *****************************************************************************/ - -#pragma once - -#include "modules/canbus_vehicle/ch/proto/ch.pb.h" -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace ch { - -class Turnsignalstatus513 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { - public: - static const int32_t ID; - Turnsignalstatus513(); - void Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const override; - - private: - // config detail: {'bit': 0, 'description': 'Lighting control(Status)', - // 'enum': {0: 'TURN_SIGNAL_STS_NONE', 1: 'TURN_SIGNAL_STS_LEFT', 2: - // 'TURN_SIGNAL_STS_RIGHT', 3: 'TURN_SIGNAL_STS_HAZARD_WARNING_LAMPSTS_ON'}, - // 'is_signed_var': False, 'len': 8, 'name': 'TURN_SIGNAL_STS', 'offset': 0.0, - // 'order': 'intel', 'physical_range': '[0|2]', 'physical_unit': '', - // 'precision': 1.0, 'type': 'enum'} - Turnsignal_status__513::Turn_signal_stsType turn_signal_sts( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 8, 'description': 'Lighting control(Status)', - // 'enum': {0: 'LOW_BEAM_STS_ON', 1: 'LOW_BEAM_STS_OFF'}, 'is_signed_var': - // False, 'len': 2, 'name': 'LOW_BEAM_STS', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|2]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - Turnsignal_status__513::Low_beam_stsType low_beam_sts( - const std::uint8_t* bytes, const int32_t length) const; -}; - -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/vehicle_mode_command_116.cc b/modules/canbus_vehicle/ch/protocol/vehicle_mode_command_116.cc deleted file mode 100644 index 4c3f53e0bf0..00000000000 --- a/modules/canbus_vehicle/ch/protocol/vehicle_mode_command_116.cc +++ /dev/null @@ -1,68 +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/canbus_vehicle/ch/protocol/vehicle_mode_command_116.h" - -#include "modules/drivers/canbus/common/byte.h" - -namespace apollo { -namespace canbus { -namespace ch { - -using ::apollo::drivers::canbus::Byte; - -const int32_t Vehiclemodecommand116::ID = 0x116; - -// public -Vehiclemodecommand116::Vehiclemodecommand116() { Reset(); } - -uint32_t Vehiclemodecommand116::GetPeriod() const { - // TODO(All) : modify every protocol's period manually - static const uint32_t PERIOD = 500 * 1000; - return PERIOD; -} - -void Vehiclemodecommand116::UpdateData(uint8_t* data) { - set_p_vin_req_cmd(data, vin_req_cmd_); -} - -void Vehiclemodecommand116::Reset() { - // TODO(All) : you should check this manually - vin_req_cmd_ = Vehicle_mode_command_116::VIN_REQ_CMD_VIN_REQ_DISABLE; -} - -Vehiclemodecommand116* Vehiclemodecommand116::set_vin_req_cmd( - Vehicle_mode_command_116::Vin_req_cmdType vin_req_cmd) { - vin_req_cmd_ = vin_req_cmd; - return this; -} - -// config detail: {'bit': 0, 'description': 'Request VIN(Command)', 'enum': {0: -// 'VIN_REQ_CMD_VIN_REQ_DISABLE', 1: 'VIN_REQ_CMD_VIN_REQ_ENABLE'}, -// 'is_signed_var': False, 'len': 1, 'name': 'VIN_REQ_CMD', 'offset': 0.0, -// 'order': 'intel', 'physical_range': '[0|1]', 'physical_unit': '', -// 'precision': 1.0, 'type': 'enum'} -void Vehiclemodecommand116::set_p_vin_req_cmd( - uint8_t* data, Vehicle_mode_command_116::Vin_req_cmdType vin_req_cmd) { - int x = vin_req_cmd; - - Byte to_set(data + 0); - to_set.set_value(static_cast(x), 0, 1); -} - -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/vehicle_mode_command_116.h b/modules/canbus_vehicle/ch/protocol/vehicle_mode_command_116.h deleted file mode 100644 index 874bc506135..00000000000 --- a/modules/canbus_vehicle/ch/protocol/vehicle_mode_command_116.h +++ /dev/null @@ -1,62 +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 "modules/canbus_vehicle/ch/proto/ch.pb.h" -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace ch { - -class Vehiclemodecommand116 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { - public: - static const int32_t ID; - - Vehiclemodecommand116(); - - uint32_t GetPeriod() const override; - - void UpdateData(uint8_t* data) override; - - void Reset() override; - - // config detail: {'bit': 0, 'description': 'Request VIN(Command)', 'enum': - // {0: 'VIN_REQ_CMD_VIN_REQ_DISABLE', 1: 'VIN_REQ_CMD_VIN_REQ_ENABLE'}, - // 'is_signed_var': False, 'len': 1, 'name': 'VIN_REQ_CMD', 'offset': 0.0, - // 'order': 'intel', 'physical_range': '[0|1]', 'physical_unit': '', - // 'precision': 1.0, 'type': 'enum'} - Vehiclemodecommand116* set_vin_req_cmd( - Vehicle_mode_command_116::Vin_req_cmdType vin_req_cmd); - - private: - // config detail: {'bit': 0, 'description': 'Request VIN(Command)', 'enum': - // {0: 'VIN_REQ_CMD_VIN_REQ_DISABLE', 1: 'VIN_REQ_CMD_VIN_REQ_ENABLE'}, - // 'is_signed_var': False, 'len': 1, 'name': 'VIN_REQ_CMD', 'offset': 0.0, - // 'order': 'intel', 'physical_range': '[0|1]', 'physical_unit': '', - // 'precision': 1.0, 'type': 'enum'} - void set_p_vin_req_cmd(uint8_t* data, - Vehicle_mode_command_116::Vin_req_cmdType vin_req_cmd); - - private: - Vehicle_mode_command_116::Vin_req_cmdType vin_req_cmd_; -}; - -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/vin_resp1_51b.cc b/modules/canbus_vehicle/ch/protocol/vin_resp1_51b.cc deleted file mode 100644 index c43852a9823..00000000000 --- a/modules/canbus_vehicle/ch/protocol/vin_resp1_51b.cc +++ /dev/null @@ -1,168 +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/canbus_vehicle/ch/protocol/vin_resp1_51b.h" - -#include - -#include "glog/logging.h" - -#include "modules/drivers/canbus/common/byte.h" -#include "modules/drivers/canbus/common/canbus_consts.h" - -namespace apollo { -namespace canbus { -namespace ch { - -using ::apollo::drivers::canbus::Byte; - -Vinresp151b::Vinresp151b() {} -const int32_t Vinresp151b::ID = 0x51B; - -void Vinresp151b::Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const { - chassis->mutable_vin_resp1_51b()->set_vin08( - vin08(bytes, length)); - chassis->mutable_vin_resp1_51b()->set_vin07( - vin07(bytes, length)); - chassis->mutable_vin_resp1_51b()->set_vin06( - vin06(bytes, length)); - chassis->mutable_vin_resp1_51b()->set_vin05( - vin05(bytes, length)); - chassis->mutable_vin_resp1_51b()->set_vin04( - vin04(bytes, length)); - chassis->mutable_vin_resp1_51b()->set_vin03( - vin03(bytes, length)); - chassis->mutable_vin_resp1_51b()->set_vin02( - vin02(bytes, length)); - chassis->mutable_vin_resp1_51b()->set_vin01( - vin01(bytes, length)); -} - -// config detail: {'bit': 56, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin08', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp151b::vin08(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 48, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin07', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp151b::vin07(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 40, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin06', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp151b::vin06(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 5); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 32, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin05', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp151b::vin05(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 4); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 24, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin04', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp151b::vin04(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 3); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 16, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin03', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp151b::vin03(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 2); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 8, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin02', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp151b::vin02(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 0, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin01', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp151b::vin01(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/vin_resp1_51b.h b/modules/canbus_vehicle/ch/protocol/vin_resp1_51b.h deleted file mode 100644 index cdb024c5cc2..00000000000 --- a/modules/canbus_vehicle/ch/protocol/vin_resp1_51b.h +++ /dev/null @@ -1,88 +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 "modules/canbus_vehicle/ch/proto/ch.pb.h" -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace ch { - -class Vinresp151b : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { - public: - static const int32_t ID; - Vinresp151b(); - void Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const override; - - private: - // config detail: {'bit': 56, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN08', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin08(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 48, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN07', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin07(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 40, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN06', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin06(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 32, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN05', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin05(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 24, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN04', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin04(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 16, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN03', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin03(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 8, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN02', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin02(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 0, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN01', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin01(const std::uint8_t* bytes, const int32_t length) const; -}; - -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/vin_resp2_51c.cc b/modules/canbus_vehicle/ch/protocol/vin_resp2_51c.cc deleted file mode 100644 index e75aa534a13..00000000000 --- a/modules/canbus_vehicle/ch/protocol/vin_resp2_51c.cc +++ /dev/null @@ -1,168 +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/canbus_vehicle/ch/protocol/vin_resp2_51c.h" - -#include - -#include "glog/logging.h" - -#include "modules/drivers/canbus/common/byte.h" -#include "modules/drivers/canbus/common/canbus_consts.h" - -namespace apollo { -namespace canbus { -namespace ch { - -using ::apollo::drivers::canbus::Byte; - -Vinresp251c::Vinresp251c() {} -const int32_t Vinresp251c::ID = 0x51C; - -void Vinresp251c::Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const { - chassis->mutable_vin_resp2_51c()->set_vin16( - vin16(bytes, length)); - chassis->mutable_vin_resp2_51c()->set_vin15( - vin15(bytes, length)); - chassis->mutable_vin_resp2_51c()->set_vin14( - vin14(bytes, length)); - chassis->mutable_vin_resp2_51c()->set_vin13( - vin13(bytes, length)); - chassis->mutable_vin_resp2_51c()->set_vin12( - vin12(bytes, length)); - chassis->mutable_vin_resp2_51c()->set_vin11( - vin11(bytes, length)); - chassis->mutable_vin_resp2_51c()->set_vin10( - vin10(bytes, length)); - chassis->mutable_vin_resp2_51c()->set_vin09( - vin09(bytes, length)); -} - -// config detail: {'bit': 56, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin16', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp251c::vin16(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 48, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin15', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp251c::vin15(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 40, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin14', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp251c::vin14(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 5); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 32, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin13', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp251c::vin13(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 4); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 24, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin12', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp251c::vin12(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 3); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 16, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin11', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp251c::vin11(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 2); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 8, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin10', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp251c::vin10(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 0, 'description': 'VIN Response', 'is_signed_var': -// False, 'len': 8, 'name': 'vin09', 'offset': 0.0, 'order': 'intel', -// 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'int'} -std::string Vinresp251c::vin09(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/vin_resp2_51c.h b/modules/canbus_vehicle/ch/protocol/vin_resp2_51c.h deleted file mode 100644 index c039cf60592..00000000000 --- a/modules/canbus_vehicle/ch/protocol/vin_resp2_51c.h +++ /dev/null @@ -1,88 +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 "modules/canbus_vehicle/ch/proto/ch.pb.h" -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace ch { - -class Vinresp251c : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { - public: - static const int32_t ID; - Vinresp251c(); - void Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const override; - - private: - // config detail: {'bit': 56, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN16', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin16(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 48, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN15', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin15(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 40, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN14', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin14(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 32, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN13', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin13(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 24, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN12', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin12(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 16, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN11', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin11(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 8, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN10', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin10(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 0, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN09', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin09(const std::uint8_t* bytes, const int32_t length) const; -}; - -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/vin_resp3_51d.h b/modules/canbus_vehicle/ch/protocol/vin_resp3_51d.h deleted file mode 100644 index 4d644999e66..00000000000 --- a/modules/canbus_vehicle/ch/protocol/vin_resp3_51d.h +++ /dev/null @@ -1,46 +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 "modules/canbus_vehicle/ch/proto/ch.pb.h" -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace ch { - -class Vinresp351d : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { - public: - static const int32_t ID; - Vinresp351d(); - void Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const override; - - private: - // config detail: {'bit': 0, 'description': 'VIN Response', 'is_signed_var': - // False, 'len': 8, 'name': 'VIN17', 'offset': 0.0, 'order': 'intel', - // 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'int'} - std::string vin17(const std::uint8_t* bytes, const int32_t length) const; -}; - -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/wheelspeed_report_51e.cc b/modules/canbus_vehicle/ch/protocol/wheelspeed_report_51e.cc deleted file mode 100644 index 293519497d3..00000000000 --- a/modules/canbus_vehicle/ch/protocol/wheelspeed_report_51e.cc +++ /dev/null @@ -1,130 +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/canbus_vehicle/ch/protocol/wheelspeed_report_51e.h" - -#include "glog/logging.h" - -#include "modules/drivers/canbus/common/byte.h" -#include "modules/drivers/canbus/common/canbus_consts.h" - -namespace apollo { -namespace canbus { -namespace ch { - -using ::apollo::drivers::canbus::Byte; - -Wheelspeedreport51e::Wheelspeedreport51e() {} -const int32_t Wheelspeedreport51e::ID = 0x51E; - -void Wheelspeedreport51e::Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const { - chassis->mutable_wheelspeed_report_51e()->set_rr( - rr(bytes, length)); - chassis->mutable_wheelspeed_report_51e()->set_rl( - rl(bytes, length)); - chassis->mutable_wheelspeed_report_51e()->set_fr( - fr(bytes, length)); - chassis->mutable_wheelspeed_report_51e()->set_fl( - fl(bytes, length)); -} - -// config detail: {'bit': 48, 'description': 'wheel speed rear right', -// 'is_signed_var': True, 'len': 16, 'name': 'rr', 'offset': 0.0, 'order': -// 'intel', 'physical_range': '[-327.68|327.67]', 'physical_unit': 'm/s', -// 'precision': 0.01, 'type': 'double'} -double Wheelspeedreport51e::rr(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 6); - int32_t t = t1.get_byte(0, 8); - x <<= 8; - x |= t; - - x <<= 16; - x >>= 16; - - double ret = x * 0.010000; - return ret; -} - -// config detail: {'bit': 32, 'description': 'wheel speed rear left', -// 'is_signed_var': True, 'len': 16, 'name': 'rl', 'offset': 0.0, 'order': -// 'intel', 'physical_range': '[-327.68|327.67]', 'physical_unit': 'm/s', -// 'precision': 0.01, 'type': 'double'} -double Wheelspeedreport51e::rl(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 5); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 4); - int32_t t = t1.get_byte(0, 8); - x <<= 8; - x |= t; - - x <<= 16; - x >>= 16; - - double ret = x * 0.010000; - return ret; -} - -// config detail: {'bit': 16, 'description': 'wheel speed front right', -// 'is_signed_var': True, 'len': 16, 'name': 'fr', 'offset': 0.0, 'order': -// 'intel', 'physical_range': '[-327.68|327.67]', 'physical_unit': 'm/s', -// 'precision': 0.01, 'type': 'double'} -double Wheelspeedreport51e::fr(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 3); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 2); - int32_t t = t1.get_byte(0, 8); - x <<= 8; - x |= t; - - x <<= 16; - x >>= 16; - - double ret = x * 0.010000; - return ret; -} - -// config detail: {'bit': 0, 'description': 'wheel speed front left', -// 'is_signed_var': True, 'len': 16, 'name': 'fl', 'offset': 0.0, 'order': -// 'intel', 'physical_range': '[-327.68|327.67]', 'physical_unit': 'm/s', -// 'precision': 0.01, 'type': 'double'} -double Wheelspeedreport51e::fl(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 0); - int32_t t = t1.get_byte(0, 8); - x <<= 8; - x |= t; - - x <<= 16; - x >>= 16; - - double ret = x * 0.010000; - return ret; -} -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/protocol/wheelspeed_report_51e.h b/modules/canbus_vehicle/ch/protocol/wheelspeed_report_51e.h deleted file mode 100644 index 6c3754617ee..00000000000 --- a/modules/canbus_vehicle/ch/protocol/wheelspeed_report_51e.h +++ /dev/null @@ -1,62 +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 "modules/canbus_vehicle/ch/proto/ch.pb.h" -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace ch { - -class Wheelspeedreport51e : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Ch> { - public: - static const int32_t ID; - Wheelspeedreport51e(); - void Parse(const std::uint8_t* bytes, int32_t length, - Ch* chassis) const override; - - private: - // config detail: {'bit': 48, 'description': 'wheel speed rear right', - // 'is_signed_var': True, 'len': 16, 'name': 'RR', 'offset': 0.0, 'order': - // 'intel', 'physical_range': '[-327.68|327.67]', 'physical_unit': 'm/s', - // 'precision': 0.01, 'type': 'double'} - double rr(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 32, 'description': 'wheel speed rear left', - // 'is_signed_var': True, 'len': 16, 'name': 'RL', 'offset': 0.0, 'order': - // 'intel', 'physical_range': '[-327.68|327.67]', 'physical_unit': 'm/s', - // 'precision': 0.01, 'type': 'double'} - double rl(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 16, 'description': 'wheel speed front right', - // 'is_signed_var': True, 'len': 16, 'name': 'FR', 'offset': 0.0, 'order': - // 'intel', 'physical_range': '[-327.68|327.67]', 'physical_unit': 'm/s', - // 'precision': 0.01, 'type': 'double'} - double fr(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 0, 'description': 'wheel speed front left', - // 'is_signed_var': True, 'len': 16, 'name': 'FL', 'offset': 0.0, 'order': - // 'intel', 'physical_range': '[-327.68|327.67]', 'physical_unit': 'm/s', - // 'precision': 0.01, 'type': 'double'} - double fl(const std::uint8_t* bytes, const int32_t length) const; -}; - -} // namespace ch -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ch/testdata/ch_canbus_conf_test.pb.txt b/modules/canbus_vehicle/ch/testdata/ch_canbus_conf_test.pb.txt deleted file mode 100644 index 6fe29139476..00000000000 --- a/modules/canbus_vehicle/ch/testdata/ch_canbus_conf_test.pb.txt +++ /dev/null @@ -1,15 +0,0 @@ -vehicle_parameter { - brand: CH - max_enable_fail_attempt: 5 - driving_mode: COMPLETE_AUTO_DRIVE -} - -can_card_parameter { - brand: SOCKET_CAN_RAW - type: PCI_CARD - channel_id: CHANNEL_ID_ZERO -} - -enable_debug_mode: true -enable_receiver_log: true -enable_sender_log: false diff --git a/modules/canbus_vehicle/devkit/BUILD b/modules/canbus_vehicle/devkit/BUILD deleted file mode 100755 index d83f9d58800..00000000000 --- a/modules/canbus_vehicle/devkit/BUILD +++ /dev/null @@ -1,164 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "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"]) - -CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] - -cc_library( - name = "devkit_vehicle_factory", - srcs = [ - "devkit_vehicle_factory.cc", - ], - hdrs = [ - "devkit_vehicle_factory.h", - ], - copts = CANBUS_COPTS, - alwayslink = True, - deps = [ - ":devkit_controller", - ":devkit_message_manager", - "//modules/canbus/common:canbus_gflags", - "//modules/common/adapters:adapter_gflags", - "//modules/common/status", - "//modules/canbus/vehicle:abstract_vehicle_factory", - "//modules/drivers/canbus:sensor_canbus_lib", - ], -) - -cc_binary( - name = "libdevkit_vehicle_factory_lib.so", - linkshared = True, - linkstatic = True, - deps = [":devkit_vehicle_factory"], -) - -cc_test( - name = "devkit_vehicle_factory_test", - size = "small", - srcs = ["devkit_vehicle_factory_test.cc"], - linkstatic = True, - deps = [ - ":devkit_vehicle_factory", - "@com_google_googletest//:gtest_main", - ], -) - -cc_library( - name = "devkit_message_manager", - srcs = ["devkit_message_manager.cc"], - hdrs = ["devkit_message_manager.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_test( - name = "devkit_message_manager_test", - size = "small", - srcs = ["devkit_message_manager_test.cc"], - deps = [ - ":devkit_message_manager", - "@com_google_googletest//:gtest_main", - ], -) - -cc_library( - name = "devkit_controller", - srcs = ["devkit_controller.cc"], - hdrs = ["devkit_controller.h"], - copts = CANBUS_COPTS, - deps = [ - ":devkit_message_manager", - "//modules/canbus/common:canbus_gflags", - "//modules/canbus/proto:canbus_conf_cc_proto", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", - "//modules/canbus/proto:vehicle_parameter_cc_proto", - "//modules/canbus/vehicle:vehicle_controller_base", - "//modules/canbus_vehicle/devkit/protocol:canbus_devkit_protocol", - "//modules/common_msgs/basic_msgs:error_code_cc_proto", - "//modules/common_msgs/control_msgs:control_cmd_cc_proto", - ], -) - -cc_test( - name = "devkit_controller_test", - size = "small", - srcs = ["devkit_controller_test.cc"], - data = ["//modules/canbus:test_data"], - deps = [ - ":devkit_controller", - "@com_google_googletest//:gtest_main", - ], -) - -install( - name = "install", - library_dest = "canbus-vehicle-devkit/lib", - data_dest = "canbus-vehicle-devkit", - data = [ - ":runtime_data", - ":cyberfile.xml", - ":canbus-vehicle-devkit.BUILD", - ], - targets = [ - ":libdevkit_vehicle_factory_lib.so", - ], - deps = [ - ":pb_devkit", - ":pb_hdrs", - ], -) - -install( - name = "pb_hdrs", - data_dest = "canbus-vehicle-devkit/include", - data = [ - "//modules/canbus_vehicle/devkit/proto:devkit_cc_proto", - ], -) - -install_files( - name = "pb_devkit", - dest = "canbus-vehicle-devkit", - files = [ - "//modules/canbus_vehicle/devkit/proto:devkit_py_pb2", - ], -) - -filegroup( - name = "runtime_data", - srcs = glob([ - "testdata/**", - ]), -) - -install_src_files( - name = "install_src", - deps = [ - ":install_devkit_src", - ":install_devkit_hdrs" - ], -) - -install_src_files( - name = "install_devkit_src", - src_dir = ["."], - dest = "canbus-vehicle-devkit/src", - filter = "*", -) - -install_src_files( - name = "install_devkit_hdrs", - src_dir = ["."], - dest = "canbus-vehicle-devkit/include", - filter = "*.h", -) - -cpplint() diff --git a/modules/canbus_vehicle/devkit/canbus-vehicle-devkit.BUILD b/modules/canbus_vehicle/devkit/canbus-vehicle-devkit.BUILD deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/modules/canbus_vehicle/devkit/cyberfile.xml b/modules/canbus_vehicle/devkit/cyberfile.xml deleted file mode 100644 index e89490a477d..00000000000 --- a/modules/canbus_vehicle/devkit/cyberfile.xml +++ /dev/null @@ -1,24 +0,0 @@ - - canbus-vehicle-devkit - local - - Dynamic loading for canbus devkit vehicle module - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/canbus_vehicle/devkit - - cyber-dev - common-dev - canbus-dev - common-msgs-dev - drivers-dev - 3rd-gtest-dev - - \ No newline at end of file diff --git a/modules/canbus_vehicle/devkit/devkit_vehicle_factory.cc b/modules/canbus_vehicle/devkit/devkit_vehicle_factory.cc deleted file mode 100755 index 1f6455b925f..00000000000 --- a/modules/canbus_vehicle/devkit/devkit_vehicle_factory.cc +++ /dev/null @@ -1,165 +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/canbus_vehicle/devkit/devkit_vehicle_factory.h" - -#include "cyber/common/log.h" -#include "modules/canbus/common/canbus_gflags.h" -#include "modules/canbus_vehicle/devkit/devkit_controller.h" -#include "modules/canbus_vehicle/devkit/devkit_message_manager.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common/util/util.h" -#include "modules/drivers/canbus/can_client/can_client_factory.h" - -using apollo::common::ErrorCode; -using apollo::control::ControlCommand; -using apollo::drivers::canbus::CanClientFactory; - -namespace apollo { -namespace canbus { - -bool DevkitVehicleFactory::Init(const CanbusConf *canbus_conf) { - // Init can client - auto can_factory = CanClientFactory::Instance(); - can_factory->RegisterCanClients(); - can_client_ = can_factory->CreateCANClient(canbus_conf->can_card_parameter()); - if (!can_client_) { - AERROR << "Failed to create can client."; - return false; - } - AINFO << "Can client is successfully created."; - - message_manager_ = this->CreateMessageManager(); - if (message_manager_ == nullptr) { - AERROR << "Failed to create message manager."; - return false; - } - AINFO << "Message manager is successfully created."; - - if (can_receiver_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_receiver_log()) != ErrorCode::OK) { - AERROR << "Failed to init can receiver."; - return false; - } - AINFO << "The can receiver is successfully initialized."; - - if (can_sender_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_sender_log()) != ErrorCode::OK) { - AERROR << "Failed to init can sender."; - return false; - } - AINFO << "The can sender is successfully initialized."; - - vehicle_controller_ = CreateVehicleController(); - if (vehicle_controller_ == nullptr) { - AERROR << "Failed to create vehicle controller."; - return false; - } - AINFO << "The vehicle controller is successfully created."; - - if (vehicle_controller_->Init(canbus_conf->vehicle_parameter(), &can_sender_, - message_manager_.get()) != ErrorCode::OK) { - AERROR << "Failed to init vehicle controller."; - return false; - } - - AINFO << "The vehicle controller is successfully" - << " initialized with canbus conf as : " - << canbus_conf->vehicle_parameter().ShortDebugString(); - - node_ = ::apollo::cyber::CreateNode("chassis_detail"); - - chassis_detail_writer_ = - node_->CreateWriter<::apollo::canbus::Devkit>(FLAGS_chassis_detail_topic); - - return true; -} - -bool DevkitVehicleFactory::Start() { - // 1. init and start the can card hardware - if (can_client_->Start() != ErrorCode::OK) { - AERROR << "Failed to start can client"; - return false; - } - AINFO << "Can client is started."; - - // 2. start receive first then send - if (can_receiver_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can receiver."; - return false; - } - AINFO << "Can receiver is started."; - - // 3. start send - if (can_sender_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can sender."; - return false; - } - - // 4. start controller - if (!vehicle_controller_->Start()) { - AERROR << "Failed to start vehicle controller."; - return false; - } - - return true; -} - -void DevkitVehicleFactory::Stop() { - can_sender_.Stop(); - can_receiver_.Stop(); - can_client_->Stop(); - vehicle_controller_->Stop(); - AINFO << "Cleanup cansender, canreceiver, canclient, vehicle controller."; -} - -void DevkitVehicleFactory::UpdateCommand( - const apollo::control::ControlCommand *control_command) { - if (vehicle_controller_->Update(*control_command) != ErrorCode::OK) { - AERROR << "Failed to process callback function OnControlCommand because " - "vehicle_controller_->Update error."; - return; - } - can_sender_.Update(); -} - -Chassis DevkitVehicleFactory::publish_chassis() { - Chassis chassis = vehicle_controller_->chassis(); - ADEBUG << chassis.ShortDebugString(); - return chassis; -} - -void DevkitVehicleFactory::PublishChassisDetail() { - Devkit chassis_detail; - message_manager_->GetSensorData(&chassis_detail); - ADEBUG << chassis_detail.ShortDebugString(); - chassis_detail_writer_->Write(chassis_detail); -} - -std::unique_ptr> -DevkitVehicleFactory::CreateVehicleController() { - return std::unique_ptr>( - new devkit::DevkitController()); -} - -std::unique_ptr> -DevkitVehicleFactory::CreateMessageManager() { - return std::unique_ptr>( - new devkit::DevkitMessageManager()); -} - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/devkit_vehicle_factory.h b/modules/canbus_vehicle/devkit/devkit_vehicle_factory.h deleted file mode 100755 index ad84e44b132..00000000000 --- a/modules/canbus_vehicle/devkit/devkit_vehicle_factory.h +++ /dev/null @@ -1,123 +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 devkit_vehicle_factory.h - */ - -#pragma once - -#include - -#include "modules/canbus/proto/canbus_conf.pb.h" -#include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "modules/canbus_vehicle/devkit/proto/devkit.pb.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -#include "cyber/cyber.h" -#include "modules/canbus/vehicle/abstract_vehicle_factory.h" -#include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/common/status/status.h" -#include "modules/drivers/canbus/can_client/can_client.h" -#include "modules/drivers/canbus/can_comm/can_receiver.h" -#include "modules/drivers/canbus/can_comm/can_sender.h" -#include "modules/drivers/canbus/can_comm/message_manager.h" - -/** - * @namespace apollo::canbus - * @brief apollo::canbus - */ -namespace apollo { -namespace canbus { - -/** - * @class DevkitVehicleFactory - * - * @brief this class is inherited from AbstractVehicleFactory. It can be used to - * create controller and message manager for devkit vehicle. - */ -class DevkitVehicleFactory : public AbstractVehicleFactory { - public: - /** - * @brief destructor - */ - virtual ~DevkitVehicleFactory() = default; - - /** - * @brief init vehicle factory - * @returns true if successfully initialized - */ - bool Init(const CanbusConf *canbus_conf) override; - - /** - * @brief start canclient, cansender, canreceiver, vehicle controller - * @returns true if successfully started - */ - bool Start() override; - - /** - * @brief create ch vehicle controller - * @returns a unique_ptr that points to the created controller - */ - void Stop() override; - - /** - * @brief update control command - */ - void UpdateCommand( - const apollo::control::ControlCommand *control_command) override; - - /** - * @brief publish chassis messages - */ - Chassis publish_chassis() override; - - /** - * @brief publish chassis for vehicle messages - */ - void PublishChassisDetail() override; - - private: - /** - * @brief create devkit vehicle controller - * @returns a unique_ptr that points to the created controller - */ - std::unique_ptr> - CreateVehicleController(); - - /** - * @brief create devkit message manager - * @returns a unique_ptr that points to the created message manager - */ - std::unique_ptr> - CreateMessageManager(); - - std::unique_ptr<::apollo::cyber::Node> node_ = nullptr; - std::unique_ptr can_client_; - CanSender<::apollo::canbus::Devkit> can_sender_; - apollo::drivers::canbus::CanReceiver<::apollo::canbus::Devkit> can_receiver_; - std::unique_ptr> message_manager_; - std::unique_ptr> - vehicle_controller_; - - std::shared_ptr<::apollo::cyber::Writer<::apollo::canbus::Devkit>> - chassis_detail_writer_; -}; - -CYBER_REGISTER_VEHICLEFACTORY(DevkitVehicleFactory) - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/proto/BUILD b/modules/canbus_vehicle/devkit/proto/BUILD deleted file mode 100644 index 11597845d89..00000000000 --- a/modules/canbus_vehicle/devkit/proto/BUILD +++ /dev/null @@ -1,25 +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") - -package(default_visibility = ["//visibility:public"]) - -cc_proto_library( - name = "devkit_cc_proto", - deps = [ - ":devkit_proto", - ], -) - -proto_library( - name = "devkit_proto", - srcs = ["devkit.proto"], -) - -py_proto_library( - name = "devkit_py_pb2", - deps = [ - ":devkit_proto", - ], -) \ No newline at end of file diff --git a/modules/canbus_vehicle/devkit/protocol/bms_report_512.cc b/modules/canbus_vehicle/devkit/protocol/bms_report_512.cc deleted file mode 100644 index 044347ce853..00000000000 --- a/modules/canbus_vehicle/devkit/protocol/bms_report_512.cc +++ /dev/null @@ -1,145 +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/canbus_vehicle/devkit/protocol/bms_report_512.h" - -#include "glog/logging.h" - -#include "modules/drivers/canbus/common/byte.h" -#include "modules/drivers/canbus/common/canbus_consts.h" - -namespace apollo { -namespace canbus { -namespace devkit { - -using ::apollo::drivers::canbus::Byte; - -Bmsreport512::Bmsreport512() {} -const int32_t Bmsreport512::ID = 0x512; - -void Bmsreport512::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_bms_report_512()->set_battery_current( - battery_current(bytes, length)); - chassis->mutable_bms_report_512()->set_battery_voltage( - battery_voltage(bytes, length)); - chassis->mutable_bms_report_512()->set_battery_soc_percentage( - battery_soc_percentage(bytes, length)); - chassis->mutable_bms_report_512()->set_is_battery_soc_low( - battery_soc_percentage(bytes, length) <= 15); - chassis->mutable_bms_report_512()->set_battery_inside_temperature( - battery_inside_temperature(bytes, length)); - chassis->mutable_bms_report_512()->set_battery_flt_low_temp( - battery_flt_low_temp(bytes, length)); - chassis->mutable_bms_report_512()->set_battery_flt_over_temp( - battery_flt_over_temp(bytes, length)); -} - -// config detail: {'bit': 23, 'description': 'Battery Total Current', -// 'is_signed_var': False, 'len': 16, 'name': 'battery_current', 'offset': -// -3200.0, 'order': 'motorola', 'physical_range': '[-3200|3200]', -// 'physical_unit': 'A', 'precision': 0.1, 'type': 'double'} -double Bmsreport512::battery_current(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 2); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 3); - int32_t t = t1.get_byte(0, 8); - x <<= 8; - x |= t; - - double ret = x * 0.100000 + -3200.000000; - return ret; -} - -// config detail: {'bit': 7, 'description': 'Battery Total Voltage', -// 'is_signed_var': False, 'len': 16, 'name': 'battery_voltage', 'offset': 0.0, -// 'order': 'motorola', 'physical_range': '[0|300]', 'physical_unit': 'V', -// 'precision': 0.01, 'type': 'double'} -double Bmsreport512::battery_voltage(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 1); - int32_t t = t1.get_byte(0, 8); - x <<= 8; - x |= t; - - double ret = x * 0.010000; - return ret; -} - -// config detail: {'bit': 39, 'description': 'Battery Soc percentage', -// 'is_signed_var': False, 'len': 8, 'name': 'battery_soc_percentage', 'offset': -// 0.0, 'order': 'motorola', 'physical_range': '[0|100]', 'physical_unit': '%', -// 'precision': 1.0, 'type': 'int'} -int Bmsreport512::battery_soc_percentage(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 4); - int32_t x = t0.get_byte(0, 8); - - int ret = x; - return ret; -} - -// config detail: {'bit': 40, 'description': 'Battery Inside temperature', -// 'is_signed_var': False, 'len': 1, 'name': 'Battery_Inside_Temperature', -// 'offset': -40, 'order': 'motorola', 'physical_range': '[-40|215]', -// 'physical_unit': 'C', 'precision': 1.0, 'type': 'int'} -int Bmsreport512::battery_inside_temperature(const std::uint8_t* bytes, - const int32_t length) const { - Byte t0(bytes + 5); - int32_t x = t0.get_byte(0, 8); - - int ret = x - 40; - return ret; -} - -// config detail: {'description': 'Battery Below Low temp fault', 'enum': -// {0: 'BATTERY_FLT_LOW_TEMP_NO_FAULT', 1: -// 'BATTERY_FLT_LOW_TEMP_FAULT'}, 'precision': 1.0, 'len': 1, -// 'name': 'Brake_FLT2', 'is_signed_var': False, 'offset': 0.0, -// 'physical_range': '[0|1]', 'bit': 48, 'type': 'enum', 'order': 'motorola', -// 'physical_unit': ''} -Bms_report_512::Battery_flt_lowtempType Bmsreport512::battery_flt_low_temp( - const std::uint8_t* bytes, const int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(0, 1); - - Bms_report_512::Battery_flt_lowtempType ret = - static_cast(x); - return ret; -} -// config detail: {'description': 'Battery Over High Temp fault', 'enum': -// {0: 'BATTERY_FLT_OVER_TEMP_NO_FAULT', 1: -// 'BATTERY_FLT_OVER_TEMP_FAULT'}, 'precision': 1.0, 'len': 1, -// 'name': 'Brake_FLT2', 'is_signed_var': False, 'offset': 0.0, -// 'physical_range': '[0|1]', 'bit': 49, 'type': 'enum', 'order': 'motorola', -// 'physical_unit': ''} -Bms_report_512::Battery_flt_overtempType Bmsreport512::battery_flt_over_temp( - const std::uint8_t* bytes, const int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(1, 1); - - Bms_report_512::Battery_flt_overtempType ret = - static_cast(x); - return ret; -} -} // namespace devkit -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/vcu_report_505.cc b/modules/canbus_vehicle/devkit/protocol/vcu_report_505.cc deleted file mode 100755 index b33aa1d1c2f..00000000000 --- a/modules/canbus_vehicle/devkit/protocol/vcu_report_505.cc +++ /dev/null @@ -1,249 +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/canbus_vehicle/devkit/protocol/vcu_report_505.h" - -#include "glog/logging.h" - -#include "modules/drivers/canbus/common/byte.h" -#include "modules/drivers/canbus/common/canbus_consts.h" - -namespace apollo { -namespace canbus { -namespace devkit { - -using ::apollo::drivers::canbus::Byte; - -Vcureport505::Vcureport505() {} -const int32_t Vcureport505::ID = 0x505; - -void Vcureport505::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_vcu_report_505()->set_steer_mode_sts( - steer_mode_sts(bytes, length)); - chassis->mutable_vcu_report_505()->set_brake_light_actual( - brake_light_actual(bytes, length)); - chassis->mutable_vcu_report_505()->set_acc( - acc(bytes, length)); - chassis->mutable_vcu_report_505()->set_speed( - speed(bytes, length)); - chassis->mutable_vcu_report_505()->set_aeb_brake_state( - aeb_brake_state(bytes, length)); - chassis->mutable_vcu_report_505()->set_frontcrash_state( - frontcrash_state(bytes, length)); - chassis->mutable_vcu_report_505()->set_backcrash_state( - backcrash_state(bytes, length)); - chassis->mutable_vcu_report_505()->set_vehicle_mode_state( - vehicle_mode_state(bytes, length)); - chassis->mutable_vcu_report_505()->set_drive_mode_sts( - drive_mode_sts(bytes, length)); - chassis->mutable_vcu_report_505()->set_chassis_errcode( - chassis_errcode(bytes, length)); - chassis->mutable_vcu_report_505()->set_turn_light_actual( - turn_light_actual(bytes, length)); - chassis->mutable_vcu_report_505()->set_aeb_mode( - aeb_mode(bytes, length)); -} - -// config detail: {'bit': 10, 'enum': {0: 'STEER_MODE_STS_STANDARD_STEER_MODE', -// 1: 'STEER_MODE_STS_NON_DIRECTION_STEER_MODE', 2: -// 'STEER_MODE_STS_SYNC_DIRECTION_STEER_MODE'}, 'is_signed_var': False, 'len': -// 3, 'name': 'steer_mode_sts', 'offset': 0.0, 'order': 'motorola', -// 'physical_range': '[0|7]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'enum'} -Vcu_report_505::Steer_mode_stsType Vcureport505::steer_mode_sts( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 3); - - Vcu_report_505::Steer_mode_stsType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 11, 'enum': {0: 'BRAKE_LIGHT_ACTUAL_BRAKELIGHT_OFF', -// 1: 'BRAKE_LIGHT_ACTUAL_BRAKELIGHT_ON'}, 'is_signed_var': False, 'len': 1, -// 'name': 'brake_light_actual', 'offset': 0.0, 'order': 'motorola', -// 'physical_range': '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'enum'} -Vcu_report_505::Brake_light_actualType Vcureport505::brake_light_actual( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(3, 1); - - Vcu_report_505::Brake_light_actualType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 7, 'is_signed_var': True, 'len': 12, 'name': 'acc', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[-10|10]', -// 'physical_unit': 'm/s^2', 'precision': 0.01, 'type': 'double'} -double Vcureport505::acc(const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 1); - int32_t t = t1.get_byte(4, 4); - x <<= 4; - x |= t; - - x <<= 20; - x >>= 20; - - double ret = x * 0.010000; - return ret; -} - -// config detail: {'bit': 23, 'is_signed_var': True, 'len': 16, 'name': 'speed', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[-32.768|32.767]', -// 'physical_unit': 'm/s', 'precision': 0.001, 'type': 'double'} -double Vcureport505::speed(const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 2); - int32_t x = t0.get_byte(0, 8); - - Byte t1(bytes + 3); - int32_t t = t1.get_byte(0, 8); - x <<= 8; - x |= t; - - x <<= 16; - x >>= 16; - - double ret = x * 0.001000; - return ret; -} - -// config detail: {'bit': 32, 'description': 'describle the vehicle AEB mode -// whether was set', 'enum': {0: 'AEB_BRAKE_STATE_INACTIVE', 1: -// 'AEB_BRAKE_STATE_ACTIVE'}, 'is_signed_var': False, 'len': 1, 'name': -// 'aeb_brake_state', 'offset': 0.0, 'order': 'motorola', 'physical_range': -// '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Vcu_report_505::Aeb_brake_stateType Vcureport505::aeb_brake_state( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 4); - int32_t x = t0.get_byte(0, 1); - - Vcu_report_505::Aeb_brake_stateType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 33, 'enum': {0: 'FRONTCRASH_STATE_NO_EVENT', 1: -// 'FRONTCRASH_STATE_CRASH_EVENT'}, 'is_signed_var': False, 'len': 1, 'name': -// 'frontcrash_state', 'offset': 0.0, 'order': 'motorola', 'physical_range': -// '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Vcu_report_505::Frontcrash_stateType Vcureport505::frontcrash_state( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 4); - int32_t x = t0.get_byte(1, 1); - - Vcu_report_505::Frontcrash_stateType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 34, 'enum': {0: 'BACKCRASH_STATE_NO_EVENT', 1: -// 'BACKCRASH_STATE_CRASH_EVENT'}, 'is_signed_var': False, 'len': 1, 'name': -// 'backcrash_state', 'offset': 0.0, 'order': 'motorola', 'physical_range': -// '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Vcu_report_505::Backcrash_stateType Vcureport505::backcrash_state( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 4); - int32_t x = t0.get_byte(2, 1); - - Vcu_report_505::Backcrash_stateType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 36, 'enum': {0: -// 'VEHICLE_MODE_STATE_MANUAL_REMOTE_MODE', 1: 'VEHICLE_MODE_STATE_AUTO_MODE', -// 2: 'VEHICLE_MODE_STATE_EMERGENCY_MODE', 3: -// 'VEHICLE_MODE_STATE_STANDBY_MODE'}, 'is_signed_var': False, 'len': 2, 'name': -// 'vehicle_mode_state', 'offset': 0.0, 'order': 'motorola', 'physical_range': -// '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Vcu_report_505::Vehicle_mode_stateType Vcureport505::vehicle_mode_state( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 4); - int32_t x = t0.get_byte(3, 2); - - Vcu_report_505::Vehicle_mode_stateType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 39, 'enum': {0: -// 'DRIVE_MODE_STS_THROTTLE_PADDLE_DRIVE_MODE', 1: -// 'DRIVE_MODE_STS_SPEED_DRIVE_MODE'}, 'is_signed_var': False, 'len': 3, 'name': -// 'drive_mode_sts', 'offset': 0.0, 'order': 'motorola', 'physical_range': -// '[0|7]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Vcu_report_505::Drive_mode_stsType Vcureport505::drive_mode_sts( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 4); - int32_t x = t0.get_byte(5, 3); - - Vcu_report_505::Drive_mode_stsType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 47, 'is_signed_var': False, 'len': 8, 'name': -// 'chassis_errcode', 'offset': 0.0, 'order': 'motorola', 'physical_range': -// '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -int Vcureport505::chassis_errcode(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 5); - int32_t x = t0.get_byte(0, 8); - - int ret = x; - return ret; -} - -// config detail: {'bit': 57, 'enum': {0: 'TURN_LIGHT_ACTUAL_TURNLAMPSTS_OFF', -// 1: 'TURN_LIGHT_ACTUAL_LEFT_TURNLAMPSTS_ON', 2: -// 'TURN_LIGHT_ACTUAL_RIGHT_TURNLAMPSTS_ON', 3: -// 'TURN_LIGHT_ACTUAL_HAZARD_WARNING_LAMPSTS_ON'}, 'is_signed_var': False, -// 'len': 2, 'name': 'turn_light_actual', 'offset': 0.0, 'order': 'motorola', -// 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'enum'} -Vcu_report_505::Turn_light_actualType Vcureport505::turn_light_actual( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 2); - - Vcu_report_505::Turn_light_actualType ret = - static_cast(x); - return ret; -} - -// config detail: {'bit': 58, 'description': 'describe the vehicle e-brake -// command whether was triggered by AEB', 'enum': {0: 'AEB_MODE_DISABLE', 1: -// 'AEB_MODE_ENABLE'}, 'is_signed_var': False, 'len': 1, 'name': 'aeb_mode', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|1]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -Vcu_report_505::Aeb_modeType Vcureport505::aeb_mode(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(2, 1); - - Vcu_report_505::Aeb_modeType ret = - static_cast(x); - return ret; -} -} // namespace devkit -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/vcu_report_505.h b/modules/canbus_vehicle/devkit/protocol/vcu_report_505.h deleted file mode 100755 index a52cd08ad60..00000000000 --- a/modules/canbus_vehicle/devkit/protocol/vcu_report_505.h +++ /dev/null @@ -1,132 +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 "modules/canbus_vehicle/devkit/proto/devkit.pb.h" - -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace devkit { - -class Vcureport505 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { - public: - static const int32_t ID; - Vcureport505(); - void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; - - private: - // config detail: {'bit': 10, 'enum': {0: - // 'STEER_MODE_STS_STANDARD_STEER_MODE', 1: - // 'STEER_MODE_STS_NON_DIRECTION_STEER_MODE', 2: - // 'STEER_MODE_STS_SYNC_DIRECTION_STEER_MODE'}, 'is_signed_var': False, 'len': - // 3, 'name': 'Steer_Mode_STS', 'offset': 0.0, 'order': 'motorola', - // 'physical_range': '[0|7]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - Vcu_report_505::Steer_mode_stsType steer_mode_sts(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 11, 'enum': {0: 'BRAKE_LIGHT_ACTUAL_BRAKELIGHT_OFF', - // 1: 'BRAKE_LIGHT_ACTUAL_BRAKELIGHT_ON'}, 'is_signed_var': False, 'len': 1, - // 'name': 'Brake_Light_Actual', 'offset': 0.0, 'order': 'motorola', - // 'physical_range': '[0|1]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - Vcu_report_505::Brake_light_actualType brake_light_actual( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 7, 'is_signed_var': True, 'len': 12, 'name': 'ACC', - // 'offset': 0.0, 'order': 'motorola', 'physical_range': '[-10|10]', - // 'physical_unit': 'm/s^2', 'precision': 0.01, 'type': 'double'} - double acc(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 23, 'is_signed_var': True, 'len': 16, 'name': - // 'SPEED', 'offset': 0.0, 'order': 'motorola', 'physical_range': - // '[-32.768|32.767]', 'physical_unit': 'm/s', 'precision': 0.001, 'type': - // 'double'} - double speed(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 32, 'description': 'describle the vehicle AEB mode - // whether was set', 'enum': {0: 'AEB_BRAKE_STATE_INACTIVE', 1: - // 'AEB_BRAKE_STATE_ACTIVE'}, 'is_signed_var': False, 'len': 1, 'name': - // 'AEB_Brake_State', 'offset': 0.0, 'order': 'motorola', 'physical_range': - // '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Vcu_report_505::Aeb_brake_stateType aeb_brake_state( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 33, 'enum': {0: 'FRONTCRASH_STATE_NO_EVENT', 1: - // 'FRONTCRASH_STATE_CRASH_EVENT'}, 'is_signed_var': False, 'len': 1, 'name': - // 'FrontCrash_State', 'offset': 0.0, 'order': 'motorola', 'physical_range': - // '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Vcu_report_505::Frontcrash_stateType frontcrash_state( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 34, 'enum': {0: 'BACKCRASH_STATE_NO_EVENT', 1: - // 'BACKCRASH_STATE_CRASH_EVENT'}, 'is_signed_var': False, 'len': 1, 'name': - // 'BackCrash_State', 'offset': 0.0, 'order': 'motorola', 'physical_range': - // '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Vcu_report_505::Backcrash_stateType backcrash_state( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 36, 'enum': {0: - // 'VEHICLE_MODE_STATE_MANUAL_REMOTE_MODE', 1: 'VEHICLE_MODE_STATE_AUTO_MODE', - // 2: 'VEHICLE_MODE_STATE_EMERGENCY_MODE', 3: - // 'VEHICLE_MODE_STATE_STANDBY_MODE'}, 'is_signed_var': False, 'len': 2, - // 'name': 'Vehicle_Mode_State', 'offset': 0.0, 'order': 'motorola', - // 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - Vcu_report_505::Vehicle_mode_stateType vehicle_mode_state( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 39, 'enum': {0: - // 'DRIVE_MODE_STS_THROTTLE_PADDLE_DRIVE_MODE', 1: - // 'DRIVE_MODE_STS_SPEED_DRIVE_MODE'}, 'is_signed_var': False, 'len': 3, - // 'name': 'Drive_Mode_STS', 'offset': 0.0, 'order': 'motorola', - // 'physical_range': '[0|7]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - Vcu_report_505::Drive_mode_stsType drive_mode_sts(const std::uint8_t* bytes, - const int32_t length) const; - - // config detail: {'bit': 47, 'is_signed_var': False, 'len': 8, 'name': - // 'Chassis_errcode', 'offset': 0.0, 'order': 'motorola', 'physical_range': - // '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - int chassis_errcode(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 57, 'enum': {0: 'TURN_LIGHT_ACTUAL_TURNLAMPSTS_OFF', - // 1: 'TURN_LIGHT_ACTUAL_LEFT_TURNLAMPSTS_ON', 2: - // 'TURN_LIGHT_ACTUAL_RIGHT_TURNLAMPSTS_ON', 3: - // 'TURN_LIGHT_ACTUAL_HAZARD_WARNING_LAMPSTS_ON'}, 'is_signed_var': False, - // 'len': 2, 'name': 'Turn_Light_Actual', 'offset': 0.0, 'order': 'motorola', - // 'physical_range': '[0|0]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - Vcu_report_505::Turn_light_actualType turn_light_actual( - const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 58, 'description': 'describe the vehicle e-brake - // command whether was triggered by AEB', 'enum': {0: 'AEB_MODE_DISABLE', 1: - // 'AEB_MODE_ENABLE'}, 'is_signed_var': False, 'len': 1, 'name': 'AEB_Mode', - // 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|1]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Vcu_report_505::Aeb_modeType aeb_mode(const std::uint8_t* bytes, - const int32_t length) const; -}; - -} // namespace devkit -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/vehicle_mode_command_105.cc b/modules/canbus_vehicle/devkit/protocol/vehicle_mode_command_105.cc deleted file mode 100644 index b794f8b5736..00000000000 --- a/modules/canbus_vehicle/devkit/protocol/vehicle_mode_command_105.cc +++ /dev/null @@ -1,224 +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/canbus_vehicle/devkit/protocol/vehicle_mode_command_105.h" - -#include "modules/drivers/canbus/common/byte.h" - -namespace apollo { -namespace canbus { -namespace devkit { - -using ::apollo::drivers::canbus::Byte; - -const int32_t Vehiclemodecommand105::ID = 0x105; - -// public -Vehiclemodecommand105::Vehiclemodecommand105() { Reset(); } - -uint32_t Vehiclemodecommand105::GetPeriod() const { - // TODO(All) : modify every protocol's period manually - static const uint32_t PERIOD = 20 * 1000; - return PERIOD; -} - -void Vehiclemodecommand105::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_vehicle_mode_command_105()->set_turn_light_ctrl( - turn_light_ctrl(bytes, length)); - chassis->mutable_vehicle_mode_command_105()->set_vin_req( - vin_req(bytes, length)); - chassis->mutable_vehicle_mode_command_105()->set_drive_mode_ctrl( - drive_mode_ctrl(bytes, length)); - chassis->mutable_vehicle_mode_command_105()->set_steer_mode_ctrl( - steer_mode_ctrl(bytes, length)); - chassis->mutable_vehicle_mode_command_105()->set_checksum_105( - checksum_105(bytes, length)); -} - -void Vehiclemodecommand105::UpdateData(uint8_t* data) { - set_p_turn_light_ctrl(data, turn_light_ctrl_); - set_p_vin_req(data, vin_req_); - set_p_drive_mode_ctrl(data, drive_mode_ctrl_); - set_p_steer_mode_ctrl(data, steer_mode_ctrl_); - checksum_105_ = - data[0] ^ data[1] ^ data[2] ^ data[3] ^ data[4] ^ data[5] ^ data[6]; - set_p_checksum_105(data, checksum_105_); -} - -void Vehiclemodecommand105::Reset() { - // TODO(All) : you should check this manually - checksum_105_ = 0; - turn_light_ctrl_ = Vehicle_mode_command_105::TURN_LIGHT_CTRL_TURNLAMP_OFF; - vin_req_ = Vehicle_mode_command_105::VIN_REQ_VIN_REQ_DISABLE; - drive_mode_ctrl_ = - Vehicle_mode_command_105::DRIVE_MODE_CTRL_THROTTLE_PADDLE_DRIVE; - steer_mode_ctrl_ = Vehicle_mode_command_105::STEER_MODE_CTRL_STANDARD_STEER; -} - -Vehiclemodecommand105* Vehiclemodecommand105::set_checksum_105( - int checksum_105) { - checksum_105_ = checksum_105; - return this; -} - -// config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': -// 'CheckSum_105', 'offset': 0.0, 'order': 'motorola', 'physical_range': -// '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -void Vehiclemodecommand105::set_p_checksum_105(uint8_t* data, - int checksum_105) { - checksum_105 = ProtocolData::BoundedValue(0, 255, checksum_105); - int x = checksum_105; - - Byte to_set(data + 7); - to_set.set_value(x, 0, 8); -} - -Vehiclemodecommand105* Vehiclemodecommand105::set_turn_light_ctrl( - Vehicle_mode_command_105::Turn_light_ctrlType turn_light_ctrl) { - turn_light_ctrl_ = turn_light_ctrl; - return this; -} - -// config detail: {'bit': 17, 'enum': {0: 'TURN_LIGHT_CTRL_TURNLAMP_OFF', 1: -// 'TURN_LIGHT_CTRL_LEFT_TURNLAMP_ON', 2: 'TURN_LIGHT_CTRL_RIGHT_TURNLAMP_ON', -// 3: 'TURN_LIGHT_CTRL_HAZARD_WARNING_LAMPSTS_ON'}, 'is_signed_var': False, -// 'len': 2, 'name': 'Turn_Light_CTRL', 'offset': 0.0, 'order': 'motorola', -// 'physical_range': '[0|7]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'enum'} -void Vehiclemodecommand105::set_p_turn_light_ctrl( - uint8_t* data, - Vehicle_mode_command_105::Turn_light_ctrlType turn_light_ctrl) { - int x = turn_light_ctrl; - - Byte to_set(data + 2); - to_set.set_value(x, 0, 2); -} - -Vehiclemodecommand105* Vehiclemodecommand105::set_vin_req( - Vehicle_mode_command_105::Vin_reqType vin_req) { - vin_req_ = vin_req; - return this; -} - -// config detail: {'bit': 24, 'enum': {0: 'VIN_REQ_VIN_REQ_DISABLE', 1: -// 'VIN_REQ_VIN_REQ_ENABLE'}, 'is_signed_var': False, 'len': 1, 'name': -// 'VIN_Req', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|1]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} -void Vehiclemodecommand105::set_p_vin_req( - uint8_t* data, Vehicle_mode_command_105::Vin_reqType vin_req) { - int x = vin_req; - - Byte to_set(data + 3); - to_set.set_value(x, 0, 1); -} - -Vehiclemodecommand105* Vehiclemodecommand105::set_drive_mode_ctrl( - Vehicle_mode_command_105::Drive_mode_ctrlType drive_mode_ctrl) { - drive_mode_ctrl_ = drive_mode_ctrl; - return this; -} - -// config detail: {'bit': 10, 'enum': {0: -// 'DRIVE_MODE_CTRL_THROTTLE_PADDLE_DRIVE', 1: 'DRIVE_MODE_CTRL_SPEED_DRIVE'}, -// 'is_signed_var': False, 'len': 3, 'name': 'Drive_Mode_CTRL', 'offset': 0.0, -// 'order': 'motorola', 'physical_range': '[0|7]', 'physical_unit': '', -// 'precision': 1.0, 'type': 'enum'} -void Vehiclemodecommand105::set_p_drive_mode_ctrl( - uint8_t* data, - Vehicle_mode_command_105::Drive_mode_ctrlType drive_mode_ctrl) { - int x = drive_mode_ctrl; - - Byte to_set(data + 1); - to_set.set_value(x, 0, 3); -} - -Vehiclemodecommand105* Vehiclemodecommand105::set_steer_mode_ctrl( - Vehicle_mode_command_105::Steer_mode_ctrlType steer_mode_ctrl) { - steer_mode_ctrl_ = steer_mode_ctrl; - return this; -} - -// config detail: {'bit': 2, 'enum': {0: 'STEER_MODE_CTRL_STANDARD_STEER', 1: -// 'STEER_MODE_CTRL_NON_DIRECTION_STEER', 2: -// 'STEER_MODE_CTRL_SYNC_DIRECTION_STEER'}, 'is_signed_var': False, 'len': 3, -// 'name': 'Steer_Mode_CTRL', 'offset': 0.0, 'order': 'motorola', -// 'physical_range': '[0|7]', 'physical_unit': '', 'precision': 1.0, 'type': -// 'enum'} -void Vehiclemodecommand105::set_p_steer_mode_ctrl( - uint8_t* data, - Vehicle_mode_command_105::Steer_mode_ctrlType steer_mode_ctrl) { - int x = steer_mode_ctrl; - - Byte to_set(data + 0); - to_set.set_value(x, 0, 3); -} - -Vehicle_mode_command_105::Turn_light_ctrlType -Vehiclemodecommand105::turn_light_ctrl(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 2); - int32_t x = t0.get_byte(0, 2); - - Vehicle_mode_command_105::Turn_light_ctrlType ret = - static_cast(x); - return ret; -} - -Vehicle_mode_command_105::Vin_reqType Vehiclemodecommand105::vin_req( - const std::uint8_t* bytes, int32_t length) const { - Byte t0(bytes + 3); - int32_t x = t0.get_byte(0, 1); - - Vehicle_mode_command_105::Vin_reqType ret = - static_cast(x); - return ret; -} - -Vehicle_mode_command_105::Drive_mode_ctrlType -Vehiclemodecommand105::drive_mode_ctrl(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 3); - - Vehicle_mode_command_105::Drive_mode_ctrlType ret = - static_cast(x); - return ret; -} - -Vehicle_mode_command_105::Steer_mode_ctrlType -Vehiclemodecommand105::steer_mode_ctrl(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 3); - - Vehicle_mode_command_105::Steer_mode_ctrlType ret = - static_cast(x); - return ret; -} - -int Vehiclemodecommand105::checksum_105(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 8); - - int ret = x; - return ret; -} - -} // namespace devkit -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/vehicle_mode_command_105.h b/modules/canbus_vehicle/devkit/protocol/vehicle_mode_command_105.h deleted file mode 100644 index 60673d73a88..00000000000 --- a/modules/canbus_vehicle/devkit/protocol/vehicle_mode_command_105.h +++ /dev/null @@ -1,148 +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 "modules/canbus_vehicle/devkit/proto/devkit.pb.h" - -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace devkit { - -class Vehiclemodecommand105 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { - public: - static const int32_t ID; - - Vehiclemodecommand105(); - - uint32_t GetPeriod() const override; - - void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; - - void UpdateData(uint8_t* data) override; - - void Reset() override; - - // config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': - // 'CheckSum_105', 'offset': 0.0, 'order': 'motorola', 'physical_range': - // '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - Vehiclemodecommand105* set_checksum_105(int checksum_105); - - // config detail: {'bit': 17, 'enum': {0: 'TURN_LIGHT_CTRL_TURNLAMP_OFF', 1: - // 'TURN_LIGHT_CTRL_LEFT_TURNLAMP_ON', 2: 'TURN_LIGHT_CTRL_RIGHT_TURNLAMP_ON', - // 3: 'TURN_LIGHT_CTRL_HAZARD_WARNING_LAMPSTS_ON'}, 'is_signed_var': False, - // 'len': 2, 'name': 'Turn_Light_CTRL', 'offset': 0.0, 'order': 'motorola', - // 'physical_range': '[0|7]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - Vehiclemodecommand105* set_turn_light_ctrl( - Vehicle_mode_command_105::Turn_light_ctrlType turn_light_ctrl); - - // config detail: {'bit': 24, 'enum': {0: 'VIN_REQ_VIN_REQ_DISABLE', 1: - // 'VIN_REQ_VIN_REQ_ENABLE'}, 'is_signed_var': False, 'len': 1, 'name': - // 'VIN_Req', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|1]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - Vehiclemodecommand105* set_vin_req( - Vehicle_mode_command_105::Vin_reqType vin_req); - - // config detail: {'bit': 10, 'enum': {0: - // 'DRIVE_MODE_CTRL_THROTTLE_PADDLE_DRIVE', 1: 'DRIVE_MODE_CTRL_SPEED_DRIVE'}, - // 'is_signed_var': False, 'len': 3, 'name': 'Drive_Mode_CTRL', 'offset': 0.0, - // 'order': 'motorola', 'physical_range': '[0|7]', 'physical_unit': '', - // 'precision': 1.0, 'type': 'enum'} - Vehiclemodecommand105* set_drive_mode_ctrl( - Vehicle_mode_command_105::Drive_mode_ctrlType drive_mode_ctrl); - - // config detail: {'bit': 2, 'enum': {0: 'STEER_MODE_CTRL_STANDARD_STEER', 1: - // 'STEER_MODE_CTRL_NON_DIRECTION_STEER', 2: - // 'STEER_MODE_CTRL_SYNC_DIRECTION_STEER'}, 'is_signed_var': False, 'len': 3, - // 'name': 'Steer_Mode_CTRL', 'offset': 0.0, 'order': 'motorola', - // 'physical_range': '[0|7]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - Vehiclemodecommand105* set_steer_mode_ctrl( - Vehicle_mode_command_105::Steer_mode_ctrlType steer_mode_ctrl); - - private: - // config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': - // 'CheckSum_105', 'offset': 0.0, 'order': 'motorola', 'physical_range': - // '[0|255]', 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - void set_p_checksum_105(uint8_t* data, int checksum_105); - - // config detail: {'bit': 17, 'enum': {0: 'TURN_LIGHT_CTRL_TURNLAMP_OFF', 1: - // 'TURN_LIGHT_CTRL_LEFT_TURNLAMP_ON', 2: 'TURN_LIGHT_CTRL_RIGHT_TURNLAMP_ON', - // 3: 'TURN_LIGHT_CTRL_HAZARD_WARNING_LAMPSTS_ON'}, 'is_signed_var': False, - // 'len': 2, 'name': 'Turn_Light_CTRL', 'offset': 0.0, 'order': 'motorola', - // 'physical_range': '[0|7]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - void set_p_turn_light_ctrl( - uint8_t* data, - Vehicle_mode_command_105::Turn_light_ctrlType turn_light_ctrl); - - // config detail: {'bit': 24, 'enum': {0: 'VIN_REQ_VIN_REQ_DISABLE', 1: - // 'VIN_REQ_VIN_REQ_ENABLE'}, 'is_signed_var': False, 'len': 1, 'name': - // 'VIN_Req', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|1]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'enum'} - void set_p_vin_req(uint8_t* data, - Vehicle_mode_command_105::Vin_reqType vin_req); - - // config detail: {'bit': 10, 'enum': {0: - // 'DRIVE_MODE_CTRL_THROTTLE_PADDLE_DRIVE', 1: 'DRIVE_MODE_CTRL_SPEED_DRIVE'}, - // 'is_signed_var': False, 'len': 3, 'name': 'Drive_Mode_CTRL', 'offset': 0.0, - // 'order': 'motorola', 'physical_range': '[0|7]', 'physical_unit': '', - // 'precision': 1.0, 'type': 'enum'} - void set_p_drive_mode_ctrl( - uint8_t* data, - Vehicle_mode_command_105::Drive_mode_ctrlType drive_mode_ctrl); - - // config detail: {'bit': 2, 'enum': {0: 'STEER_MODE_CTRL_STANDARD_STEER', 1: - // 'STEER_MODE_CTRL_NON_DIRECTION_STEER', 2: - // 'STEER_MODE_CTRL_SYNC_DIRECTION_STEER'}, 'is_signed_var': False, 'len': 3, - // 'name': 'Steer_Mode_CTRL', 'offset': 0.0, 'order': 'motorola', - // 'physical_range': '[0|7]', 'physical_unit': '', 'precision': 1.0, 'type': - // 'enum'} - void set_p_steer_mode_ctrl( - uint8_t* data, - Vehicle_mode_command_105::Steer_mode_ctrlType steer_mode_ctrl); - - // report the command - Vehicle_mode_command_105::Turn_light_ctrlType turn_light_ctrl( - const std::uint8_t* bytes, const int32_t length) const; - - Vehicle_mode_command_105::Vin_reqType vin_req(const std::uint8_t* bytes, - const int32_t length) const; - - Vehicle_mode_command_105::Drive_mode_ctrlType drive_mode_ctrl( - const std::uint8_t* bytes, const int32_t length) const; - - Vehicle_mode_command_105::Steer_mode_ctrlType steer_mode_ctrl( - const std::uint8_t* bytes, const int32_t length) const; - - int checksum_105(const std::uint8_t* bytes, const int32_t length) const; - - private: - int checksum_105_; - Vehicle_mode_command_105::Turn_light_ctrlType turn_light_ctrl_; - Vehicle_mode_command_105::Vin_reqType vin_req_; - Vehicle_mode_command_105::Drive_mode_ctrlType drive_mode_ctrl_; - Vehicle_mode_command_105::Steer_mode_ctrlType steer_mode_ctrl_; -}; - -} // namespace devkit -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/vin_resp1_514.cc b/modules/canbus_vehicle/devkit/protocol/vin_resp1_514.cc deleted file mode 100644 index 0d4c13d3d16..00000000000 --- a/modules/canbus_vehicle/devkit/protocol/vin_resp1_514.cc +++ /dev/null @@ -1,160 +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/canbus_vehicle/devkit/protocol/vin_resp1_514.h" - -#include - -#include "glog/logging.h" - -#include "modules/drivers/canbus/common/byte.h" -#include "modules/drivers/canbus/common/canbus_consts.h" - -namespace apollo { -namespace canbus { -namespace devkit { - -using ::apollo::drivers::canbus::Byte; - -Vinresp1514::Vinresp1514() {} -const int32_t Vinresp1514::ID = 0x514; - -void Vinresp1514::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_vin_resp1_514()->set_vin07( - vin07(bytes, length)); - chassis->mutable_vin_resp1_514()->set_vin06( - vin06(bytes, length)); - chassis->mutable_vin_resp1_514()->set_vin05( - vin05(bytes, length)); - chassis->mutable_vin_resp1_514()->set_vin04( - vin04(bytes, length)); - chassis->mutable_vin_resp1_514()->set_vin03( - vin03(bytes, length)); - chassis->mutable_vin_resp1_514()->set_vin02( - vin02(bytes, length)); - chassis->mutable_vin_resp1_514()->set_vin01( - vin01(bytes, length)); - chassis->mutable_vin_resp1_514()->set_vin00( - vin00(bytes, length)); -} - -// config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': 'vin07', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp1514::vin07(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 55, 'is_signed_var': False, 'len': 8, 'name': 'vin06', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp1514::vin06(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 47, 'is_signed_var': False, 'len': 8, 'name': 'vin05', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp1514::vin05(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 5); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 39, 'is_signed_var': False, 'len': 8, 'name': 'vin04', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp1514::vin04(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 4); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 31, 'is_signed_var': False, 'len': 8, 'name': 'vin03', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp1514::vin03(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 3); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 23, 'is_signed_var': False, 'len': 8, 'name': 'vin02', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp1514::vin02(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 2); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 15, 'is_signed_var': False, 'len': 8, 'name': 'vin01', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp1514::vin01(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 7, 'is_signed_var': False, 'len': 8, 'name': 'vin00', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp1514::vin00(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} -} // namespace devkit -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/vin_resp1_514.h b/modules/canbus_vehicle/devkit/protocol/vin_resp1_514.h deleted file mode 100644 index ebdff875ef1..00000000000 --- a/modules/canbus_vehicle/devkit/protocol/vin_resp1_514.h +++ /dev/null @@ -1,81 +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 "modules/canbus_vehicle/devkit/proto/devkit.pb.h" - -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace devkit { - -class Vinresp1514 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { - public: - static const int32_t ID; - Vinresp1514(); - void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; - - private: - // config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN07', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin07(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 55, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN06', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin06(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 47, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN05', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin05(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 39, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN04', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin04(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 31, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN03', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin03(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 23, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN02', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin02(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 15, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN01', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin01(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 7, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN00', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin00(const std::uint8_t* bytes, const int32_t length) const; -}; - -} // namespace devkit -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/vin_resp2_515.cc b/modules/canbus_vehicle/devkit/protocol/vin_resp2_515.cc deleted file mode 100644 index c0f6dabef10..00000000000 --- a/modules/canbus_vehicle/devkit/protocol/vin_resp2_515.cc +++ /dev/null @@ -1,160 +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/canbus_vehicle/devkit/protocol/vin_resp2_515.h" - -#include - -#include "glog/logging.h" - -#include "modules/drivers/canbus/common/byte.h" -#include "modules/drivers/canbus/common/canbus_consts.h" - -namespace apollo { -namespace canbus { -namespace devkit { - -using ::apollo::drivers::canbus::Byte; - -Vinresp2515::Vinresp2515() {} -const int32_t Vinresp2515::ID = 0x515; - -void Vinresp2515::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_vin_resp2_515()->set_vin15( - vin15(bytes, length)); - chassis->mutable_vin_resp2_515()->set_vin14( - vin14(bytes, length)); - chassis->mutable_vin_resp2_515()->set_vin13( - vin13(bytes, length)); - chassis->mutable_vin_resp2_515()->set_vin12( - vin12(bytes, length)); - chassis->mutable_vin_resp2_515()->set_vin11( - vin11(bytes, length)); - chassis->mutable_vin_resp2_515()->set_vin10( - vin10(bytes, length)); - chassis->mutable_vin_resp2_515()->set_vin09( - vin09(bytes, length)); - chassis->mutable_vin_resp2_515()->set_vin08( - vin08(bytes, length)); -} - -// config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': 'vin15', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp2515::vin15(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 7); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 55, 'is_signed_var': False, 'len': 8, 'name': 'vin14', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp2515::vin14(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 6); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 47, 'is_signed_var': False, 'len': 8, 'name': 'vin13', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp2515::vin13(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 5); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 39, 'is_signed_var': False, 'len': 8, 'name': 'vin12', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp2515::vin12(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 4); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 31, 'is_signed_var': False, 'len': 8, 'name': 'vin11', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp2515::vin11(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 3); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 23, 'is_signed_var': False, 'len': 8, 'name': 'vin10', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp2515::vin10(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 2); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 15, 'is_signed_var': False, 'len': 8, 'name': 'vin09', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp2515::vin09(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 1); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} - -// config detail: {'bit': 7, 'is_signed_var': False, 'len': 8, 'name': 'vin08', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp2515::vin08(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} -} // namespace devkit -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/vin_resp2_515.h b/modules/canbus_vehicle/devkit/protocol/vin_resp2_515.h deleted file mode 100644 index f66dc25f8e1..00000000000 --- a/modules/canbus_vehicle/devkit/protocol/vin_resp2_515.h +++ /dev/null @@ -1,81 +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 "modules/canbus_vehicle/devkit/proto/devkit.pb.h" - -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace devkit { - -class Vinresp2515 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { - public: - static const int32_t ID; - Vinresp2515(); - void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; - - private: - // config detail: {'bit': 63, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN15', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin15(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 55, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN14', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin14(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 47, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN13', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin13(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 39, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN12', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin12(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 31, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN11', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin11(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 23, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN10', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin10(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 15, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN09', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin09(const std::uint8_t* bytes, const int32_t length) const; - - // config detail: {'bit': 7, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN08', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin08(const std::uint8_t* bytes, const int32_t length) const; -}; - -} // namespace devkit -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/vin_resp3_516.cc b/modules/canbus_vehicle/devkit/protocol/vin_resp3_516.cc deleted file mode 100644 index 79182e915f6..00000000000 --- a/modules/canbus_vehicle/devkit/protocol/vin_resp3_516.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/canbus_vehicle/devkit/protocol/vin_resp3_516.h" - -#include - -#include "glog/logging.h" - -#include "modules/drivers/canbus/common/byte.h" -#include "modules/drivers/canbus/common/canbus_consts.h" - -namespace apollo { -namespace canbus { -namespace devkit { - -using ::apollo::drivers::canbus::Byte; - -Vinresp3516::Vinresp3516() {} -const int32_t Vinresp3516::ID = 0x516; - -void Vinresp3516::Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const { - chassis->mutable_vin_resp3_516()->set_vin16( - vin16(bytes, length)); -} - -// config detail: {'bit': 7, 'is_signed_var': False, 'len': 8, 'name': 'vin16', -// 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', -// 'physical_unit': '', 'precision': 1.0, 'type': 'int'} -std::string Vinresp3516::vin16(const std::uint8_t* bytes, - int32_t length) const { - Byte t0(bytes + 0); - int32_t x = t0.get_byte(0, 8); - - std::string ret = ""; - ret += x; - return ret; -} -} // namespace devkit -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/protocol/vin_resp3_516.h b/modules/canbus_vehicle/devkit/protocol/vin_resp3_516.h deleted file mode 100644 index 7081dd9e1d2..00000000000 --- a/modules/canbus_vehicle/devkit/protocol/vin_resp3_516.h +++ /dev/null @@ -1,46 +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 "modules/canbus_vehicle/devkit/proto/devkit.pb.h" - -#include "modules/drivers/canbus/can_comm/protocol_data.h" - -namespace apollo { -namespace canbus { -namespace devkit { - -class Vinresp3516 : public ::apollo::drivers::canbus::ProtocolData< - ::apollo::canbus::Devkit> { - public: - static const int32_t ID; - Vinresp3516(); - void Parse(const std::uint8_t* bytes, int32_t length, - Devkit* chassis) const override; - - private: - // config detail: {'bit': 7, 'is_signed_var': False, 'len': 8, 'name': - // 'VIN16', 'offset': 0.0, 'order': 'motorola', 'physical_range': '[0|255]', - // 'physical_unit': '', 'precision': 1.0, 'type': 'int'} - std::string vin16(const std::uint8_t* bytes, const int32_t length) const; -}; - -} // namespace devkit -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/devkit/testdata/devkit_canbus_conf_test.pb.txt b/modules/canbus_vehicle/devkit/testdata/devkit_canbus_conf_test.pb.txt deleted file mode 100755 index c77056ce223..00000000000 --- a/modules/canbus_vehicle/devkit/testdata/devkit_canbus_conf_test.pb.txt +++ /dev/null @@ -1,13 +0,0 @@ -vehicle_parameter { - brand: DKIT - max_enable_fail_attempt: 5 - driving_mode: COMPLETE_AUTO_DRIVE -} - -can_card_parameter { - brand:SOCKET_CAN_RAW - type: PCI_CARD - channel_id: CHANNEL_ID_ZERO -} - -enable_debug_mode: false diff --git a/modules/canbus_vehicle/ge3/BUILD b/modules/canbus_vehicle/ge3/BUILD deleted file mode 100644 index fd963cb8a5b..00000000000 --- a/modules/canbus_vehicle/ge3/BUILD +++ /dev/null @@ -1,160 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "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"]) - -CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] - -cc_library( - name = "ge3_vehicle_factory", - srcs = ["ge3_vehicle_factory.cc"], - hdrs = ["ge3_vehicle_factory.h"], - copts = CANBUS_COPTS, - alwayslink = True, - deps = [ - ":ge3_controller", - ":ge3_message_manager", - "//modules/canbus/common:canbus_gflags", - "//modules/common/adapters:adapter_gflags", - "//modules/common/status", - "//modules/canbus/proto:vehicle_parameter_cc_proto", - "//modules/canbus/vehicle:abstract_vehicle_factory", - "//modules/drivers/canbus:sensor_canbus_lib", - ], -) - -cc_binary( - name = "libge3_vehicle_factory_lib.so", - linkshared = True, - linkstatic = True, - deps = [":ge3_vehicle_factory"], -) - -cc_test( - name = "ge3_vehicle_factory_test", - size = "small", - srcs = ["ge3_vehicle_factory_test.cc"], - data = ["//modules/canbus:test_data"], - linkstatic = True, - deps = [ - ":ge3_vehicle_factory", - "@com_google_googletest//:gtest_main", - ], -) - -cc_library( - name = "ge3_message_manager", - srcs = ["ge3_message_manager.cc"], - hdrs = ["ge3_message_manager.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/ge3/proto:ge3_cc_proto", - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_test( - name = "ge3_message_manager_test", - size = "small", - srcs = ["ge3_message_manager_test.cc"], - deps = [ - ":ge3_message_manager", - "@com_google_googletest//:gtest_main", - ], -) - -cc_library( - name = "ge3_controller", - srcs = ["ge3_controller.cc"], - hdrs = ["ge3_controller.h"], - copts = CANBUS_COPTS, - deps = [ - ":ge3_message_manager", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/canbus/vehicle:vehicle_controller_base", - "//modules/canbus_vehicle/ge3/protocol:canbus_ge3_protocol_pc_bcm_201", - "//modules/drivers/canbus/can_comm:can_sender", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_test( - name = "ge3_controller_test", - size = "small", - srcs = ["ge3_controller_test.cc"], - data = ["//modules/canbus:test_data"], - deps = [ - ":ge3_controller", - "//modules/common/util", - "@com_google_googletest//:gtest_main", - ], -) - -install( - name = "install", - library_dest = "canbus-vehicle-ge3/lib", - data_dest = "canbus-vehicle-ge3", - data = [ - ":runtime_data", - ":cyberfile.xml", - ":canbus-vehicle-ge3.BUILD", - ], - targets = [ - ":libge3_vehicle_factory_lib.so", - ], - deps = [ - ":pb_ge3", - ":pb_hdrs", - ], -) - -install( - name = "pb_hdrs", - data_dest = "canbus-vehicle-ge3/include", - data = [ - "//modules/canbus_vehicle/ge3/proto:ge3_cc_proto", - ], -) - -install_files( - name = "pb_ge3", - dest = "canbus-vehicle-ge3", - files = [ - "//modules/canbus_vehicle/ge3/proto:ge3_py_pb2", - ], -) - -filegroup( - name = "runtime_data", - srcs = glob([ - "testdata/**", - ]), -) - -install_src_files( - name = "install_src", - deps = [ - ":install_ge3_src", - ":install_ge3_hdrs" - ], -) - -install_src_files( - name = "install_ge3_src", - src_dir = ["."], - dest = "canbus-vehicle-ge3/src", - filter = "*", -) - -install_src_files( - name = "install_ge3_hdrs", - src_dir = ["."], - dest = "canbus-vehicle-ge3/include", - filter = "*.h", -) - -cpplint() diff --git a/modules/canbus_vehicle/ge3/canbus-vehicle-ge3.BUILD b/modules/canbus_vehicle/ge3/canbus-vehicle-ge3.BUILD deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/modules/canbus_vehicle/ge3/cyberfile.xml b/modules/canbus_vehicle/ge3/cyberfile.xml deleted file mode 100644 index 5672ee76dba..00000000000 --- a/modules/canbus_vehicle/ge3/cyberfile.xml +++ /dev/null @@ -1,24 +0,0 @@ - - canbus-vehicle-ge3 - local - - Dynamic loading for canbus ge3 vehicle module - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/canbus_vehicle/ge3 - - cyber-dev - common-dev - canbus-dev - common-msgs-dev - drivers-dev - 3rd-gtest-dev - - \ No newline at end of file diff --git a/modules/canbus_vehicle/ge3/ge3_vehicle_factory.cc b/modules/canbus_vehicle/ge3/ge3_vehicle_factory.cc deleted file mode 100644 index 3d87c657059..00000000000 --- a/modules/canbus_vehicle/ge3/ge3_vehicle_factory.cc +++ /dev/null @@ -1,166 +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/canbus_vehicle/ge3/ge3_vehicle_factory.h" - -#include "cyber/common/log.h" -#include "modules/canbus/common/canbus_gflags.h" -#include "modules/canbus_vehicle/ge3/ge3_controller.h" -#include "modules/canbus_vehicle/ge3/ge3_message_manager.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common/util/util.h" -#include "modules/drivers/canbus/can_client/can_client_factory.h" - -using apollo::common::ErrorCode; -using apollo::control::ControlCommand; -using apollo::drivers::canbus::CanClientFactory; - -namespace apollo { -namespace canbus { - -bool Ge3VehicleFactory::Init(const CanbusConf *canbus_conf) { - // Init can client - auto can_factory = CanClientFactory::Instance(); - can_factory->RegisterCanClients(); - can_client_ = can_factory->CreateCANClient(canbus_conf->can_card_parameter()); - if (!can_client_) { - AERROR << "Failed to create can client."; - return false; - } - AINFO << "Can client is successfully created."; - - message_manager_ = this->CreateMessageManager(); - if (message_manager_ == nullptr) { - AERROR << "Failed to create message manager."; - return false; - } - AINFO << "Message manager is successfully created."; - - if (can_receiver_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_receiver_log()) != ErrorCode::OK) { - AERROR << "Failed to init can receiver."; - return false; - } - AINFO << "The can receiver is successfully initialized."; - - if (can_sender_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_sender_log()) != ErrorCode::OK) { - AERROR << "Failed to init can sender."; - return false; - } - AINFO << "The can sender is successfully initialized."; - - vehicle_controller_ = CreateVehicleController(); - if (vehicle_controller_ == nullptr) { - AERROR << "Failed to create vehicle controller."; - return false; - } - AINFO << "The vehicle controller is successfully created."; - - if (vehicle_controller_->Init(canbus_conf->vehicle_parameter(), &can_sender_, - message_manager_.get()) != ErrorCode::OK) { - AERROR << "Failed to init vehicle controller."; - return false; - } - - AINFO << "The vehicle controller is successfully" - << " initialized with canbus conf as : " - << canbus_conf->vehicle_parameter().ShortDebugString(); - - node_ = ::apollo::cyber::CreateNode("chassis_detail"); - - chassis_detail_writer_ = - node_->CreateWriter<::apollo::canbus::Ge3>(FLAGS_chassis_detail_topic); - - return true; -} - -bool Ge3VehicleFactory::Start() { - // 1. init and start the can card hardware - if (can_client_->Start() != ErrorCode::OK) { - AERROR << "Failed to start can client"; - return false; - } - AINFO << "Can client is started."; - - // 2. start receive first then send - if (can_receiver_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can receiver."; - return false; - } - AINFO << "Can receiver is started."; - - // 3. start send - if (can_sender_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can sender."; - return false; - } - - // 4. start controller - if (!vehicle_controller_->Start()) { - AERROR << "Failed to start vehicle controller."; - return false; - } - - return true; -} - -void Ge3VehicleFactory::Stop() { - can_sender_.Stop(); - can_receiver_.Stop(); - can_client_->Stop(); - vehicle_controller_->Stop(); - AINFO << "Cleanup cansender, canreceiver, canclient, vehicle controller."; -} - -void Ge3VehicleFactory::UpdateCommand( - const apollo::control::ControlCommand *control_command) { - if (vehicle_controller_->Update(*control_command) != ErrorCode::OK) { - AERROR << "Failed to process callback function OnControlCommand because " - "vehicle_controller_->Update error."; - return; - } - can_sender_.Update(); -} - -Chassis Ge3VehicleFactory::publish_chassis() { - Chassis chassis = vehicle_controller_->chassis(); - ADEBUG << chassis.ShortDebugString(); - return chassis; -} - -void Ge3VehicleFactory::PublishChassisDetail() { - Ge3 chassis_detail; - message_manager_->GetSensorData(&chassis_detail); - ADEBUG << chassis_detail.ShortDebugString(); - chassis_detail_writer_->Write(chassis_detail); -} - -std::unique_ptr> -Ge3VehicleFactory::CreateVehicleController() { - return std::unique_ptr>( - new ge3::Ge3Controller()); -} - -std::unique_ptr> -Ge3VehicleFactory::CreateMessageManager() { - return std::unique_ptr>( - new ge3::Ge3MessageManager()); -} - -} // namespace canbus -} // namespace apollo - diff --git a/modules/canbus_vehicle/ge3/ge3_vehicle_factory.h b/modules/canbus_vehicle/ge3/ge3_vehicle_factory.h deleted file mode 100644 index 0a9e39e72bd..00000000000 --- a/modules/canbus_vehicle/ge3/ge3_vehicle_factory.h +++ /dev/null @@ -1,121 +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. - *****************************************************************************/ - -/** - * @file ge3_vehicle_factory.h - */ - -#pragma once - -#include - -#include "modules/canbus/proto/canbus_conf.pb.h" -#include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "modules/canbus_vehicle/ge3/proto/ge3.pb.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -#include "cyber/cyber.h" -#include "modules/canbus/vehicle/abstract_vehicle_factory.h" -#include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/common/status/status.h" -#include "modules/drivers/canbus/can_client/can_client.h" -#include "modules/drivers/canbus/can_comm/can_receiver.h" -#include "modules/drivers/canbus/can_comm/can_sender.h" -#include "modules/drivers/canbus/can_comm/message_manager.h" - -/** - * @namespace apollo::canbus - * @brief apollo::canbus - */ -namespace apollo { -namespace canbus { - -/** - * @class Ge3VehicleFactory - * - * @brief this class is inherited from AbstractVehicleFactory. It can be used to - * create controller and message manager for ge3 vehicle. - */ -class Ge3VehicleFactory : public AbstractVehicleFactory { - public: - /** - * @brief destructor - */ - virtual ~Ge3VehicleFactory() = default; - - /** - * @brief init vehicle factory - * @returns true if successfully initialized - */ - bool Init(const CanbusConf *canbus_conf) override; - - /** - * @brief start canclient, cansender, canreceiver, vehicle controller - * @returns true if successfully started - */ - bool Start() override; - - /** - * @brief create ch vehicle controller - * @returns a unique_ptr that points to the created controller - */ - void Stop() override; - - /** - * @brief update control command - */ - void UpdateCommand( - const apollo::control::ControlCommand *control_command) override; - - /** - * @brief publish chassis messages - */ - Chassis publish_chassis() override; - - /** - * @brief publish chassis for vehicle messages - */ - void PublishChassisDetail() override; - - private: - /** - * @brief create ge3 vehicle controller - * @returns a unique_ptr that points to the created controller - */ - std::unique_ptr> - CreateVehicleController(); - - /** - * @brief create ge3 message manager - * @returns a unique_ptr that points to the created message manager - */ - std::unique_ptr> CreateMessageManager(); - - std::unique_ptr<::apollo::cyber::Node> node_ = nullptr; - std::unique_ptr can_client_; - CanSender<::apollo::canbus::Ge3> can_sender_; - apollo::drivers::canbus::CanReceiver<::apollo::canbus::Ge3> can_receiver_; - std::unique_ptr> message_manager_; - std::unique_ptr> vehicle_controller_; - - std::shared_ptr<::apollo::cyber::Writer<::apollo::canbus::Ge3>> - chassis_detail_writer_; -}; - -CYBER_REGISTER_VEHICLEFACTORY(Ge3VehicleFactory) - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ge3/proto/BUILD b/modules/canbus_vehicle/ge3/proto/BUILD deleted file mode 100644 index 6809b4849d2..00000000000 --- a/modules/canbus_vehicle/ge3/proto/BUILD +++ /dev/null @@ -1,25 +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") - -package(default_visibility = ["//visibility:public"]) - -cc_proto_library( - name = "ge3_cc_proto", - deps = [ - ":ge3_proto", - ], -) - -proto_library( - name = "ge3_proto", - srcs = ["ge3.proto"], -) - -py_proto_library( - name = "ge3_py_pb2", - deps = [ - ":ge3_proto", - ], -) diff --git a/modules/canbus_vehicle/ge3/protocol/scu_vcu_1_312_test.cc b/modules/canbus_vehicle/ge3/protocol/scu_vcu_1_312_test.cc deleted file mode 100644 index 450c1dda756..00000000000 --- a/modules/canbus_vehicle/ge3/protocol/scu_vcu_1_312_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/canbus_vehicle/ge3/protocol/scu_vcu_1_312.h" -#include "gtest/gtest.h" - -namespace apollo { -namespace canbus { -namespace ge3 { - -class Scuvcu1312Test : public ::testing::Test { - public: - virtual void SetUp() {} -}; - -TEST_F(Scuvcu1312Test, reset) { - Scuvcu1312 scuvcu1312; - int32_t length = 8; - Ge3 chassis_detail; - uint8_t bytes[8] = {0x01, 0x02, 0x03, 0x04, 0x11, 0x12, 0x13, 0x14}; - - scuvcu1312.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_elcsysfault(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_brkpedst(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_intidx(), 4); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_gearintidx(), 2); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_geardrvmode(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_accpedact(), 14.45); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_brkpedpst(), 6.664); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_vehrng(), 515); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_accpedpst(), 1.568); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_vehrdyst(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_faultst(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_drvmode(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_gearpst(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_gearfaultst(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.scu_vcu_1_312().vcu_gearact(), 0); -} - -} // namespace ge3 -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/ge3/testdata/ge3_canbus_conf_test.pb.txt b/modules/canbus_vehicle/ge3/testdata/ge3_canbus_conf_test.pb.txt deleted file mode 100644 index 8ee5076f130..00000000000 --- a/modules/canbus_vehicle/ge3/testdata/ge3_canbus_conf_test.pb.txt +++ /dev/null @@ -1,13 +0,0 @@ -vehicle_parameter { - brand: GE3 - max_enable_fail_attempt: 5 - driving_mode: COMPLETE_AUTO_DRIVE -} - -can_card_parameter { - brand:SOCKET_CAN_RAW - type: PCI_CARD - channel_id: CHANNEL_ID_ZERO -} - -enable_debug_mode: false diff --git a/modules/canbus_vehicle/gem/canbus-vehicle-gem.BUILD b/modules/canbus_vehicle/gem/canbus-vehicle-gem.BUILD deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/modules/canbus_vehicle/gem/cyberfile.xml b/modules/canbus_vehicle/gem/cyberfile.xml deleted file mode 100644 index 2c76fdfc947..00000000000 --- a/modules/canbus_vehicle/gem/cyberfile.xml +++ /dev/null @@ -1,24 +0,0 @@ - - canbus-vehicle-gem - local - - Dynamic loading for canbus gem vehicle module - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/canbus_vehicle/gem - - cyber-dev - common-dev - canbus-dev - common-msgs-dev - drivers-dev - 3rd-gtest-dev - - \ No newline at end of file diff --git a/modules/canbus_vehicle/gem/gem_vehicle_factory.cc b/modules/canbus_vehicle/gem/gem_vehicle_factory.cc deleted file mode 100644 index 9e92f888667..00000000000 --- a/modules/canbus_vehicle/gem/gem_vehicle_factory.cc +++ /dev/null @@ -1,165 +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/canbus_vehicle/gem/gem_vehicle_factory.h" - -#include "cyber/common/log.h" -// #include "modules/canbus/common/canbus_gflags.h" -#include "modules/canbus_vehicle/gem/gem_controller.h" -#include "modules/canbus_vehicle/gem/gem_message_manager.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common/util/util.h" -#include "modules/drivers/canbus/can_client/can_client_factory.h" - -using apollo::common::ErrorCode; -using apollo::control::ControlCommand; -using apollo::drivers::canbus::CanClientFactory; - -namespace apollo { -namespace canbus { - -bool GemVehicleFactory::Init(const CanbusConf *canbus_conf) { - // Init can client - auto can_factory = CanClientFactory::Instance(); - can_factory->RegisterCanClients(); - can_client_ = can_factory->CreateCANClient(canbus_conf->can_card_parameter()); - if (!can_client_) { - AERROR << "Failed to create can client."; - return false; - } - AINFO << "Can client is successfully created."; - - message_manager_ = this->CreateMessageManager(); - if (message_manager_ == nullptr) { - AERROR << "Failed to create message manager."; - return false; - } - AINFO << "Message manager is successfully created."; - - if (can_receiver_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_receiver_log()) != ErrorCode::OK) { - AERROR << "Failed to init can receiver."; - return false; - } - AINFO << "The can receiver is successfully initialized."; - - if (can_sender_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_sender_log()) != ErrorCode::OK) { - AERROR << "Failed to init can sender."; - return false; - } - AINFO << "The can sender is successfully initialized."; - - vehicle_controller_ = CreateVehicleController(); - if (vehicle_controller_ == nullptr) { - AERROR << "Failed to create vehicle controller."; - return false; - } - AINFO << "The vehicle controller is successfully created."; - - if (vehicle_controller_->Init(canbus_conf->vehicle_parameter(), &can_sender_, - message_manager_.get()) != ErrorCode::OK) { - AERROR << "Failed to init vehicle controller."; - return false; - } - - AINFO << "The vehicle controller is successfully" - << " initialized with canbus conf as : " - << canbus_conf->vehicle_parameter().ShortDebugString(); - - node_ = ::apollo::cyber::CreateNode("chassis_detail"); - - chassis_detail_writer_ = - node_->CreateWriter<::apollo::canbus::Gem>(FLAGS_chassis_detail_topic); - - return true; -} - -bool GemVehicleFactory::Start() { - // 1. init and start the can card hardware - if (can_client_->Start() != ErrorCode::OK) { - AERROR << "Failed to start can client"; - return false; - } - AINFO << "Can client is started."; - - // 2. start receive first then send - if (can_receiver_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can receiver."; - return false; - } - AINFO << "Can receiver is started."; - - // 3. start send - if (can_sender_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can sender."; - return false; - } - - // 4. start controller - if (!vehicle_controller_->Start()) { - AERROR << "Failed to start vehicle controller."; - return false; - } - - return true; -} - -void GemVehicleFactory::Stop() { - can_sender_.Stop(); - can_receiver_.Stop(); - can_client_->Stop(); - vehicle_controller_->Stop(); - AINFO << "Cleanup cansender, canreceiver, canclient, vehicle controller."; -} - -void GemVehicleFactory::UpdateCommand( - const apollo::control::ControlCommand *control_command) { - if (vehicle_controller_->Update(*control_command) != ErrorCode::OK) { - AERROR << "Failed to process callback function OnControlCommand because " - "vehicle_controller_->Update error."; - return; - } - can_sender_.Update(); -} - -Chassis GemVehicleFactory::publish_chassis() { - Chassis chassis = vehicle_controller_->chassis(); - ADEBUG << chassis.ShortDebugString(); - return chassis; -} - -void GemVehicleFactory::PublishChassisDetail() { - Gem chassis_detail; - message_manager_->GetSensorData(&chassis_detail); - ADEBUG << chassis_detail.ShortDebugString(); - chassis_detail_writer_->Write(chassis_detail); -} - -std::unique_ptr> -GemVehicleFactory::CreateVehicleController() { - return std::unique_ptr>( - new gem::GemController()); -} - -std::unique_ptr> -GemVehicleFactory::CreateMessageManager() { - return std::unique_ptr>( - new gem::GemMessageManager()); -} - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/gem/gem_vehicle_factory.h b/modules/canbus_vehicle/gem/gem_vehicle_factory.h deleted file mode 100644 index 76554da9c8b..00000000000 --- a/modules/canbus_vehicle/gem/gem_vehicle_factory.h +++ /dev/null @@ -1,120 +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. - *****************************************************************************/ - -/** - * @file gem_vehicle_factory.h - */ - -#pragma once - -#include - -#include "modules/canbus/proto/canbus_conf.pb.h" -#include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "modules/canbus_vehicle/gem/proto/gem.pb.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -#include "cyber/cyber.h" -#include "modules/canbus/vehicle/abstract_vehicle_factory.h" -#include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/drivers/canbus/can_client/can_client.h" -#include "modules/drivers/canbus/can_comm/can_receiver.h" -#include "modules/drivers/canbus/can_comm/can_sender.h" -#include "modules/drivers/canbus/can_comm/message_manager.h" - -/** - * @namespace apollo::canbus - * @brief apollo::canbus - */ -namespace apollo { -namespace canbus { - -/** - * @class GemVehicleFactory - * - * @brief this class is inherited from AbstractVehicleFactory. It can be used to - * create controller and message manager for Gem vehicle. - */ -class GemVehicleFactory : public AbstractVehicleFactory { - public: - /** - * @brief destructor - */ - virtual ~GemVehicleFactory() = default; - - /** - * @brief init vehicle factory - * @returns true if successfully initialized - */ - bool Init(const CanbusConf *canbus_conf) override; - - /** - * @brief start canclient, cansender, canreceiver, vehicle controller - * @returns true if successfully started - */ - bool Start() override; - - /** - * @brief create ch vehicle controller - * @returns a unique_ptr that points to the created controller - */ - void Stop() override; - - /** - * @brief update control command - */ - void UpdateCommand( - const apollo::control::ControlCommand *control_command) override; - - /** - * @brief publish chassis messages - */ - Chassis publish_chassis() override; - - /** - * @brief publish chassis for vehicle messages - */ - void PublishChassisDetail() override; - - private: - /** - * @brief create Gem vehicle controller - * @returns a unique_ptr that points to the created controller - */ - std::unique_ptr> - CreateVehicleController(); - - /** - * @brief create Gem message manager - * @returns a unique_ptr that points to the created message manager - */ - std::unique_ptr> CreateMessageManager(); - - std::unique_ptr<::apollo::cyber::Node> node_ = nullptr; - std::unique_ptr can_client_; - CanSender<::apollo::canbus::Gem> can_sender_; - apollo::drivers::canbus::CanReceiver<::apollo::canbus::Gem> can_receiver_; - std::unique_ptr> message_manager_; - std::unique_ptr> vehicle_controller_; - - std::shared_ptr<::apollo::cyber::Writer<::apollo::canbus::Gem>> - chassis_detail_writer_; -}; - -CYBER_REGISTER_VEHICLEFACTORY(GemVehicleFactory) - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/gem/proto/BUILD b/modules/canbus_vehicle/gem/proto/BUILD deleted file mode 100644 index e0c9ae94be6..00000000000 --- a/modules/canbus_vehicle/gem/proto/BUILD +++ /dev/null @@ -1,25 +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") - -package(default_visibility = ["//visibility:public"]) - -cc_proto_library( - name = "gem_cc_proto", - deps = [ - ":gem_proto", - ], -) - -proto_library( - name = "gem_proto", - srcs = ["gem.proto"], -) - -py_proto_library( - name = "gem_py_pb2", - deps = [ - ":gem_proto", - ], -) diff --git a/modules/canbus_vehicle/gem/proto/gem.proto b/modules/canbus_vehicle/gem/proto/gem.proto deleted file mode 100644 index 1d77f1657bc..00000000000 --- a/modules/canbus_vehicle/gem/proto/gem.proto +++ /dev/null @@ -1,507 +0,0 @@ -syntax = "proto2"; - -package apollo.canbus; - -// Gem vehicle starts from here -// TODO(QiL) : Re-factor needed here - -message Global_rpt_6a { - // Report Message - enum Pacmod_statusType { - PACMOD_STATUS_CONTROL_DISABLED = 0; - PACMOD_STATUS_CONTROL_ENABLED = 1; - } - enum Override_statusType { - OVERRIDE_STATUS_NOT_OVERRIDDEN = 0; - OVERRIDE_STATUS_OVERRIDDEN = 1; - } - enum Brk_can_timeoutType { - BRK_CAN_TIMEOUT_NO_ACTIVE_CAN_TIMEOUT = 0; - BRK_CAN_TIMEOUT_ACTIVE_CAN_TIMEOUT = 1; - } - // [] [0|1] - optional Pacmod_statusType pacmod_status = 1; - // [] [0|1] - optional Override_statusType override_status = 2; - // [] [0|1] - optional bool veh_can_timeout = 3; - // [] [0|1] - optional bool str_can_timeout = 4; - // [] [0|1] - optional Brk_can_timeoutType brk_can_timeout = 5; - // [] [0|1] - optional bool usr_can_timeout = 6; - // [] [0|65535] - optional int32 usr_can_read_errors = 7; -} - -message Brake_cmd_6b { - // Report Message - // [%] [0|1] - optional double brake_cmd = 1; -} - -message Brake_rpt_6c { - // Report Message - enum Brake_on_offType { - BRAKE_ON_OFF_OFF = 0; - BRAKE_ON_OFF_ON = 1; - } - // [%] [0|1] - optional double manual_input = 1; - // [%] [0|1] - optional double commanded_value = 2; - // [%] [0|1] - optional double output_value = 3; - // [] [0|1] - optional Brake_on_offType brake_on_off = 4; -} - -message Steering_cmd_6d { - // Report Message - // [radians] [-2147483.648|2147483.647] - optional double position_value = 1; - // [rad/s] [0|65.535] - optional double speed_limit = 2; -} - -message Steering_rpt_1_6e { - // Report Message - // [rad/s] [-32.768|32.767] - optional double manual_input = 1; - // [rad/s] [-32.768|32.767] - optional double commanded_value = 2; - // [rad/s] [-32.768|32.767] - optional double output_value = 3; -} - -message Wheel_speed_rpt_7a { - // Report Message - // [rad/s] [-32768|32767] - optional int32 wheel_spd_rear_right = 1; - // [rad/s] [-32768|32767] - optional int32 wheel_spd_rear_left = 2; - // [rad/s] [-32768|32767] - optional int32 wheel_spd_front_right = 3; - // [rad/s] [-32768|32767] - optional int32 wheel_spd_front_left = 4; -} - -message Date_time_rpt_83 { - // Report Message - // [sec] [0|60] - optional int32 time_second = 1; - // [min] [0|60] - optional int32 time_minute = 2; - // [hr] [0|23] - optional int32 time_hour = 3; - // [dy] [1|31] - optional int32 date_day = 4; - // [mon] [1|12] - optional int32 date_month = 5; - // [yr] [2000|2255] - optional int32 date_year = 6; -} - -message Brake_motor_rpt_1_70 { - // Report Message - // [amps] [0|4294967.295] - optional double motor_current = 1; - // [radians] [-2147483.648|2147483.647] - optional double shaft_position = 2; -} - -message Headlight_rpt_77 { - // Report Message - enum Output_valueType { - OUTPUT_VALUE_HEADLIGHTS_OFF = 0; - OUTPUT_VALUE_LOW_BEAMS = 1; - OUTPUT_VALUE_HIGH_BEAMS = 2; - } - enum Manual_inputType { - MANUAL_INPUT_HEADLIGHTS_OFF = 0; - MANUAL_INPUT_LOW_BEAMS = 1; - MANUAL_INPUT_HIGH_BEAMS = 2; - } - enum Commanded_valueType { - COMMANDED_VALUE_HEADLIGHTS_OFF = 0; - COMMANDED_VALUE_LOW_BEAMS = 1; - COMMANDED_VALUE_HIGH_BEAMS = 2; - } - // [] [0|2] - optional Output_valueType output_value = 1; - // [] [0|2] - optional Manual_inputType manual_input = 2; - // [] [0|2] - optional Commanded_valueType commanded_value = 3; -} - -message Accel_rpt_68 { - // Report Message - // [%] [0|1] - optional double manual_input = 1; - // [%] [0|1] - optional double commanded_value = 2; - // [%] [0|1] - optional double output_value = 3; -} - -message Steering_motor_rpt_3_75 { - // Report Message - // [N-m] [-2147483.648|2147483.647] - optional double torque_output = 1; - // [N-m] [-2147483.648|2147483.647] - optional double torque_input = 2; -} - -message Turn_cmd_63 { - // Report Message - enum Turn_signal_cmdType { - TURN_SIGNAL_CMD_RIGHT = 0; - TURN_SIGNAL_CMD_NONE = 1; - TURN_SIGNAL_CMD_LEFT = 2; - TURN_SIGNAL_CMD_HAZARD = 3; - } - // [] [0|3] - optional Turn_signal_cmdType turn_signal_cmd = 1; -} - -message Turn_rpt_64 { - // Report Message - enum Manual_inputType { - MANUAL_INPUT_RIGHT = 0; - MANUAL_INPUT_NONE = 1; - MANUAL_INPUT_LEFT = 2; - MANUAL_INPUT_HAZARD = 3; - } - enum Commanded_valueType { - COMMANDED_VALUE_RIGHT = 0; - COMMANDED_VALUE_NONE = 1; - COMMANDED_VALUE_LEFT = 2; - COMMANDED_VALUE_HAZARD = 3; - } - enum Output_valueType { - OUTPUT_VALUE_RIGHT = 0; - OUTPUT_VALUE_NONE = 1; - OUTPUT_VALUE_LEFT = 2; - OUTPUT_VALUE_HAZARD = 3; - } - // [] [0|3] - optional Manual_inputType manual_input = 1; - // [] [0|3] - optional Commanded_valueType commanded_value = 2; - // [] [0|3] - optional Output_valueType output_value = 3; -} - -message Shift_cmd_65 { - // Report Message - enum Shift_cmdType { - SHIFT_CMD_PARK = 0; - SHIFT_CMD_REVERSE = 1; - SHIFT_CMD_NEUTRAL = 2; - SHIFT_CMD_FORWARD = 3; - SHIFT_CMD_LOW = 4; - } - // FORWARD_is_also_LOW_on_vehicles_with_LOW/HIGH,_PARK_and_HIGH_only_available_on_certain_Vehicles - // [] [0|4] - optional Shift_cmdType shift_cmd = 1; -} - -message Shift_rpt_66 { - // Report Message - enum Manual_inputType { - MANUAL_INPUT_PARK = 0; - MANUAL_INPUT_REVERSE = 1; - MANUAL_INPUT_NEUTRAL = 2; - MANUAL_INPUT_FORWARD = 3; - MANUAL_INPUT_HIGH = 4; - } - enum Commanded_valueType { - COMMANDED_VALUE_PARK = 0; - COMMANDED_VALUE_REVERSE = 1; - COMMANDED_VALUE_NEUTRAL = 2; - COMMANDED_VALUE_FORWARD = 3; - COMMANDED_VALUE_HIGH = 4; - } - enum Output_valueType { - OUTPUT_VALUE_PARK = 0; - OUTPUT_VALUE_REVERSE = 1; - OUTPUT_VALUE_NEUTRAL = 2; - OUTPUT_VALUE_FORWARD = 3; - OUTPUT_VALUE_HIGH = 4; - } - // [] [0|4] - optional Manual_inputType manual_input = 1; - // [] [0|4] - optional Commanded_valueType commanded_value = 2; - // [] [0|4] - optional Output_valueType output_value = 3; -} - -message Accel_cmd_67 { - // Report Message - // [%] [0|1] - optional double accel_cmd = 1; -} - -message Lat_lon_heading_rpt_82 { - // Report Message - // [deg] [-327.68|327.67] - optional double heading = 1; - // [sec] [-128|127] - optional int32 longitude_seconds = 2; - // [min] [-128|127] - optional int32 longitude_minutes = 3; - // [deg] [-128|127] - optional int32 longitude_degrees = 4; - // [sec] [-128|127] - optional int32 latitude_seconds = 5; - // [min] [-128|127] - optional int32 latitude_minutes = 6; - // [deg] [-128|127] - optional int32 latitude_degrees = 7; -} - -message Global_cmd_69 { - // Report Message - enum Pacmod_enableType { - PACMOD_ENABLE_CONTROL_DISABLED = 0; - PACMOD_ENABLE_CONTROL_ENABLED = 1; - } - enum Clear_overrideType { - CLEAR_OVERRIDE_DON_T_CLEAR_ACTIVE_OVERRIDES = 0; - CLEAR_OVERRIDE_CLEAR_ACTIVE_OVERRIDES = 1; - } - enum Ignore_overrideType { - IGNORE_OVERRIDE_DON_T_IGNORE_USER_OVERRIDES = 0; - IGNORE_OVERRIDE_IGNORE_USER_OVERRIDES = 1; - } - // [] [0|1] - optional Pacmod_enableType pacmod_enable = 1; - // [] [0|1] - optional Clear_overrideType clear_override = 2; - // [] [0|1] - optional Ignore_overrideType ignore_override = 3; -} - -message Parking_brake_status_rpt_80 { - // Report Message - enum Parking_brake_enabledType { - PARKING_BRAKE_ENABLED_OFF = 0; - PARKING_BRAKE_ENABLED_ON = 1; - } - // [] [0|1] - optional Parking_brake_enabledType parking_brake_enabled = 1; -} - -message Yaw_rate_rpt_81 { - // Report Message - // [rad/s] [-327.68|327.67] - optional double yaw_rate = 1; -} - -message Horn_rpt_79 { - // Report Message - enum Output_valueType { - OUTPUT_VALUE_OFF = 0; - OUTPUT_VALUE_ON = 1; - } - enum Commanded_valueType { - COMMANDED_VALUE_OFF = 0; - COMMANDED_VALUE_ON = 1; - } - enum Manual_inputType { - MANUAL_INPUT_OFF = 0; - MANUAL_INPUT_ON = 1; - } - // [] [0|1] - optional Output_valueType output_value = 1; - // [] [0|1] - optional Commanded_valueType commanded_value = 2; - // [] [0|1] - optional Manual_inputType manual_input = 3; -} - -message Horn_cmd_78 { - // Report Message - enum Horn_cmdType { - HORN_CMD_OFF = 0; - HORN_CMD_ON = 1; - } - // [] [0|1] - optional Horn_cmdType horn_cmd = 1; -} - -message Wiper_rpt_91 { - // Report Message - enum Output_valueType { - OUTPUT_VALUE_WIPERS_OFF = 0; - OUTPUT_VALUE_INTERMITTENT_1 = 1; - OUTPUT_VALUE_INTERMITTENT_2 = 2; - OUTPUT_VALUE_INTERMITTENT_3 = 3; - OUTPUT_VALUE_INTERMITTENT_4 = 4; - OUTPUT_VALUE_INTERMITTENT_5 = 5; - OUTPUT_VALUE_LOW = 6; - OUTPUT_VALUE_HIGH = 7; - } - enum Commanded_valueType { - COMMANDED_VALUE_WIPERS_OFF = 0; - COMMANDED_VALUE_INTERMITTENT_1 = 1; - COMMANDED_VALUE_INTERMITTENT_2 = 2; - COMMANDED_VALUE_INTERMITTENT_3 = 3; - COMMANDED_VALUE_INTERMITTENT_4 = 4; - COMMANDED_VALUE_INTERMITTENT_5 = 5; - COMMANDED_VALUE_LOW = 6; - COMMANDED_VALUE_HIGH = 7; - } - enum Manual_inputType { - MANUAL_INPUT_WIPERS_OFF = 0; - MANUAL_INPUT_INTERMITTENT_1 = 1; - MANUAL_INPUT_INTERMITTENT_2 = 2; - MANUAL_INPUT_INTERMITTENT_3 = 3; - MANUAL_INPUT_INTERMITTENT_4 = 4; - MANUAL_INPUT_INTERMITTENT_5 = 5; - MANUAL_INPUT_LOW = 6; - MANUAL_INPUT_HIGH = 7; - } - // [] [0|7] - optional Output_valueType output_value = 1; - // [] [0|7] - optional Commanded_valueType commanded_value = 2; - // [] [0|7] - optional Manual_inputType manual_input = 3; -} - -message Vehicle_speed_rpt_6f { - // Report Message - enum Vehicle_speed_validType { - VEHICLE_SPEED_VALID_INVALID = 0; - VEHICLE_SPEED_VALID_VALID = 1; - } - // [m/s] [-327.68|327.67] - optional double vehicle_speed = 1; - // [] [0|1] - optional Vehicle_speed_validType vehicle_speed_valid = 2; -} - -message Headlight_cmd_76 { - // Report Message - enum Headlight_cmdType { - HEADLIGHT_CMD_HEADLIGHTS_OFF = 0; - HEADLIGHT_CMD_LOW_BEAMS = 1; - HEADLIGHT_CMD_HIGH_BEAMS = 2; - } - // [] [0|2] - optional Headlight_cmdType headlight_cmd = 1; -} - -message Steering_motor_rpt_2_74 { - // Report Message - // [deg C] [-32808|32727] - optional int32 encoder_temperature = 1; - // [deg C] [-32808|32727] - optional int32 motor_temperature = 2; - // [rev/s] [-2147483.648|2147483.647] - optional double angular_speed = 3; -} - -message Brake_motor_rpt_2_71 { - // Report Message - // [deg C] [-32808|32727] - optional int32 encoder_temperature = 1; - // [deg C] [-32808|32727] - optional int32 motor_temperature = 2; - // [rev/s] [0|4294967.295] - optional double angular_speed = 3; -} - -message Steering_motor_rpt_1_73 { - // Report Message - // [amps] [0|4294967.295] - optional double motor_current = 1; - // [amps] [-2147483.648|2147483.647] - optional double shaft_position = 2; -} - -message Wiper_cmd_90 { - // Report Message - enum Wiper_cmdType { - WIPER_CMD_WIPERS_OFF = 0; - WIPER_CMD_INTERMITTENT_1 = 1; - WIPER_CMD_INTERMITTENT_2 = 2; - WIPER_CMD_INTERMITTENT_3 = 3; - WIPER_CMD_INTERMITTENT_4 = 4; - WIPER_CMD_INTERMITTENT_5 = 5; - WIPER_CMD_LOW = 6; - WIPER_CMD_HIGH = 7; - } - // [] [0|7] - optional Wiper_cmdType wiper_cmd = 1; -} - -message Brake_motor_rpt_3_72 { - // Report Message - // [N-m] [-2147483.648|2147483.647] - optional double torque_output = 1; - // [N-m] [-2147483.648|2147483.647] - optional double torque_input = 2; -} - -message Light { - enum TurnLightType { - TURN_LIGHT_OFF = 0; - TURN_LEFT_ON = 1; - TURN_RIGHT_ON = 2; - TURN_LIGHT_ON = 3; - } - enum BeamLampType { - BEAM_OFF = 0; - HIGH_BEAM_ON = 1; - LOW_BEAM_ON = 2; - } - - optional TurnLightType turn_light_type = 1; - optional BeamLampType beam_lamp_type = 2; - optional bool is_brake_lamp_on = 3; - -} - -message Gem { - optional Global_rpt_6a global_rpt_6a = 1; // report message - optional Brake_cmd_6b brake_cmd_6b = 2; // report message - optional Brake_rpt_6c brake_rpt_6c = 3; // report message - optional Steering_cmd_6d steering_cmd_6d = 4; // report message - optional Steering_rpt_1_6e steering_rpt_1_6e = 5; // report message - optional Wheel_speed_rpt_7a wheel_speed_rpt_7a = 6; // report message - optional Date_time_rpt_83 date_time_rpt_83 = 7; // report message - optional Brake_motor_rpt_1_70 brake_motor_rpt_1_70 = 8; // report message - optional Headlight_rpt_77 headlight_rpt_77 = 9; // report message - optional Accel_rpt_68 accel_rpt_68 = 10; // report message - optional Steering_motor_rpt_3_75 steering_motor_rpt_3_75 = - 11; // report message - optional Turn_cmd_63 turn_cmd_63 = 12; // report message - optional Turn_rpt_64 turn_rpt_64 = 13; // report message - optional Shift_cmd_65 shift_cmd_65 = 14; // report message - optional Shift_rpt_66 shift_rpt_66 = 15; // report message - optional Accel_cmd_67 accel_cmd_67 = 16; // report message - optional Lat_lon_heading_rpt_82 lat_lon_heading_rpt_82 = - 17; // report message - optional Global_cmd_69 global_cmd_69 = 18; // report message - optional Parking_brake_status_rpt_80 parking_brake_status_rpt_80 = - 19; // report message - optional Yaw_rate_rpt_81 yaw_rate_rpt_81 = 20; // report message - optional Horn_rpt_79 horn_rpt_79 = 21; // report message - optional Horn_cmd_78 horn_cmd_78 = 22; // report message - optional Wiper_rpt_91 wiper_rpt_91 = 23; // report message - optional Vehicle_speed_rpt_6f vehicle_speed_rpt_6f = 24; // report message - optional Headlight_cmd_76 headlight_cmd_76 = 25; // report message - optional Steering_motor_rpt_2_74 steering_motor_rpt_2_74 = - 26; // report message - optional Brake_motor_rpt_2_71 brake_motor_rpt_2_71 = 27; // report message - optional Steering_motor_rpt_1_73 steering_motor_rpt_1_73 = - 28; // report message - optional Wiper_cmd_90 wiper_cmd_90 = 29; // report message - optional Brake_motor_rpt_3_72 brake_motor_rpt_3_72 = 30; // report message - optional Light light = 31; // report message -} diff --git a/modules/canbus_vehicle/gem/testdata/gem_canbus_conf_test.pb.txt b/modules/canbus_vehicle/gem/testdata/gem_canbus_conf_test.pb.txt deleted file mode 100644 index 19227630e51..00000000000 --- a/modules/canbus_vehicle/gem/testdata/gem_canbus_conf_test.pb.txt +++ /dev/null @@ -1,13 +0,0 @@ -vehicle_parameter { - brand: GEM - max_enable_fail_attempt: 5 - driving_mode: COMPLETE_AUTO_DRIVE -} - -can_card_parameter { - brand:SOCKET_CAN_RAW - type: PCI_CARD - channel_id: CHANNEL_ID_ZERO -} - -enable_debug_mode: false \ No newline at end of file diff --git a/modules/canbus_vehicle/lexus/BUILD b/modules/canbus_vehicle/lexus/BUILD deleted file mode 100644 index fcc3884e57c..00000000000 --- a/modules/canbus_vehicle/lexus/BUILD +++ /dev/null @@ -1,149 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "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"]) - -CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] - -cc_library( - name = "lexus_vehicle_factory", - srcs = ["lexus_vehicle_factory.cc"], - hdrs = ["lexus_vehicle_factory.h"], - copts = CANBUS_COPTS, - alwayslink = True, - deps = [ - ":lexus_controller", - ":lexus_message_manager", - "//modules/canbus/common:canbus_gflags", - "//modules/common/adapters:adapter_gflags", - "//modules/common/status", - "//modules/canbus/vehicle:abstract_vehicle_factory", - "//modules/drivers/canbus:sensor_canbus_lib", - ], -) - -cc_binary( - name = "liblexus_vehicle_factory_lib.so", - linkshared = True, - linkstatic = True, - deps = [":lexus_vehicle_factory"], -) - -cc_library( - name = "lexus_message_manager", - srcs = ["lexus_message_manager.cc"], - hdrs = ["lexus_message_manager.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/lexus/proto:lexus_cc_proto", - "//modules/canbus_vehicle/lexus/protocol:canbus_lexus_protocol", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_library( - name = "lexus_controller", - srcs = ["lexus_controller.cc"], - hdrs = ["lexus_controller.h"], - copts = CANBUS_COPTS, - deps = [ - ":lexus_message_manager", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/canbus_vehicle/lexus/proto:lexus_cc_proto", - "//modules/canbus/vehicle:vehicle_controller_base", - "//modules/canbus_vehicle/lexus/protocol:canbus_lexus_protocol", - "//modules/drivers/canbus/can_comm:can_sender", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_test( - name = "lexus_controller_test", - size = "small", - srcs = ["lexus_controller_test.cc"], - data = ["//modules/canbus:test_data"], - deps = [ - "//modules/canbus_vehicle/lexus:lexus_controller", - "@com_google_googletest//:gtest_main", - ], -) - -cc_test( - name = "lexus_vehicle_factory_test", - size = "small", - srcs = ["lexus_vehicle_factory_test.cc"], - data = ["//modules/canbus:test_data"], - linkstatic = True, - deps = [ - ":lexus_vehicle_factory", - "@com_google_googletest//:gtest_main", - ], -) - -install( - name = "install", - library_dest = "canbus-vehicle-lexus/lib", - data_dest = "canbus-vehicle-lexus", - data = [ - ":runtime_data", - ":cyberfile.xml", - ":canbus-vehicle-lexus.BUILD", - ], - targets = [ - ":liblexus_vehicle_factory_lib.so", - ], - deps = [ - ":pb_lexus", - ":pb_hdrs", - ], -) - -install( - name = "pb_hdrs", - data_dest = "canbus-vehicle-lexus/include", - data = [ - "//modules/canbus_vehicle/lexus/proto:lexus_cc_proto", - ], -) - -install_files( - name = "pb_lexus", - dest = "canbus-vehicle-lexus", - files = [ - "//modules/canbus_vehicle/lexus/proto:lexus_py_pb2", - ], -) - -filegroup( - name = "runtime_data", - srcs = glob([ - "testdata/**", - ]), -) - -install_src_files( - name = "install_src", - deps = [ - ":install_lexus_src", - ":install_lexus_hdrs" - ], -) - -install_src_files( - name = "install_lexus_src", - src_dir = ["."], - dest = "canbus-vehicle-lexus/src", - filter = "*", -) - -install_src_files( - name = "install_lexus_hdrs", - src_dir = ["."], - dest = "canbus-vehicle-lexus/include", - filter = "*.h", -) - -cpplint() diff --git a/modules/canbus_vehicle/lexus/canbus-vehicle-lexus.BUILD b/modules/canbus_vehicle/lexus/canbus-vehicle-lexus.BUILD deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/modules/canbus_vehicle/lexus/cyberfile.xml b/modules/canbus_vehicle/lexus/cyberfile.xml deleted file mode 100644 index 4251e580ff9..00000000000 --- a/modules/canbus_vehicle/lexus/cyberfile.xml +++ /dev/null @@ -1,24 +0,0 @@ - - canbus-vehicle-lexus - local - - Dynamic loading for canbus lexus vehicle module - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/canbus_vehicle/lexus - - cyber-dev - common-dev - canbus-dev - common-msgs-dev - drivers-dev - 3rd-gtest-dev - - \ No newline at end of file diff --git a/modules/canbus_vehicle/lexus/lexus_vehicle_factory.cc b/modules/canbus_vehicle/lexus/lexus_vehicle_factory.cc deleted file mode 100644 index a8d243ddb7a..00000000000 --- a/modules/canbus_vehicle/lexus/lexus_vehicle_factory.cc +++ /dev/null @@ -1,165 +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/canbus_vehicle/lexus/lexus_vehicle_factory.h" - -#include "cyber/common/log.h" -#include "modules/canbus/common/canbus_gflags.h" -#include "modules/canbus_vehicle/lexus/lexus_controller.h" -#include "modules/canbus_vehicle/lexus/lexus_message_manager.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common/util/util.h" -#include "modules/drivers/canbus/can_client/can_client_factory.h" - -using apollo::common::ErrorCode; -using apollo::control::ControlCommand; -using apollo::drivers::canbus::CanClientFactory; - -namespace apollo { -namespace canbus { - -bool LexusVehicleFactory::Init(const CanbusConf *canbus_conf) { - // Init can client - auto can_factory = CanClientFactory::Instance(); - can_factory->RegisterCanClients(); - can_client_ = can_factory->CreateCANClient(canbus_conf->can_card_parameter()); - if (!can_client_) { - AERROR << "Failed to create can client."; - return false; - } - AINFO << "Can client is successfully created."; - - message_manager_ = this->CreateMessageManager(); - if (message_manager_ == nullptr) { - AERROR << "Failed to create message manager."; - return false; - } - AINFO << "Message manager is successfully created."; - - if (can_receiver_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_receiver_log()) != ErrorCode::OK) { - AERROR << "Failed to init can receiver."; - return false; - } - AINFO << "The can receiver is successfully initialized."; - - if (can_sender_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_sender_log()) != ErrorCode::OK) { - AERROR << "Failed to init can sender."; - return false; - } - AINFO << "The can sender is successfully initialized."; - - vehicle_controller_ = CreateVehicleController(); - if (vehicle_controller_ == nullptr) { - AERROR << "Failed to create vehicle controller."; - return false; - } - AINFO << "The vehicle controller is successfully created."; - - if (vehicle_controller_->Init(canbus_conf->vehicle_parameter(), &can_sender_, - message_manager_.get()) != ErrorCode::OK) { - AERROR << "Failed to init vehicle controller."; - return false; - } - - AINFO << "The vehicle controller is successfully" - << " initialized with canbus conf as : " - << canbus_conf->vehicle_parameter().ShortDebugString(); - - node_ = ::apollo::cyber::CreateNode("chassis_detail"); - - chassis_detail_writer_ = - node_->CreateWriter<::apollo::canbus::Lexus>(FLAGS_chassis_detail_topic); - - return true; -} - -bool LexusVehicleFactory::Start() { - // 1. init and start the can card hardware - if (can_client_->Start() != ErrorCode::OK) { - AERROR << "Failed to start can client"; - return false; - } - AINFO << "Can client is started."; - - // 2. start receive first then send - if (can_receiver_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can receiver."; - return false; - } - AINFO << "Can receiver is started."; - - // 3. start send - if (can_sender_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can sender."; - return false; - } - - // 4. start controller - if (!vehicle_controller_->Start()) { - AERROR << "Failed to start vehicle controller."; - return false; - } - - return true; -} - -void LexusVehicleFactory::Stop() { - can_sender_.Stop(); - can_receiver_.Stop(); - can_client_->Stop(); - vehicle_controller_->Stop(); - AINFO << "Cleanup cansender, canreceiver, canclient, vehicle controller."; -} - -void LexusVehicleFactory::UpdateCommand( - const apollo::control::ControlCommand *control_command) { - if (vehicle_controller_->Update(*control_command) != ErrorCode::OK) { - AERROR << "Failed to process callback function OnControlCommand because " - "vehicle_controller_->Update error."; - return; - } - can_sender_.Update(); -} - -Chassis LexusVehicleFactory::publish_chassis() { - Chassis chassis = vehicle_controller_->chassis(); - ADEBUG << chassis.ShortDebugString(); - return chassis; -} - -void LexusVehicleFactory::PublishChassisDetail() { - Lexus chassis_detail; - message_manager_->GetSensorData(&chassis_detail); - ADEBUG << chassis_detail.ShortDebugString(); - chassis_detail_writer_->Write(chassis_detail); -} - -std::unique_ptr> -LexusVehicleFactory::CreateVehicleController() { - return std::unique_ptr>( - new lexus::LexusController()); -} - -std::unique_ptr> -LexusVehicleFactory::CreateMessageManager() { - return std::unique_ptr>( - new lexus::LexusMessageManager()); -} - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/lexus/lexus_vehicle_factory.h b/modules/canbus_vehicle/lexus/lexus_vehicle_factory.h deleted file mode 100644 index 0c5ba7dfa08..00000000000 --- a/modules/canbus_vehicle/lexus/lexus_vehicle_factory.h +++ /dev/null @@ -1,123 +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. - *****************************************************************************/ - -/** - * @file lexus_vehicle_factory.h - */ - -#pragma once - -#include - -#include "modules/canbus/proto/canbus_conf.pb.h" -#include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "modules/canbus_vehicle/lexus/proto/lexus.pb.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -#include "cyber/cyber.h" -#include "modules/canbus/vehicle/abstract_vehicle_factory.h" -#include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/common/status/status.h" -#include "modules/drivers/canbus/can_client/can_client.h" -#include "modules/drivers/canbus/can_comm/can_receiver.h" -#include "modules/drivers/canbus/can_comm/can_sender.h" -#include "modules/drivers/canbus/can_comm/message_manager.h" - -/** - * @namespace apollo::canbus - * @brief apollo::canbus - */ -namespace apollo { -namespace canbus { - -/** - * @class LexusVehicleFactory - * - * @brief this class is inherited from AbstractVehicleFactory. It can be used to - * create controller and message manager for lexus vehicle. - */ -class LexusVehicleFactory : public AbstractVehicleFactory { - public: - /** - * @brief destructor - */ - virtual ~LexusVehicleFactory() = default; - - /** - * @brief init vehicle factory - * @returns true if successfully initialized - */ - bool Init(const CanbusConf *canbus_conf) override; - - /** - * @brief start canclient, cansender, canreceiver, vehicle controller - * @returns true if successfully started - */ - bool Start() override; - - /** - * @brief create ch vehicle controller - * @returns a unique_ptr that points to the created controller - */ - void Stop() override; - - /** - * @brief update control command - */ - void UpdateCommand( - const apollo::control::ControlCommand *control_command) override; - - /** - * @brief publish chassis messages - */ - Chassis publish_chassis() override; - - /** - * @brief publish chassis for vehicle messages - */ - void PublishChassisDetail() override; - - private: - /** - * @brief create lexus vehicle controller - * @returns a unique_ptr that points to the created controller - */ - std::unique_ptr> - CreateVehicleController(); - - /** - * @brief create lexus message manager - * @returns a unique_ptr that points to the created message manager - */ - std::unique_ptr> - CreateMessageManager(); - - std::unique_ptr<::apollo::cyber::Node> node_ = nullptr; - std::unique_ptr can_client_; - CanSender<::apollo::canbus::Lexus> can_sender_; - apollo::drivers::canbus::CanReceiver<::apollo::canbus::Lexus> can_receiver_; - std::unique_ptr> message_manager_; - std::unique_ptr> - vehicle_controller_; - - std::shared_ptr<::apollo::cyber::Writer<::apollo::canbus::Lexus>> - chassis_detail_writer_; -}; - -CYBER_REGISTER_VEHICLEFACTORY(LexusVehicleFactory) - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/lexus/lexus_vehicle_factory_test.cc b/modules/canbus_vehicle/lexus/lexus_vehicle_factory_test.cc deleted file mode 100644 index ef2938e1b2e..00000000000 --- a/modules/canbus_vehicle/lexus/lexus_vehicle_factory_test.cc +++ /dev/null @@ -1,53 +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/canbus_vehicle/lexus/lexus_vehicle_factory.h" - -#include "gtest/gtest.h" - -#include "modules/canbus/proto/canbus_conf.pb.h" -#include "modules/canbus/proto/vehicle_parameter.pb.h" - -#include "cyber/common/file.h" - -namespace apollo { -namespace canbus { - -class LexusVehicleFactoryTest : public ::testing::Test { - public: - virtual void SetUp() { - std::string canbus_conf_file = - "modules/canbus/testdata/conf/lexus_canbus_conf_test.pb.txt"; - cyber::common::GetProtoFromFile(canbus_conf_file, &canbus_conf_); - params_ = canbus_conf_.vehicle_parameter(); - params_.set_brand(apollo::common::LEXUS); - lexus_factory_.SetVehicleParameter(params_); - } - virtual void TearDown() {} - - protected: - LexusVehicleFactory lexus_factory_; - CanbusConf canbus_conf_; - VehicleParameter params_; -}; - -TEST_F(LexusVehicleFactoryTest, Init) { - apollo::cyber::Init("vehicle_factory_test"); - EXPECT_EQ(lexus_factory_.Init(&canbus_conf_), true); -} - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/lexus/proto/BUILD b/modules/canbus_vehicle/lexus/proto/BUILD deleted file mode 100644 index 763cf4f077c..00000000000 --- a/modules/canbus_vehicle/lexus/proto/BUILD +++ /dev/null @@ -1,25 +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") - -package(default_visibility = ["//visibility:public"]) - -cc_proto_library( - name = "lexus_cc_proto", - deps = [ - ":lexus_proto", - ], -) - -proto_library( - name = "lexus_proto", - srcs = ["lexus.proto"], -) - -py_proto_library( - name = "lexus_py_pb2", - deps = [ - ":lexus_proto", - ], -) diff --git a/modules/canbus_vehicle/lexus/protocol/BUILD b/modules/canbus_vehicle/lexus/protocol/BUILD deleted file mode 100644 index 2a7b5e74379..00000000000 --- a/modules/canbus_vehicle/lexus/protocol/BUILD +++ /dev/null @@ -1,24 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_library") -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] - -cc_library( - name = "canbus_lexus_protocol", - srcs = glob([ - "*.cc", - ]), - hdrs = glob([ - "*.h", - ]), - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/lexus/proto:lexus_cc_proto", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cpplint() diff --git a/modules/canbus_vehicle/lexus/testdata/lexus_canbus_conf_test.pb.txt b/modules/canbus_vehicle/lexus/testdata/lexus_canbus_conf_test.pb.txt deleted file mode 100644 index c103b83f42d..00000000000 --- a/modules/canbus_vehicle/lexus/testdata/lexus_canbus_conf_test.pb.txt +++ /dev/null @@ -1,13 +0,0 @@ -vehicle_parameter { - brand: LEXUS - max_enable_fail_attempt: 5 - driving_mode: COMPLETE_AUTO_DRIVE -} - -can_card_parameter { - brand:SOCKET_CAN_RAW - type: PCI_CARD - channel_id: CHANNEL_ID_ZERO -} - -enable_debug_mode: false diff --git a/modules/canbus_vehicle/lincoln/BUILD b/modules/canbus_vehicle/lincoln/BUILD deleted file mode 100644 index 05a7f876b93..00000000000 --- a/modules/canbus_vehicle/lincoln/BUILD +++ /dev/null @@ -1,161 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "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"]) - -CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] - -cc_library( - name = "lincoln_vehicle_factory", - srcs = ["lincoln_vehicle_factory.cc"], - hdrs = ["lincoln_vehicle_factory.h"], - copts = CANBUS_COPTS, - alwayslink = True, - deps = [ - ":lincoln_controller", - ":lincoln_message_manager", - "//modules/canbus/common:canbus_gflags", - "//modules/common/adapters:adapter_gflags", - "//modules/common/status", - "//modules/canbus/vehicle:abstract_vehicle_factory", - "//modules/drivers/canbus:sensor_canbus_lib", - ], -) - -cc_binary( - name = "liblincoln_vehicle_factory_lib.so", - linkshared = True, - linkstatic = True, - deps = [":lincoln_vehicle_factory"], -) - -cc_library( - name = "lincoln_message_manager", - srcs = ["lincoln_message_manager.cc"], - hdrs = ["lincoln_message_manager.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/lincoln/proto:lincoln_cc_proto", - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_library( - name = "lincoln_controller", - srcs = ["lincoln_controller.cc"], - hdrs = ["lincoln_controller.h"], - copts = CANBUS_COPTS, - deps = [ - ":lincoln_message_manager", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/canbus_vehicle/lincoln/proto:lincoln_cc_proto", - "//modules/canbus/vehicle:vehicle_controller_base", - "//modules/canbus_vehicle/lincoln/protocol:canbus_lincoln_protocol", - "//modules/common/kv_db", - "//modules/drivers/canbus/can_comm:can_sender", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - "@com_google_googletest//:gtest", - ], -) - -cc_test( - name = "lincoln_controller_test", - size = "small", - srcs = ["lincoln_controller_test.cc"], - data = ["//modules/canbus:test_data"], - deps = [ - "//modules/canbus_vehicle/lincoln:lincoln_controller", - "@com_google_googletest//:gtest_main", - ], -) - -cc_test( - name = "lincoln_message_manager_test", - size = "small", - srcs = ["lincoln_message_manager_test.cc"], - deps = [ - "//modules/canbus_vehicle/lincoln:lincoln_message_manager", - "@com_google_googletest//:gtest_main", - ], -) - -cc_test( - name = "lincoln_vehicle_factory_test", - size = "small", - srcs = ["lincoln_vehicle_factory_test.cc"], - data = ["//modules/canbus:test_data"], - linkstatic = True, - deps = [ - ":lincoln_vehicle_factory", - "@com_google_googletest//:gtest_main", - ], -) - -install( - name = "install", - library_dest = "canbus-vehicle-lincoln/lib", - data_dest = "canbus-vehicle-lincoln", - data = [ - ":runtime_data", - ":cyberfile.xml", - ":canbus-vehicle-lincoln.BUILD", - ], - targets = [ - ":liblincoln_vehicle_factory_lib.so", - ], - deps = [ - ":pb_lincoln", - ":pb_hdrs", - ], -) - -install( - name = "pb_hdrs", - data_dest = "canbus-vehicle-lincoln/include", - data = [ - "//modules/canbus_vehicle/lincoln/proto:lincoln_cc_proto", - ], -) - -install_files( - name = "pb_lincoln", - dest = "canbus-vehicle-lincoln", - files = [ - "//modules/canbus_vehicle/lincoln/proto:lincoln_py_pb2", - ], -) - -filegroup( - name = "runtime_data", - srcs = glob([ - "testdata/**", - ]), -) - -install_src_files( - name = "install_src", - deps = [ - ":install_lincoln_src", - ":install_lincoln_hdrs" - ], -) - -install_src_files( - name = "install_lincoln_src", - src_dir = ["."], - dest = "canbus-vehicle-lincoln/src", - filter = "*", -) - -install_src_files( - name = "install_lincoln_hdrs", - src_dir = ["."], - dest = "canbus-vehicle-lincoln/include", - filter = "*.h", -) - -cpplint() diff --git a/modules/canbus_vehicle/lincoln/canbus-vehicle-lincoln.BUILD b/modules/canbus_vehicle/lincoln/canbus-vehicle-lincoln.BUILD deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/modules/canbus_vehicle/lincoln/cyberfile.xml b/modules/canbus_vehicle/lincoln/cyberfile.xml deleted file mode 100644 index 6e0b6c3c1d6..00000000000 --- a/modules/canbus_vehicle/lincoln/cyberfile.xml +++ /dev/null @@ -1,24 +0,0 @@ - - canbus-vehicle-lincoln - local - - Dynamic loading for canbus module - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/canbus_vehicle/lincoln - - cyber-dev - common-dev - canbus-dev - common-msgs-dev - drivers-dev - 3rd-gtest-dev - - \ No newline at end of file diff --git a/modules/canbus_vehicle/lincoln/lincoln_vehicle_factory.cc b/modules/canbus_vehicle/lincoln/lincoln_vehicle_factory.cc deleted file mode 100644 index 380c2ca1ac4..00000000000 --- a/modules/canbus_vehicle/lincoln/lincoln_vehicle_factory.cc +++ /dev/null @@ -1,165 +0,0 @@ -/****************************************************************************** - * Copyright 2017 The Apollo Authors. All Rights Reserved. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - *****************************************************************************/ - -#include "modules/canbus_vehicle/lincoln/lincoln_vehicle_factory.h" - -#include "cyber/common/log.h" -#include "modules/canbus/common/canbus_gflags.h" -#include "modules/canbus_vehicle/lincoln/lincoln_controller.h" -#include "modules/canbus_vehicle/lincoln/lincoln_message_manager.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common/util/util.h" -#include "modules/drivers/canbus/can_client/can_client_factory.h" - -using apollo::common::ErrorCode; -using apollo::control::ControlCommand; -using apollo::drivers::canbus::CanClientFactory; - -namespace apollo { -namespace canbus { - -bool LincolnVehicleFactory::Init(const CanbusConf *canbus_conf) { - // Init can client - auto can_factory = CanClientFactory::Instance(); - can_factory->RegisterCanClients(); - can_client_ = can_factory->CreateCANClient(canbus_conf->can_card_parameter()); - if (!can_client_) { - AERROR << "Failed to create can client."; - return false; - } - AINFO << "Can client is successfully created."; - - message_manager_ = this->CreateMessageManager(); - if (message_manager_ == nullptr) { - AERROR << "Failed to create message manager."; - return false; - } - AINFO << "Message manager is successfully created."; - - if (can_receiver_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_receiver_log()) != ErrorCode::OK) { - AERROR << "Failed to init can receiver."; - return false; - } - AINFO << "The can receiver is successfully initialized."; - - if (can_sender_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_sender_log()) != ErrorCode::OK) { - AERROR << "Failed to init can sender."; - return false; - } - AINFO << "The can sender is successfully initialized."; - - vehicle_controller_ = CreateVehicleController(); - if (vehicle_controller_ == nullptr) { - AERROR << "Failed to create vehicle controller."; - return false; - } - AINFO << "The vehicle controller is successfully created."; - - if (vehicle_controller_->Init(canbus_conf->vehicle_parameter(), &can_sender_, - message_manager_.get()) != ErrorCode::OK) { - AERROR << "Failed to init vehicle controller."; - return false; - } - - AINFO << "The vehicle controller is successfully" - << " initialized with canbus conf as : " - << canbus_conf->vehicle_parameter().ShortDebugString(); - - node_ = ::apollo::cyber::CreateNode("chassis_detail"); - - chassis_detail_writer_ = node_->CreateWriter<::apollo::canbus::Lincoln>( - FLAGS_chassis_detail_topic); - - return true; -} - -bool LincolnVehicleFactory::Start() { - // 1. init and start the can card hardware - if (can_client_->Start() != ErrorCode::OK) { - AERROR << "Failed to start can client"; - return false; - } - AINFO << "Can client is started."; - - // 2. start receive first then send - if (can_receiver_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can receiver."; - return false; - } - AINFO << "Can receiver is started."; - - // 3. start send - if (can_sender_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can sender."; - return false; - } - - // 4. start controller - if (!vehicle_controller_->Start()) { - AERROR << "Failed to start vehicle controller."; - return false; - } - - return true; -} - -void LincolnVehicleFactory::Stop() { - can_sender_.Stop(); - can_receiver_.Stop(); - can_client_->Stop(); - vehicle_controller_->Stop(); - AINFO << "Cleanup cansender, canreceiver, canclient, vehicle controller."; -} - -void LincolnVehicleFactory::UpdateCommand( - const apollo::control::ControlCommand *control_command) { - if (vehicle_controller_->Update(*control_command) != ErrorCode::OK) { - AERROR << "Failed to process callback function OnControlCommand because " - "vehicle_controller_->Update error."; - return; - } - can_sender_.Update(); -} - -Chassis LincolnVehicleFactory::publish_chassis() { - Chassis chassis = vehicle_controller_->chassis(); - ADEBUG << chassis.ShortDebugString(); - return chassis; -} - -void LincolnVehicleFactory::PublishChassisDetail() { - Lincoln chassis_detail; - message_manager_->GetSensorData(&chassis_detail); - ADEBUG << chassis_detail.ShortDebugString(); - chassis_detail_writer_->Write(chassis_detail); -} - -std::unique_ptr> -LincolnVehicleFactory::CreateVehicleController() { - return std::unique_ptr>( - new lincoln::LincolnController()); -} - -std::unique_ptr> -LincolnVehicleFactory::CreateMessageManager() { - return std::unique_ptr>( - new lincoln::LincolnMessageManager()); -} - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/lincoln/lincoln_vehicle_factory.h b/modules/canbus_vehicle/lincoln/lincoln_vehicle_factory.h deleted file mode 100644 index 1bac1712871..00000000000 --- a/modules/canbus_vehicle/lincoln/lincoln_vehicle_factory.h +++ /dev/null @@ -1,122 +0,0 @@ -/****************************************************************************** - * Copyright 2017 The Apollo Authors. All Rights Reserved. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - *****************************************************************************/ - -/** - * @file lincoln_vehicle_factory.h - */ - -#pragma once - -#include - -#include "modules/canbus/proto/canbus_conf.pb.h" -#include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "modules/canbus_vehicle/lincoln/proto/lincoln.pb.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -#include "cyber/cyber.h" -#include "modules/canbus/vehicle/abstract_vehicle_factory.h" -#include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/common/status/status.h" -#include "modules/drivers/canbus/can_client/can_client.h" -#include "modules/drivers/canbus/can_comm/can_receiver.h" -#include "modules/drivers/canbus/can_comm/can_sender.h" -#include "modules/drivers/canbus/can_comm/message_manager.h" - -/** - * @namespace apollo::canbus - * @brief apollo::canbus - */ -namespace apollo { -namespace canbus { - -/** - * @class LincolnVehicleFactory - * - * @brief this class is inherited from AbstractVehicleFactory. It can be used to - * create controller and message manager for lincoln vehicle. - */ -class LincolnVehicleFactory : public AbstractVehicleFactory { - public: - /** - * @brief destructor - */ - virtual ~LincolnVehicleFactory() = default; - - /** - * @brief init vehicle factory - * @returns true if successfully initialized - */ - bool Init(const CanbusConf *canbus_conf) override; - - /** - * @brief start canclient, cansender, canreceiver, vehicle controller - * @returns true if successfully started - */ - bool Start() override; - - /** - * @brief stop canclient, cansender, canreceiver, vehicle controller - */ - void Stop() override; - - /** - * @brief update control command - */ - void UpdateCommand( - const apollo::control::ControlCommand *control_command) override; - - /** - * @brief publish chassis messages - */ - Chassis publish_chassis() override; - - /** - * @brief publish chassis for vehicle messages - */ - void PublishChassisDetail() override; - - private: - /** - * @brief create Lincoln vehicle controller - * @returns a unique_ptr that points to the created controller - */ - std::unique_ptr> - CreateVehicleController(); - - /** - * @brief create lincoln message manager - * @returns a unique_ptr that points to the created message manager - */ - std::unique_ptr> - CreateMessageManager(); - - std::unique_ptr<::apollo::cyber::Node> node_ = nullptr; - std::unique_ptr can_client_; - CanSender<::apollo::canbus::Lincoln> can_sender_; - apollo::drivers::canbus::CanReceiver<::apollo::canbus::Lincoln> can_receiver_; - std::unique_ptr> message_manager_; - std::unique_ptr> - vehicle_controller_; - - std::shared_ptr<::apollo::cyber::Writer<::apollo::canbus::Lincoln>> - chassis_detail_writer_; -}; - -CYBER_REGISTER_VEHICLEFACTORY(LincolnVehicleFactory) - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/lincoln/proto/BUILD b/modules/canbus_vehicle/lincoln/proto/BUILD deleted file mode 100644 index 383c2dcae60..00000000000 --- a/modules/canbus_vehicle/lincoln/proto/BUILD +++ /dev/null @@ -1,30 +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") - -package(default_visibility = ["//visibility:public"]) - -cc_proto_library( - name = "lincoln_cc_proto", - deps = [ - ":lincoln_proto", - ], -) - -proto_library( - name = "lincoln_proto", - srcs = ["lincoln.proto"], - deps = [ - "//modules/common_msgs/basic_msgs:geometry_proto", - "//modules/common_msgs/basic_msgs:vehicle_id_proto", - "//modules/common_msgs/chassis_msgs:chassis_proto", - ] -) - -py_proto_library( - name = "lincoln_py_pb2", - deps = [ - ":lincoln_proto", - ], -) diff --git a/modules/canbus_vehicle/lincoln/proto/lincoln.proto b/modules/canbus_vehicle/lincoln/proto/lincoln.proto deleted file mode 100644 index ac4798bb3a0..00000000000 --- a/modules/canbus_vehicle/lincoln/proto/lincoln.proto +++ /dev/null @@ -1,504 +0,0 @@ -syntax = "proto2"; - -package apollo.canbus; - -import "modules/common_msgs/basic_msgs/vehicle_id.proto"; -import "modules/common_msgs/basic_msgs/geometry.proto"; -import "modules/common_msgs/chassis_msgs/chassis.proto"; - -message Lincoln { - enum Type { - QIRUI_EQ_15 = 0; - CHANGAN_RUICHENG = 1; - } - optional Type car_type = 1; // car type - optional BasicInfo basic = 2; // basic info - optional Safety safety = 3; // safety - optional Gear gear = 4; // gear - optional Ems ems = 5; // engine manager system - optional Esp esp = 6; // Electronic Stability Program - optional Gas gas = 7; // gas pedal - optional Epb epb = 8; // Electronic parking brake - optional Brake brake = 9; // brake pedal - optional Deceleration deceleration = 10; // deceleration - optional VehicleSpd vehicle_spd = 11; // vehicle speed - optional Eps eps = 12; // Electronic Power Steering - optional Light light = 13; // Light - optional Battery battery = 14; // Battery info - optional CheckResponseSignal check_response = 15; - optional Surround surround = 17; // Surround information - // Reserve fields for other vehicles - optional apollo.common.VehicleID vehicle_id = 101; -} - -// CheckResponseSignal -message CheckResponseSignal { - optional bool is_eps_online = 1 [default = false]; // byd:0x34C qirui:0x505 - optional bool is_epb_online = 2 [default = false]; // byd:0x218 - optional bool is_esp_online = 3 [default = false]; // byd:0x122 qirui:0x451 - optional bool is_vtog_online = 4 [default = false]; // byd:0x242 - optional bool is_scu_online = 5 [default = false]; // byd:0x35C - optional bool is_switch_online = 6 [default = false]; // byd:0x133 - optional bool is_vcu_online = 7 [default = false]; // qirui:0x400 -} - -// Battery -message Battery { - optional double battery_percent = 1; // unit:%, battery percentage left - // lincoln fuellevel 72 - optional double fuel_level = 2; -} - -// light -message Light { - enum TurnLightType { - TURN_LIGHT_OFF = 0; - TURN_LEFT_ON = 1; - TURN_RIGHT_ON = 2; - TURN_LIGHT_ON = 3; - } - enum BeamLampType { - BEAM_OFF = 0; - HIGH_BEAM_ON = 1; - LOW_BEAM_ON = 2; - } - enum LincolnLampType { - BEAM_NULL = 0; - BEAM_FLASH_TO_PASS = 1; - BEAM_HIGH = 2; - BEAM_INVALID = 3; - } - enum LincolnWiperType { - WIPER_OFF = 0; - WIPER_AUTO_OFF = 1; - WIPER_OFF_MOVING = 2; - WIPER_MANUAL_OFF = 3; - WIPER_MANUAL_ON = 4; - WIPER_MANUAL_LOW = 5; - WIPER_MANUAL_HIGH = 6; - WIPER_MIST_FLICK = 7; - WIPER_WASH = 8; - WIPER_AUTO_LOW = 9; - WIPER_AUTO_HIGH = 10; - WIPER_COURTESY_WIPE = 11; - WIPER_AUTO_ADJUST = 12; - WIPER_RESERVED = 13; - WIPER_STALLED = 14; - WIPER_NO_DATA = 15; - } - enum LincolnAmbientType { - AMBIENT_DARK = 0; - AMBIENT_LIGHT = 1; - AMBIENT_TWILIGHT = 2; - AMBIENT_TUNNEL_ON = 3; - AMBIENT_TUNNEL_OFF = 4; - AMBIENT_INVALID = 5; - AMBIENT_NO_DATA = 7; - } - - optional TurnLightType turn_light_type = 1; - optional BeamLampType beam_lamp_type = 2; - optional bool is_brake_lamp_on = 3; - // byd switch 133 - optional bool is_auto_light = 4; - optional int32 wiper_gear = 5; - optional int32 lotion_gear = 6; - optional bool is_horn_on = 7; - - // lincoln misc 69 - optional LincolnLampType lincoln_lamp_type = 8; - optional LincolnWiperType lincoln_wiper = 9; - optional LincolnAmbientType lincoln_ambient = 10; -} - -// Electrical Power Steering -message Eps { - enum Type { - NOT_AVAILABLE = 0; - READY = 1; - ACTIVE = 2; - INVALID = 3; - } - // changan: eps 2a0 - optional bool is_eps_fail = 1; - // eps 2a0 - optional Type eps_control_state = 2; // for changan to control steering - optional double eps_driver_hand_torq = 3; // unit:Nm - - optional bool is_steering_angle_valid = 4; - optional double steering_angle = 5; // unit:degree - optional double steering_angle_spd = 6; // unit:degree/s - - // byd sas 11f - optional bool is_trimming_status = 7; - optional bool is_calibration_status = 8; - optional bool is_failure_status = 9; - optional int32 allow_enter_autonomous_mode = 10; - optional int32 current_driving_mode = 11; - - // lincoln steering 65 - optional double steering_angle_cmd = 12; - optional double vehicle_speed = 13; - optional double epas_torque = 14; - optional bool steering_enabled = 15; - optional bool driver_override = 16; - optional bool driver_activity = 17; - optional bool watchdog_fault = 18; - optional bool channel_1_fault = 19; - optional bool channel_2_fault = 20; - optional bool calibration_fault = 21; - optional bool connector_fault = 22; - - optional double timestamp_65 = 23; - - // lincoln version 7f - optional int32 major_version = 24; - optional int32 minor_version = 25; - optional int32 build_number = 26; -} - -message VehicleSpd { - // esp 277 - optional bool is_vehicle_standstill = 1; - // esp 218 - optional bool is_vehicle_spd_valid = 2; - optional double vehicle_spd = 3 [default = 0]; // unit:m/s - // esp 208 - optional bool is_wheel_spd_rr_valid = 4; - optional WheelSpeed.WheelSpeedType wheel_direction_rr = 5; - optional double wheel_spd_rr = 6; - optional bool is_wheel_spd_rl_valid = 7; - optional WheelSpeed.WheelSpeedType wheel_direction_rl = 8; - optional double wheel_spd_rl = 9; - optional bool is_wheel_spd_fr_valid = 10; - optional WheelSpeed.WheelSpeedType wheel_direction_fr = 11; - optional double wheel_spd_fr = 12; - optional bool is_wheel_spd_fl_valid = 13; - optional WheelSpeed.WheelSpeedType wheel_direction_fl = 14; - optional double wheel_spd_fl = 15; - - // byd esp 222 - optional bool is_yaw_rate_valid = 16; - optional double yaw_rate = 17; - optional double yaw_rate_offset = 18; - - // byd esp 223 - optional bool is_ax_valid = 19; - optional double ax = 20; - optional double ax_offset = 21; - optional bool is_ay_valid = 22; - optional double ay = 23; - optional double ay_offset = 24; - - // lincoln accel 6b - optional double lat_acc = 25; - optional double long_acc = 26; - optional double vert_acc = 27; - - // lincoln gyro 6c - optional double roll_rate = 28; - - // lincoln brakeinfo 74 - optional double acc_est = 29; - - // lincoln wheelspeed 6a - optional double timestamp_sec = 30; -} - -message Deceleration { - // esp 277 - optional bool is_deceleration_available = - 1; // for changan to send deceleration value - optional bool is_deceleration_active = - 2; // for changan to send deceleration value - - optional double deceleration = 3 [default = 0]; - - optional double is_evb_fail = 4; - optional double evb_pressure = 5 [default = 0]; // mpa, 0~25.5 - - optional double brake_pressure = 6 [default = 0]; - optional double brake_pressure_spd = 7 [default = 0]; -} - -message Brake { - enum HSAStatusType { - HSA_INACTIVE = 0; - HSA_FINDING_GRADIENT = 1; - HSA_ACTIVE_PRESSED = 2; - HSA_ACTIVE_RELEASED = 3; - HSA_FAST_RELEASE = 4; - HSA_SLOW_RELEASE = 5; - HSA_FAILED = 6; - HSA_UNDEFINED = 7; - } - enum HSAModeType { - HSA_OFF = 0; - HSA_AUTO = 1; - HSA_MANUAL = 2; - HSA_MODE_UNDEFINED = 3; - } - // ems 255 - optional bool is_brake_pedal_pressed = 1 - [default = false]; // only manual brake - // esp 277 - optional bool is_brake_force_exist = - 2; // no matter auto mode brake or manual brake - optional bool is_brake_over_heat = 3; - - optional bool is_hand_brake_on = 4; // hand brake - optional double brake_pedal_position = 5; - - // byd vtog 342 - optional bool is_brake_valid = 6; - - // lincoln brake 61 - optional double brake_input = 7; - optional double brake_cmd = 8; - optional double brake_output = 9; - optional bool boo_input = 10; - optional bool boo_cmd = 11; - optional bool boo_output = 12; - optional bool watchdog_applying_brakes = 13; - optional int32 watchdog_source = 14; - optional bool brake_enabled = 15; - optional bool driver_override = 16; - optional bool driver_activity = 17; - optional bool watchdog_fault = 18; - optional bool channel_1_fault = 19; - optional bool channel_2_fault = 20; - optional bool boo_fault = 21; - optional bool connector_fault = 22; - - // lincoln brakeinfo 74 - optional double brake_torque_req = 23; - optional HSAStatusType hsa_status = 24; - optional double brake_torque_act = 25; - optional HSAModeType hsa_mode = 26; - optional double wheel_torque_act = 27; - - // lincoln version 7f - optional int32 major_version = 28; - optional int32 minor_version = 29; - optional int32 build_number = 30; -} - -// Electrical Parking Brake -message Epb { - enum PBrakeType { - PBRAKE_OFF = 0; - PBRAKE_TRANSITION = 1; - PBRAKE_ON = 2; - PBRAKE_FAULT = 3; - } - // epb 256 - optional bool is_epb_error = 1; - optional bool is_epb_released = 2; - - // byd epb 218 - optional int32 epb_status = 3; - - // lincoln brakeinfo 74 - optional PBrakeType parking_brake_status = 4; -} - -message Gas { - // ems 255 - optional bool is_gas_pedal_error = 1; - // ems 26a - optional bool is_gas_pedal_pressed_more = 2; // more than auto mode gas torq - optional double gas_pedal_position = 3 [default = 0]; // manual gas - // byd vtog 342 - optional bool is_gas_valid = 4 [default = false]; - - // lincoln throttle 63 - optional double throttle_input = 5; - optional double throttle_cmd = 6; - optional double throttle_output = 7; - optional int32 watchdog_source = 8; - optional bool throttle_enabled = 9; - optional bool driver_override = 10; - optional bool driver_activity = 11; - optional bool watchdog_fault = 12; - optional bool channel_1_fault = 13; - optional bool channel_2_fault = 14; - optional bool connector_fault = 15; - - // lincoln throttleinfo 75 - optional double accelerator_pedal = 16; - optional double accelerator_pedal_rate = 17; - - // lincoln version 7f - optional int32 major_version = 18; - optional int32 minor_version = 19; - optional int32 build_number = 20; -} - -// Electronic Stability Program -message Esp { - // esp 277 - optional bool is_esp_acc_error = 1; // for changan to control car - - // esp 218 - optional bool is_esp_on = 2; - optional bool is_esp_active = 3; - optional bool is_abs_error = 4; - optional bool is_abs_active = 5; - optional bool is_tcsvdc_fail = 6; - - // lincoln brakeinfo 74 - optional bool is_abs_enabled = 7; - optional bool is_stab_active = 8; - optional bool is_stab_enabled = 9; - optional bool is_trac_active = 10; - optional bool is_trac_enabled = 11; -} - -// Engine Manager System -message Ems { - enum Type { - STOP = 0; - CRANK = 1; - RUNNING = 2; - INVALID = 3; - } - // ems 26a - optional bool is_engine_acc_available = 1; // for changan to control car - optional bool is_engine_acc_error = 2; // for changan to control car - - // ems 265 - optional Type engine_state = 3; - optional double max_engine_torq_percent = 4; // for engine torq control, unit:% - optional double min_engine_torq_percent = 5; // for engine torq control, unit:% - optional int32 base_engine_torq_constant = 6; // for engine torq control, unit:Nm - - // ems 255 - optional bool is_engine_speed_error = 7; - optional double engine_speed = 8; - - // byd vtog 241 - optional int32 engine_torque = 9; - // byd vtog 242 - optional bool is_over_engine_torque = 10; - - // lincoln mkz throttleinfo 75 - optional double engine_rpm = 11; -} - -message Gear { - // tcu 268 - optional bool is_shift_position_valid = 1; - // chanan: tcu 268 - optional Chassis.GearPosition gear_state = 2; - // lincoln gear 67 - optional bool driver_override = 3; - optional Chassis.GearPosition gear_cmd = 4; - optional bool canbus_fault = 5; -} - - -message Safety { - // ip 270 - optional bool is_driver_car_door_close = 1; - // sas 50 - optional bool is_driver_buckled = 2; - - // byd sws 4a8 - optional int32 emergency_button = 3; - - // qirui:403 - // when car chassis error, like system fault, or warning report - optional bool has_error = 4 [default = false]; - optional bool is_motor_invertor_fault = 5; - optional bool is_system_fault = 6; - optional bool is_power_battery_fault = 7; - optional bool is_motor_invertor_over_temperature = 8; - optional bool is_small_battery_charge_discharge_fault = 9; - optional int32 driving_mode = 10; - - // lincoln misc 69 - optional bool is_passenger_door_open = 11; - optional bool is_rearleft_door_open = 12; - optional bool is_rearright_door_open = 13; - optional bool is_hood_open = 14; - optional bool is_trunk_open = 15; - optional bool is_passenger_detected = 16; - optional bool is_passenger_airbag_enabled = 17; - optional bool is_passenger_buckled = 18; - - // lincoln tirepressure 71 - optional int32 front_left_tire_press = 19; - optional int32 front_right_tire_press = 20; - optional int32 rear_left_tire_press = 21; - optional int32 rear_right_tire_press = 22; - optional DrivingMode car_driving_mode = 23; -} - -enum DrivingMode { - COMPLETE_MANUAL = 0; // human drive - COMPLETE_AUTO_DRIVE = 1; - AUTO_STEER_ONLY = 2; // only steer - AUTO_SPEED_ONLY = 3; // include throttle and brake - - // security mode when manual intervention happens, only response status - EMERGENCY_MODE = 4; -} - -message BasicInfo { - enum Type { - OFF = 0; - ACC = 1; - ON = 2; - START = 3; - INVALID = 4; - } - - optional bool is_auto_mode = 1; - optional Type power_state = 2; - optional bool is_air_bag_deployed = 3; - optional double odo_meter = 4; // odo meter, unit:km - optional double drive_range = - 5; // the meter left when drive continuously, unit:km - optional bool is_system_error = 6; - optional bool is_human_interrupt = 7; // human interrupt - - // lincoln misc 69 - optional bool acc_on_button = 8; // acc on button pressed - optional bool acc_off_button = 9; - optional bool acc_res_button = 10; - optional bool acc_cancel_button = 11; - optional bool acc_on_off_button = 12; - optional bool acc_res_cancel_button = 13; - optional bool acc_inc_spd_button = 14; - optional bool acc_dec_spd_button = 15; - optional bool acc_inc_gap_button = 16; - optional bool acc_dec_gap_button = 17; - optional bool lka_button = 18; - optional bool canbus_fault = 19; - - // lincoln gps 6d - optional double latitude = 20; - optional double longitude = 21; - optional bool gps_valid = 22; - - // lincoln gps 6e - optional int32 year = 23; - optional int32 month = 24; - optional int32 day = 25; - optional int32 hours = 26; - optional int32 minutes = 27; - optional int32 seconds = 28; - optional double compass_direction = 29; - optional double pdop = 30; - optional bool is_gps_fault = 31; - optional bool is_inferred = 32; - - // lincoln gps 6f - optional double altitude = 33; - optional double heading = 34; - optional double hdop = 35; - optional double vdop = 36; - optional GpsQuality quality = 37; - optional int32 num_satellites = 38; - optional double gps_speed = 39; -} diff --git a/modules/canbus_vehicle/lincoln/testdata/mkz_canbus_conf_test.pb.txt b/modules/canbus_vehicle/lincoln/testdata/mkz_canbus_conf_test.pb.txt deleted file mode 100644 index 1a4fbb05a86..00000000000 --- a/modules/canbus_vehicle/lincoln/testdata/mkz_canbus_conf_test.pb.txt +++ /dev/null @@ -1,13 +0,0 @@ -vehicle_parameter { - brand: LINCOLN_MKZ - max_enable_fail_attempt: 5 - driving_mode: COMPLETE_AUTO_DRIVE -} - -can_card_parameter { - brand:SOCKET_CAN_RAW - type: PCI_CARD - channel_id: CHANNEL_ID_ZERO -} - -enable_debug_mode: false diff --git a/modules/canbus_vehicle/neolix_edu/BUILD b/modules/canbus_vehicle/neolix_edu/BUILD deleted file mode 100644 index 65f45f6545f..00000000000 --- a/modules/canbus_vehicle/neolix_edu/BUILD +++ /dev/null @@ -1,170 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "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"]) - -CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] - -cc_library( - name = "neolix_edu_vehicle_factory", - srcs = [ - "neolix_edu_vehicle_factory.cc", - ], - hdrs = [ - "neolix_edu_vehicle_factory.h", - ], - copts = CANBUS_COPTS, - alwayslink = True, - deps = [ - ":neolix_edu_controller", - ":neolix_edu_message_manager", - "//modules/canbus/common:canbus_gflags", - "//modules/common/adapters:adapter_gflags", - "//modules/common/status", - "//modules/canbus/vehicle:abstract_vehicle_factory", - "//modules/drivers/canbus:sensor_canbus_lib", - ], -) - -cc_binary( - name = "libneolix_edu_vehicle_factory_lib.so", - linkshared = True, - linkstatic = True, - deps = [":neolix_edu_vehicle_factory"], -) - -cc_library( - name = "neolix_edu_message_manager", - srcs = [ - "neolix_edu_message_manager.cc", - ], - hdrs = [ - "neolix_edu_message_manager.h", - ], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/neolix_edu/proto:neolix_edu_cc_proto", - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_library( - name = "neolix_edu_controller", - srcs = [ - "neolix_edu_controller.cc", - ], - hdrs = [ - "neolix_edu_controller.h", - ], - copts = CANBUS_COPTS, - deps = [ - ":neolix_edu_message_manager", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/canbus/vehicle:vehicle_controller_base", - "//modules/canbus_vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol", - "//modules/drivers/canbus/can_comm:can_sender", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_test( - name = "neolix_edu_controller_test", - size = "small", - srcs = ["neolix_edu_controller_test.cc"], - data = ["//modules/canbus:test_data"], - deps = [ - ":neolix_edu_controller", - "@com_google_googletest//:gtest_main", - ], -) - -cc_test( - name = "neolix_edu_message_manager_test", - size = "small", - srcs = ["neolix_edu_message_manager_test.cc"], - deps = [ - ":neolix_edu_message_manager", - "@com_google_googletest//:gtest_main", - ], -) - -cc_test( - name = "neolix_edu_vehicle_factory_test", - size = "small", - srcs = ["neolix_edu_vehicle_factory_test.cc"], - data = ["//modules/canbus:test_data"], - linkstatic = True, - deps = [ - ":neolix_edu_vehicle_factory", - "@com_google_googletest//:gtest_main", - ], -) - -install( - name = "install", - library_dest = "canbus-vehicle-neolix-edu/lib", - data_dest = "canbus-vehicle-neolix-edu", - data = [ - ":runtime_data", - ":cyberfile.xml", - ":canbus-vehicle-neolix-edu.BUILD", - ], - targets = [ - ":libneolix_edu_vehicle_factory_lib.so", - ], - deps = [ - ":pb_neolix_edu", - ":pb_hdrs", - ], -) - -install( - name = "pb_hdrs", - data_dest = "canbus-vehicle-neolix-edu/include", - data = [ - "//modules/canbus_vehicle/neolix_edu/proto:neolix_edu_cc_proto", - ], -) - -install_files( - name = "pb_neolix_edu", - dest = "canbus-vehicle-neolix-edu", - files = [ - "//modules/canbus_vehicle/neolix_edu/proto:neolix_edu_py_pb2", - ], -) - -filegroup( - name = "runtime_data", - srcs = glob([ - "testdata/**", - ]), -) - -install_src_files( - name = "install_src", - deps = [ - ":install_neolix_edu_src", - ":install_neolix_edu_hdrs" - ], -) - -install_src_files( - name = "install_neolix_edu_src", - src_dir = ["."], - dest = "canbus-vehicle-neolix-edu/src", - filter = "*", -) - -install_src_files( - name = "install_neolix_edu_hdrs", - src_dir = ["."], - dest = "canbus-vehicle-neolix-edu/include", - filter = "*.h", -) - -cpplint() diff --git a/modules/canbus_vehicle/neolix_edu/canbus-vehicle-neolix-edu.BUILD b/modules/canbus_vehicle/neolix_edu/canbus-vehicle-neolix-edu.BUILD deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/modules/canbus_vehicle/neolix_edu/cyberfile.xml b/modules/canbus_vehicle/neolix_edu/cyberfile.xml deleted file mode 100644 index f1795419483..00000000000 --- a/modules/canbus_vehicle/neolix_edu/cyberfile.xml +++ /dev/null @@ -1,24 +0,0 @@ - - canbus-vehicle-neolix-edu - local - - Dynamic loading for canbus module - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/canbus_vehicle/neolix_edu - - cyber-dev - common-dev - canbus-dev - common-msgs-dev - drivers-dev - 3rd-gtest-dev - - \ No newline at end of file diff --git a/modules/canbus_vehicle/neolix_edu/neolix_edu_vehicle_factory.cc b/modules/canbus_vehicle/neolix_edu/neolix_edu_vehicle_factory.cc deleted file mode 100644 index c38b7877f35..00000000000 --- a/modules/canbus_vehicle/neolix_edu/neolix_edu_vehicle_factory.cc +++ /dev/null @@ -1,165 +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/canbus_vehicle/neolix_edu/neolix_edu_vehicle_factory.h" - -#include "cyber/common/log.h" -#include "modules/canbus/common/canbus_gflags.h" -#include "modules/canbus_vehicle/neolix_edu/neolix_edu_controller.h" -#include "modules/canbus_vehicle/neolix_edu/neolix_edu_message_manager.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common/util/util.h" -#include "modules/drivers/canbus/can_client/can_client_factory.h" - -using apollo::common::ErrorCode; -using apollo::control::ControlCommand; -using apollo::drivers::canbus::CanClientFactory; - -namespace apollo { -namespace canbus { - -bool Neolix_eduVehicleFactory::Init(const CanbusConf *canbus_conf) { - // Init can client - auto can_factory = CanClientFactory::Instance(); - can_factory->RegisterCanClients(); - can_client_ = can_factory->CreateCANClient(canbus_conf->can_card_parameter()); - if (!can_client_) { - AERROR << "Failed to create can client."; - return false; - } - AINFO << "Can client is successfully created."; - - message_manager_ = this->CreateMessageManager(); - if (message_manager_ == nullptr) { - AERROR << "Failed to create message manager."; - return false; - } - AINFO << "Message manager is successfully created."; - - if (can_receiver_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_receiver_log()) != ErrorCode::OK) { - AERROR << "Failed to init can receiver."; - return false; - } - AINFO << "The can receiver is successfully initialized."; - - if (can_sender_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_sender_log()) != ErrorCode::OK) { - AERROR << "Failed to init can sender."; - return false; - } - AINFO << "The can sender is successfully initialized."; - - vehicle_controller_ = CreateVehicleController(); - if (vehicle_controller_ == nullptr) { - AERROR << "Failed to create vehicle controller."; - return false; - } - AINFO << "The vehicle controller is successfully created."; - - if (vehicle_controller_->Init(canbus_conf->vehicle_parameter(), &can_sender_, - message_manager_.get()) != ErrorCode::OK) { - AERROR << "Failed to init vehicle controller."; - return false; - } - - AINFO << "The vehicle controller is successfully" - << " initialized with canbus conf as : " - << canbus_conf->vehicle_parameter().ShortDebugString(); - - node_ = ::apollo::cyber::CreateNode("chassis_detail"); - - chassis_detail_writer_ = node_->CreateWriter<::apollo::canbus::Neolix_edu>( - FLAGS_chassis_detail_topic); - - return true; -} - -bool Neolix_eduVehicleFactory::Start() { - // 1. init and start the can card hardware - if (can_client_->Start() != ErrorCode::OK) { - AERROR << "Failed to start can client"; - return false; - } - AINFO << "Can client is started."; - - // 2. start receive first then send - if (can_receiver_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can receiver."; - return false; - } - AINFO << "Can receiver is started."; - - // 3. start send - if (can_sender_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can sender."; - return false; - } - - // 4. start controller - if (!vehicle_controller_->Start()) { - AERROR << "Failed to start vehicle controller."; - return false; - } - - return true; -} - -void Neolix_eduVehicleFactory::Stop() { - can_sender_.Stop(); - can_receiver_.Stop(); - can_client_->Stop(); - vehicle_controller_->Stop(); - AINFO << "Cleanup cansender, canreceiver, canclient, vehicle controller."; -} - -void Neolix_eduVehicleFactory::UpdateCommand( - const apollo::control::ControlCommand *control_command) { - if (vehicle_controller_->Update(*control_command) != ErrorCode::OK) { - AERROR << "Failed to process callback function OnControlCommand because " - "vehicle_controller_->Update error."; - return; - } - can_sender_.Update(); -} - -Chassis Neolix_eduVehicleFactory::publish_chassis() { - Chassis chassis = vehicle_controller_->chassis(); - ADEBUG << chassis.ShortDebugString(); - return chassis; -} - -void Neolix_eduVehicleFactory::PublishChassisDetail() { - Neolix_edu chassis_detail; - message_manager_->GetSensorData(&chassis_detail); - ADEBUG << chassis_detail.ShortDebugString(); - chassis_detail_writer_->Write(chassis_detail); -} - -std::unique_ptr> -Neolix_eduVehicleFactory::CreateVehicleController() { - return std::unique_ptr>( - new neolix_edu::Neolix_eduController()); -} - -std::unique_ptr> -Neolix_eduVehicleFactory::CreateMessageManager() { - return std::unique_ptr>( - new neolix_edu::Neolix_eduMessageManager()); -} - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/neolix_edu/neolix_edu_vehicle_factory.h b/modules/canbus_vehicle/neolix_edu/neolix_edu_vehicle_factory.h deleted file mode 100644 index 26cac9a872e..00000000000 --- a/modules/canbus_vehicle/neolix_edu/neolix_edu_vehicle_factory.h +++ /dev/null @@ -1,125 +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 neolix_edu_vehicle_factory.h - */ - -#pragma once - -#include - -#include "modules/canbus/proto/canbus_conf.pb.h" -#include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "modules/canbus_vehicle/neolix_edu/proto/neolix_edu.pb.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -#include "cyber/cyber.h" -#include "modules/canbus/vehicle/abstract_vehicle_factory.h" -#include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/common/status/status.h" -#include "modules/drivers/canbus/can_client/can_client.h" -#include "modules/drivers/canbus/can_comm/can_receiver.h" -#include "modules/drivers/canbus/can_comm/can_sender.h" -#include "modules/drivers/canbus/can_comm/message_manager.h" - -/** - * @namespace apollo::canbus - * @brief apollo::canbus - */ -namespace apollo { -namespace canbus { - -/** - * @class Neolix_eduVehicleFactory - * - * @brief this class is inherited from AbstractVehicleFactory. It can be used to - * create controller and message manager for neolix_edu vehicle. - */ -class Neolix_eduVehicleFactory : public AbstractVehicleFactory { - public: - /** - * @brief destructor - */ - virtual ~Neolix_eduVehicleFactory() = default; - - /** - * @brief init vehicle factory - * @returns true if successfully initialized - */ - bool Init(const CanbusConf *canbus_conf) override; - - /** - * @brief start canclient, cansender, canreceiver, vehicle controller - * @returns true if successfully started - */ - bool Start() override; - - /** - * @brief create ch vehicle controller - * @returns a unique_ptr that points to the created controller - */ - void Stop() override; - - /** - * @brief update control command - */ - void UpdateCommand( - const apollo::control::ControlCommand *control_command) override; - - /** - * @brief publish chassis messages - */ - Chassis publish_chassis() override; - - /** - * @brief publish chassis for vehicle messages - */ - void PublishChassisDetail() override; - - private: - /** - * @brief create Neolix_edu vehicle controller - * @returns a unique_ptr that points to the created controller - */ - std::unique_ptr> - CreateVehicleController(); - - /** - * @brief create Neolix_edu message manager - * @returns a unique_ptr that points to the created message manager - */ - std::unique_ptr> - CreateMessageManager(); - - std::unique_ptr<::apollo::cyber::Node> node_ = nullptr; - std::unique_ptr can_client_; - CanSender<::apollo::canbus::Neolix_edu> can_sender_; - apollo::drivers::canbus::CanReceiver<::apollo::canbus::Neolix_edu> - can_receiver_; - std::unique_ptr> - message_manager_; - std::unique_ptr> - vehicle_controller_; - - std::shared_ptr<::apollo::cyber::Writer<::apollo::canbus::Neolix_edu>> - chassis_detail_writer_; -}; - -CYBER_REGISTER_VEHICLEFACTORY(Neolix_eduVehicleFactory) - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/neolix_edu/proto/BUILD b/modules/canbus_vehicle/neolix_edu/proto/BUILD deleted file mode 100644 index bb1490856f5..00000000000 --- a/modules/canbus_vehicle/neolix_edu/proto/BUILD +++ /dev/null @@ -1,28 +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") - -package(default_visibility = ["//visibility:public"]) - -cc_proto_library( - name = "neolix_edu_cc_proto", - deps = [ - ":neolix_edu_proto", - ], -) - -proto_library( - name = "neolix_edu_proto", - srcs = ["neolix_edu.proto"], - deps = [ - "//modules/common_msgs/chassis_msgs:chassis_proto", - ], -) - -py_proto_library( - name = "neolix_edu_py_pb2", - deps = [ - ":neolix_edu_proto", - ], -) \ No newline at end of file diff --git a/modules/canbus_vehicle/neolix_edu/testdata/neolix_edu_canbus_conf_test.pb.txt b/modules/canbus_vehicle/neolix_edu/testdata/neolix_edu_canbus_conf_test.pb.txt deleted file mode 100644 index 860ca0884a1..00000000000 --- a/modules/canbus_vehicle/neolix_edu/testdata/neolix_edu_canbus_conf_test.pb.txt +++ /dev/null @@ -1,16 +0,0 @@ -vehicle_parameter { - brand: NEOLIX - max_enable_fail_attempt: 5 - driving_mode: COMPLETE_AUTO_DRIVE -} - -can_card_parameter { - brand: SOCKET_CAN_RAW - type: PCI_CARD - channel_id: CHANNEL_ID_ZERO - interface: NATIVE -} - -enable_debug_mode: true -enable_receiver_log: true -enable_sender_log: true diff --git a/modules/canbus_vehicle/transit/BUILD b/modules/canbus_vehicle/transit/BUILD deleted file mode 100644 index 777f2887d14..00000000000 --- a/modules/canbus_vehicle/transit/BUILD +++ /dev/null @@ -1,149 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "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"]) - -CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] - -cc_library( - name = "transit_vehicle_factory", - srcs = ["transit_vehicle_factory.cc"], - hdrs = ["transit_vehicle_factory.h"], - copts = CANBUS_COPTS, - alwayslink = True, - deps = [ - ":transit_controller", - ":transit_message_manager", - "//modules/canbus/common:canbus_gflags", - "//modules/common/adapters:adapter_gflags", - "//modules/common/status", - "//modules/canbus/vehicle:abstract_vehicle_factory", - "//modules/drivers/canbus:sensor_canbus_lib", - ], -) - -cc_binary( - name = "libtransit_vehicle_factory_lib.so", - linkshared = True, - linkstatic = True, - deps = [":transit_vehicle_factory"], -) - -cc_library( - name = "transit_message_manager", - srcs = ["transit_message_manager.cc"], - hdrs = ["transit_message_manager.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/transit/proto:transit_cc_proto", - "//modules/canbus_vehicle/transit/protocol:canbus_transit_protocol", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_library( - name = "transit_controller", - srcs = ["transit_controller.cc"], - hdrs = ["transit_controller.h"], - copts = CANBUS_COPTS, - deps = [ - ":transit_message_manager", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/canbus/vehicle:vehicle_controller_base", - "//modules/common/kv_db", - "//modules/common_msgs/basic_msgs:vehicle_signal_cc_proto", - "//modules/drivers/canbus/can_comm:can_sender", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_test( - name = "transit_vehicle_factory_test", - size = "small", - srcs = ["transit_vehicle_factory_test.cc"], - data = ["//modules/canbus:test_data"], - linkstatic = True, - deps = [ - ":transit_vehicle_factory", - "@com_google_googletest//:gtest_main", - ], -) - -cc_test( - name = "transit_controller_test", - size = "small", - srcs = ["transit_controller_test.cc"], - data = ["//modules/canbus:test_data"], - deps = [ - ":transit_controller", - "//modules/common/util", - "@com_google_googletest//:gtest_main", - ], -) - -install( - name = "install", - library_dest = "canbus-vehicle-transit/lib", - data_dest = "canbus-vehicle-transit", - data = [ - ":runtime_data", - ":cyberfile.xml", - ":canbus-vehicle-transit.BUILD", - ], - targets = [ - ":libtransit_vehicle_factory_lib.so", - ], - deps = [ - ":pb_transit", - ":pb_hdrs", - ], -) - -install( - name = "pb_hdrs", - data_dest = "canbus-vehicle-transit/include", - data = [ - "//modules/canbus_vehicle/transit/proto:transit_cc_proto", - ], -) - -install_files( - name = "pb_transit", - dest = "canbus-vehicle-transit", - files = [ - "//modules/canbus_vehicle/transit/proto:transit_py_pb2", - ], -) - -filegroup( - name = "runtime_data", - srcs = glob([ - "testdata/**", - ]), -) - -install_src_files( - name = "install_src", - deps = [ - ":install_transit_src", - ":install_transit_hdrs" - ], -) - -install_src_files( - name = "install_transit_src", - src_dir = ["."], - dest = "canbus-vehicle-transit/src", - filter = "*", -) - -install_src_files( - name = "install_transit_hdrs", - src_dir = ["."], - dest = "canbus-vehicle-transit/include", - filter = "*.h", -) - -cpplint() diff --git a/modules/canbus_vehicle/transit/canbus-vehicle-transit.BUILD b/modules/canbus_vehicle/transit/canbus-vehicle-transit.BUILD deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/modules/canbus_vehicle/transit/cyberfile.xml b/modules/canbus_vehicle/transit/cyberfile.xml deleted file mode 100644 index 1c2061a9d87..00000000000 --- a/modules/canbus_vehicle/transit/cyberfile.xml +++ /dev/null @@ -1,24 +0,0 @@ - - canbus-vehicle-transit - local - - Dynamic loading for canbus module - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/canbus_vehicle/transit - - cyber-dev - common-dev - canbus-dev - common-msgs-dev - drivers-dev - 3rd-gtest-dev - - \ No newline at end of file diff --git a/modules/canbus_vehicle/transit/proto/BUILD b/modules/canbus_vehicle/transit/proto/BUILD deleted file mode 100644 index bfcc2d3e2e9..00000000000 --- a/modules/canbus_vehicle/transit/proto/BUILD +++ /dev/null @@ -1,25 +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") - -package(default_visibility = ["//visibility:public"]) - -cc_proto_library( - name = "transit_cc_proto", - deps = [ - ":transit_proto", - ], -) - -proto_library( - name = "transit_proto", - srcs = ["transit.proto"], -) - -py_proto_library( - name = "transit_py_pb2", - deps = [ - ":transit_proto", - ], -) \ No newline at end of file diff --git a/modules/canbus_vehicle/transit/testdata/transit_canbus_conf_test.pb.txt b/modules/canbus_vehicle/transit/testdata/transit_canbus_conf_test.pb.txt deleted file mode 100644 index e4e92780fac..00000000000 --- a/modules/canbus_vehicle/transit/testdata/transit_canbus_conf_test.pb.txt +++ /dev/null @@ -1,13 +0,0 @@ -vehicle_parameter { - brand: TRANSIT - max_enable_fail_attempt: 5 - driving_mode: COMPLETE_AUTO_DRIVE -} - -can_card_parameter { - brand:SOCKET_CAN_RAW - type: PCI_CARD - channel_id: CHANNEL_ID_ZERO -} - -enable_debug_mode: false diff --git a/modules/canbus_vehicle/transit/transit_vehicle_factory.cc b/modules/canbus_vehicle/transit/transit_vehicle_factory.cc deleted file mode 100644 index 39e0472be59..00000000000 --- a/modules/canbus_vehicle/transit/transit_vehicle_factory.cc +++ /dev/null @@ -1,165 +0,0 @@ -/****************************************************************************** - * Copyright 2017 The Apollo Authors. All Rights Reserved. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - *****************************************************************************/ - -#include "modules/canbus_vehicle/transit/transit_vehicle_factory.h" - -#include "cyber/common/log.h" -#include "modules/canbus/common/canbus_gflags.h" -#include "modules/canbus_vehicle/transit/transit_controller.h" -#include "modules/canbus_vehicle/transit/transit_message_manager.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common/util/util.h" -#include "modules/drivers/canbus/can_client/can_client_factory.h" - -using apollo::common::ErrorCode; -using apollo::control::ControlCommand; -using apollo::drivers::canbus::CanClientFactory; - -namespace apollo { -namespace canbus { - -bool TransitVehicleFactory::Init(const CanbusConf *canbus_conf) { - // Init can client - auto can_factory = CanClientFactory::Instance(); - can_factory->RegisterCanClients(); - can_client_ = can_factory->CreateCANClient(canbus_conf->can_card_parameter()); - if (!can_client_) { - AERROR << "Failed to create can client."; - return false; - } - AINFO << "Can client is successfully created."; - - message_manager_ = this->CreateMessageManager(); - if (message_manager_ == nullptr) { - AERROR << "Failed to create message manager."; - return false; - } - AINFO << "Message manager is successfully created."; - - if (can_receiver_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_receiver_log()) != ErrorCode::OK) { - AERROR << "Failed to init can receiver."; - return false; - } - AINFO << "The can receiver is successfully initialized."; - - if (can_sender_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_sender_log()) != ErrorCode::OK) { - AERROR << "Failed to init can sender."; - return false; - } - AINFO << "The can sender is successfully initialized."; - - vehicle_controller_ = CreateVehicleController(); - if (vehicle_controller_ == nullptr) { - AERROR << "Failed to create vehicle controller."; - return false; - } - AINFO << "The vehicle controller is successfully created."; - - if (vehicle_controller_->Init(canbus_conf->vehicle_parameter(), &can_sender_, - message_manager_.get()) != ErrorCode::OK) { - AERROR << "Failed to init vehicle controller."; - return false; - } - - AINFO << "The vehicle controller is successfully" - << " initialized with canbus conf as : " - << canbus_conf->vehicle_parameter().ShortDebugString(); - - node_ = ::apollo::cyber::CreateNode("chassis_detail"); - - chassis_detail_writer_ = node_->CreateWriter<::apollo::canbus::Transit>( - FLAGS_chassis_detail_topic); - - return true; -} - -bool TransitVehicleFactory::Start() { - // 1. init and start the can card hardware - if (can_client_->Start() != ErrorCode::OK) { - AERROR << "Failed to start can client"; - return false; - } - AINFO << "Can client is started."; - - // 2. start receive first then send - if (can_receiver_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can receiver."; - return false; - } - AINFO << "Can receiver is started."; - - // 3. start send - if (can_sender_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can sender."; - return false; - } - - // 4. start controller - if (!vehicle_controller_->Start()) { - AERROR << "Failed to start vehicle controller."; - return false; - } - - return true; -} - -void TransitVehicleFactory::Stop() { - can_sender_.Stop(); - can_receiver_.Stop(); - can_client_->Stop(); - vehicle_controller_->Stop(); - AINFO << "Cleanup cansender, canreceiver, canclient, vehicle controller."; -} - -void TransitVehicleFactory::UpdateCommand( - const apollo::control::ControlCommand *control_command) { - if (vehicle_controller_->Update(*control_command) != ErrorCode::OK) { - AERROR << "Failed to process callback function OnControlCommand because " - "vehicle_controller_->Update error."; - return; - } - can_sender_.Update(); -} - -Chassis TransitVehicleFactory::publish_chassis() { - Chassis chassis = vehicle_controller_->chassis(); - ADEBUG << chassis.ShortDebugString(); - return chassis; -} - -void TransitVehicleFactory::PublishChassisDetail() { - Transit chassis_detail; - message_manager_->GetSensorData(&chassis_detail); - ADEBUG << chassis_detail.ShortDebugString(); - chassis_detail_writer_->Write(chassis_detail); -} - -std::unique_ptr> -TransitVehicleFactory::CreateVehicleController() { - return std::unique_ptr>( - new transit::TransitController()); -} - -std::unique_ptr> -TransitVehicleFactory::CreateMessageManager() { - return std::unique_ptr>( - new transit::TransitMessageManager()); -} - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/transit/transit_vehicle_factory.h b/modules/canbus_vehicle/transit/transit_vehicle_factory.h deleted file mode 100644 index f10cc28809b..00000000000 --- a/modules/canbus_vehicle/transit/transit_vehicle_factory.h +++ /dev/null @@ -1,123 +0,0 @@ -/****************************************************************************** - * Copyright 2017 The Apollo Authors. All Rights Reserved. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - *****************************************************************************/ - -/** - * @file transit_vehicle_factory.h - */ - -#pragma once - -#include - -#include "modules/canbus/proto/canbus_conf.pb.h" -#include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "modules/canbus_vehicle/transit/proto/transit.pb.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -#include "cyber/cyber.h" -#include "modules/canbus/vehicle/abstract_vehicle_factory.h" -#include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/common/status/status.h" -#include "modules/drivers/canbus/can_client/can_client.h" -#include "modules/drivers/canbus/can_comm/can_receiver.h" -#include "modules/drivers/canbus/can_comm/can_sender.h" -#include "modules/drivers/canbus/can_comm/message_manager.h" - -/** - * @namespace apollo::canbus - * @brief apollo::canbus - */ -namespace apollo { -namespace canbus { - -/** - * @class TransitVehicleFactory - * - * @brief this class is inherited from AbstractVehicleFactory. It can be used to - * create controller and message manager for transit vehicle. - */ -class TransitVehicleFactory : public AbstractVehicleFactory { - public: - /** - * @brief destructor - */ - virtual ~TransitVehicleFactory() = default; - - /** - * @brief init vehicle factory - * @returns true if successfully initialized - */ - bool Init(const CanbusConf *canbus_conf) override; - - /** - * @brief start canclient, cansender, canreceiver, vehicle controller - * @returns true if successfully started - */ - bool Start() override; - - /** - * @brief create ch vehicle controller - * @returns a unique_ptr that points to the created controller - */ - void Stop() override; - - /** - * @brief update control command - */ - void UpdateCommand( - const apollo::control::ControlCommand *control_command) override; - - /** - * @brief publish chassis messages - */ - Chassis publish_chassis() override; - - /** - * @brief publish chassis for vehicle messages - */ - void PublishChassisDetail() override; - - private: - /** - * @brief create transit vehicle controller - * @returns a unique_ptr that points to the created controller - */ - std::unique_ptr> - CreateVehicleController(); - - /** - * @brief create transit message manager - * @returns a unique_ptr that points to the created message manager - */ - std::unique_ptr> - CreateMessageManager(); - - std::unique_ptr<::apollo::cyber::Node> node_ = nullptr; - std::unique_ptr can_client_; - CanSender<::apollo::canbus::Transit> can_sender_; - apollo::drivers::canbus::CanReceiver<::apollo::canbus::Transit> can_receiver_; - std::unique_ptr> message_manager_; - std::unique_ptr> - vehicle_controller_; - - std::shared_ptr<::apollo::cyber::Writer<::apollo::canbus::Transit>> - chassis_detail_writer_; -}; - -CYBER_REGISTER_VEHICLEFACTORY(TransitVehicleFactory) - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/wey/BUILD b/modules/canbus_vehicle/wey/BUILD deleted file mode 100644 index 8ce0b1ef837..00000000000 --- a/modules/canbus_vehicle/wey/BUILD +++ /dev/null @@ -1,160 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "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"]) - -CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] - -cc_library( - name = "wey_vehicle_factory", - srcs = ["wey_vehicle_factory.cc"], - hdrs = ["wey_vehicle_factory.h"], - copts = CANBUS_COPTS, - alwayslink = True, - deps = [ - ":wey_controller", - ":wey_message_manager", - "//modules/canbus/common:canbus_gflags", - "//modules/common/adapters:adapter_gflags", - "//modules/common/status", - "//modules/canbus/vehicle:abstract_vehicle_factory", - "//modules/drivers/canbus:sensor_canbus_lib", - ], -) - -cc_binary( - name = "libwey_vehicle_factory_lib.so", - linkshared = True, - linkstatic = True, - deps = [":wey_vehicle_factory"], -) - -cc_test( - name = "wey_vehicle_factory_test", - size = "small", - srcs = ["wey_vehicle_factory_test.cc"], - data = ["//modules/canbus:test_data"], - linkstatic = True, - deps = [ - ":wey_vehicle_factory", - "@com_google_googletest//:gtest_main", - ], -) - -cc_library( - name = "wey_message_manager", - srcs = ["wey_message_manager.cc"], - hdrs = ["wey_message_manager.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/wey/proto:wey_cc_proto", - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_test( - name = "wey_message_manager_test", - size = "small", - srcs = ["wey_message_manager_test.cc"], - deps = [ - ":wey_message_manager", - "@com_google_googletest//:gtest_main", - ], -) - -cc_library( - name = "wey_controller", - srcs = ["wey_controller.cc"], - hdrs = ["wey_controller.h"], - copts = CANBUS_COPTS, - deps = [ - ":wey_message_manager", - "//modules/canbus/proto:canbus_conf_cc_proto", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/canbus/proto:vehicle_parameter_cc_proto", - "//modules/canbus/vehicle:vehicle_controller_base", - "//modules/canbus_vehicle/wey/protocol:canbus_wey_protocol", - "//modules/common_msgs/basic_msgs:error_code_cc_proto", - "//modules/common_msgs/control_msgs:control_cmd_cc_proto", - ], -) - -cc_test( - name = "wey_controller_test", - size = "small", - srcs = ["wey_controller_test.cc"], - data = ["//modules/canbus:test_data"], - deps = [ - ":wey_controller", - "//modules/common/util", - "@com_google_googletest//:gtest_main", - ], -) - -install( - name = "install", - library_dest = "canbus-vehicle-wey/lib", - data_dest = "canbus-vehicle-wey", - data = [ - ":runtime_data", - ":cyberfile.xml", - ":canbus-vehicle-wey.BUILD", - ], - targets = [ - ":libwey_vehicle_factory_lib.so", - ], - deps = [ - ":pb_wey", - ":pb_hdrs", - ], -) - -install( - name = "pb_hdrs", - data_dest = "canbus-vehicle-wey/include", - data = [ - "//modules/canbus_vehicle/wey/proto:wey_cc_proto", - ], -) - -install_files( - name = "pb_wey", - dest = "canbus-vehicle-wey", - files = [ - "//modules/canbus_vehicle/wey/proto:wey_py_pb2", - ], -) - -filegroup( - name = "runtime_data", - srcs = glob([ - "testdata/**", - ]), -) - -install_src_files( - name = "install_src", - deps = [ - ":install_wey_src", - ":install_wey_hdrs" - ], -) - -install_src_files( - name = "install_wey_src", - src_dir = ["."], - dest = "canbus-vehicle-wey/src", - filter = "*", -) - -install_src_files( - name = "install_wey_hdrs", - src_dir = ["."], - dest = "canbus-vehicle-wey/include", - filter = "*.h", -) - -cpplint() diff --git a/modules/canbus_vehicle/wey/canbus-vehicle-wey.BUILD b/modules/canbus_vehicle/wey/canbus-vehicle-wey.BUILD deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/modules/canbus_vehicle/wey/cyberfile.xml b/modules/canbus_vehicle/wey/cyberfile.xml deleted file mode 100644 index 3bba7b22128..00000000000 --- a/modules/canbus_vehicle/wey/cyberfile.xml +++ /dev/null @@ -1,24 +0,0 @@ - - canbus-vehicle-wey - local - - Dynamic loading for canbus module - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/canbus_vehicle/wey - - cyber-dev - common-dev - canbus-dev - common-msgs-dev - drivers-dev - 3rd-gtest-dev - - \ No newline at end of file diff --git a/modules/canbus_vehicle/wey/proto/BUILD b/modules/canbus_vehicle/wey/proto/BUILD deleted file mode 100644 index 24235b50b8c..00000000000 --- a/modules/canbus_vehicle/wey/proto/BUILD +++ /dev/null @@ -1,25 +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") - -package(default_visibility = ["//visibility:public"]) - -cc_proto_library( - name = "wey_cc_proto", - deps = [ - ":wey_proto", - ], -) - -proto_library( - name = "wey_proto", - srcs = ["wey.proto"], -) - -py_proto_library( - name = "wey_py_pb2", - deps = [ - ":wey_proto", - ], -) \ No newline at end of file diff --git a/modules/canbus_vehicle/wey/protocol/status_310_test.cc b/modules/canbus_vehicle/wey/protocol/status_310_test.cc deleted file mode 100644 index 32b53e410e2..00000000000 --- a/modules/canbus_vehicle/wey/protocol/status_310_test.cc +++ /dev/null @@ -1,75 +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/canbus_vehicle/wey/protocol/status_310.h" -#include "gtest/gtest.h" - -namespace apollo { -namespace canbus { -namespace wey { - -class Status310Test : public ::testing::Test { - public: - virtual void SetUp() {} -}; - -TEST_F(Status310Test, reset) { - Status310 status; - int32_t length = 8; - Wey chassis_detail; - uint8_t bytes[8] = {0x88, 0x44, 0x22, 0x11, 0x11, 0x12, 0x13, 0x14}; - - status.Parse(bytes, length, &chassis_detail); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().longitudeaccvalid(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().lateralaccevalid(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().vehdynyawratevalid(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().flwheelspdvalid(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().frwheelspdvalid(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().rlwheelspdvalid(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().rrwheelspdvalid(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().vehiclespdvalid(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().longitudedrivingmode(), 2); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().engspdvalid(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().accepedaloverride(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().brakepedalstatus(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().espbrakelightsts(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().epbswtpositionvalid(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().epbsts(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().currentgearvalid(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().epstrqsnsrsts(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().eps_interferdetdvalid(), - 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().epshandsdetnsts(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().eps_handsdetnstsvalid(), - 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().steerwheelanglesign(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().steerwheelspdsign(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().driverdoorsts(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().rldoorsts(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().rrdoorsts(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().frontfoglmpsts(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().rearfoglmpsts(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().lowbeamsts(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().highbeamsts(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().leftturnlampsts(), 0); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().rightturnlampsts(), 1); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().bcm_availsts(), 2); - EXPECT_DOUBLE_EQ(chassis_detail.status_310().brakelmpsts(), 0); -} - -} // namespace wey -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/wey/testdata/wey_canbus_conf_test.pb.txt b/modules/canbus_vehicle/wey/testdata/wey_canbus_conf_test.pb.txt deleted file mode 100644 index 48f655360ae..00000000000 --- a/modules/canbus_vehicle/wey/testdata/wey_canbus_conf_test.pb.txt +++ /dev/null @@ -1,13 +0,0 @@ -vehicle_parameter { - brand: WEY - max_enable_fail_attempt: 5 - driving_mode: COMPLETE_AUTO_DRIVE -} - -can_card_parameter { - brand:SOCKET_CAN_RAW - type: PCI_CARD - channel_id: CHANNEL_ID_ZERO -} - -enable_debug_mode: false diff --git a/modules/canbus_vehicle/wey/wey_vehicle_factory.cc b/modules/canbus_vehicle/wey/wey_vehicle_factory.cc deleted file mode 100644 index fc987e12cdf..00000000000 --- a/modules/canbus_vehicle/wey/wey_vehicle_factory.cc +++ /dev/null @@ -1,165 +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/canbus_vehicle/wey/wey_vehicle_factory.h" - -#include "cyber/common/log.h" -#include "modules/canbus/common/canbus_gflags.h" -#include "modules/canbus_vehicle/wey/wey_controller.h" -#include "modules/canbus_vehicle/wey/wey_message_manager.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common/util/util.h" -#include "modules/drivers/canbus/can_client/can_client_factory.h" - -using apollo::common::ErrorCode; -using apollo::control::ControlCommand; -using apollo::drivers::canbus::CanClientFactory; - -namespace apollo { -namespace canbus { - -bool WeyVehicleFactory::Init(const CanbusConf *canbus_conf) { - // Init can client - auto can_factory = CanClientFactory::Instance(); - can_factory->RegisterCanClients(); - can_client_ = can_factory->CreateCANClient(canbus_conf->can_card_parameter()); - if (!can_client_) { - AERROR << "Failed to create can client."; - return false; - } - AINFO << "Can client is successfully created."; - - message_manager_ = this->CreateMessageManager(); - if (message_manager_ == nullptr) { - AERROR << "Failed to create message manager."; - return false; - } - AINFO << "Message manager is successfully created."; - - if (can_receiver_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_receiver_log()) != ErrorCode::OK) { - AERROR << "Failed to init can receiver."; - return false; - } - AINFO << "The can receiver is successfully initialized."; - - if (can_sender_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_sender_log()) != ErrorCode::OK) { - AERROR << "Failed to init can sender."; - return false; - } - AINFO << "The can sender is successfully initialized."; - - vehicle_controller_ = CreateVehicleController(); - if (vehicle_controller_ == nullptr) { - AERROR << "Failed to create vehicle controller."; - return false; - } - AINFO << "The vehicle controller is successfully created."; - - if (vehicle_controller_->Init(canbus_conf->vehicle_parameter(), &can_sender_, - message_manager_.get()) != ErrorCode::OK) { - AERROR << "Failed to init vehicle controller."; - return false; - } - - AINFO << "The vehicle controller is successfully" - << " initialized with canbus conf as : " - << canbus_conf->vehicle_parameter().ShortDebugString(); - - node_ = ::apollo::cyber::CreateNode("chassis_detail"); - - chassis_detail_writer_ = - node_->CreateWriter<::apollo::canbus::Wey>(FLAGS_chassis_detail_topic); - - return true; -} - -bool WeyVehicleFactory::Start() { - // 1. init and start the can card hardware - if (can_client_->Start() != ErrorCode::OK) { - AERROR << "Failed to start can client"; - return false; - } - AINFO << "Can client is started."; - - // 2. start receive first then send - if (can_receiver_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can receiver."; - return false; - } - AINFO << "Can receiver is started."; - - // 3. start send - if (can_sender_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can sender."; - return false; - } - - // 4. start controller - if (!vehicle_controller_->Start()) { - AERROR << "Failed to start vehicle controller."; - return false; - } - - return true; -} - -void WeyVehicleFactory::Stop() { - can_sender_.Stop(); - can_receiver_.Stop(); - can_client_->Stop(); - vehicle_controller_->Stop(); - AINFO << "Cleanup cansender, canreceiver, canclient, vehicle controller."; -} - -void WeyVehicleFactory::UpdateCommand( - const apollo::control::ControlCommand *control_command) { - if (vehicle_controller_->Update(*control_command) != ErrorCode::OK) { - AERROR << "Failed to process callback function OnControlCommand because " - "vehicle_controller_->Update error."; - return; - } - can_sender_.Update(); -} - -Chassis WeyVehicleFactory::publish_chassis() { - Chassis chassis = vehicle_controller_->chassis(); - ADEBUG << chassis.ShortDebugString(); - return chassis; -} - -void WeyVehicleFactory::PublishChassisDetail() { - Wey chassis_detail; - message_manager_->GetSensorData(&chassis_detail); - ADEBUG << chassis_detail.ShortDebugString(); - chassis_detail_writer_->Write(chassis_detail); -} - -std::unique_ptr> -WeyVehicleFactory::CreateVehicleController() { - return std::unique_ptr>( - new wey::WeyController()); -} - -std::unique_ptr> -WeyVehicleFactory::CreateMessageManager() { - return std::unique_ptr>( - new wey::WeyMessageManager()); -} - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/wey/wey_vehicle_factory.h b/modules/canbus_vehicle/wey/wey_vehicle_factory.h deleted file mode 100644 index 4532150f317..00000000000 --- a/modules/canbus_vehicle/wey/wey_vehicle_factory.h +++ /dev/null @@ -1,121 +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. - *****************************************************************************/ - -/** - * @file wey_vehicle_factory.h - */ - -#pragma once - -#include - -#include "modules/canbus/proto/canbus_conf.pb.h" -#include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "modules/canbus_vehicle/wey/proto/wey.pb.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -#include "cyber/cyber.h" -#include "modules/canbus/vehicle/abstract_vehicle_factory.h" -#include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/common/status/status.h" -#include "modules/drivers/canbus/can_client/can_client.h" -#include "modules/drivers/canbus/can_comm/can_receiver.h" -#include "modules/drivers/canbus/can_comm/can_sender.h" -#include "modules/drivers/canbus/can_comm/message_manager.h" - -/** - * @namespace apollo::canbus - * @brief apollo::canbus - */ -namespace apollo { -namespace canbus { - -/** - * @class WeyVehicleFactory - * - * @brief this class is inherited from AbstractVehicleFactory. It can be used - * to create controller and message manager for wey vehicle. - */ -class WeyVehicleFactory : public AbstractVehicleFactory { - public: - /** - * @brief destructor - */ - virtual ~WeyVehicleFactory() = default; - - /** - * @brief init vehicle factory - * @returns true if successfully initialized - */ - bool Init(const CanbusConf *canbus_conf) override; - - /** - * @brief start canclient, cansender, canreceiver, vehicle controller - * @returns true if successfully started - */ - bool Start() override; - - /** - * @brief create ch vehicle controller - * @returns a unique_ptr that points to the created controller - */ - void Stop() override; - - /** - * @brief update control command - */ - void UpdateCommand( - const apollo::control::ControlCommand *control_command) override; - - /** - * @brief publish chassis messages - */ - Chassis publish_chassis() override; - - /** - * @brief publish chassis for vehicle messages - */ - void PublishChassisDetail() override; - - private: - /** - * @brief create wey vehicle controller - * @returns a unique_ptr that points to the created controller - */ - std::unique_ptr> - CreateVehicleController(); - - /** - * @brief create wey message manager - * @returns a unique_ptr that points to the created message manager - */ - std::unique_ptr> CreateMessageManager(); - - std::unique_ptr<::apollo::cyber::Node> node_ = nullptr; - std::unique_ptr can_client_; - CanSender<::apollo::canbus::Wey> can_sender_; - apollo::drivers::canbus::CanReceiver<::apollo::canbus::Wey> can_receiver_; - std::unique_ptr> message_manager_; - std::unique_ptr> vehicle_controller_; - - std::shared_ptr<::apollo::cyber::Writer<::apollo::canbus::Wey>> - chassis_detail_writer_; -}; - -CYBER_REGISTER_VEHICLEFACTORY(WeyVehicleFactory) - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/zhongyun/BUILD b/modules/canbus_vehicle/zhongyun/BUILD deleted file mode 100644 index 0973ac8f823..00000000000 --- a/modules/canbus_vehicle/zhongyun/BUILD +++ /dev/null @@ -1,160 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "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"]) - -CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""] - -cc_library( - name = "zhongyun_vehicle_factory", - srcs = ["zhongyun_vehicle_factory.cc"], - hdrs = ["zhongyun_vehicle_factory.h"], - copts = CANBUS_COPTS, - alwayslink = True, - deps = [ - ":zhongyun_controller", - ":zhongyun_message_manager", - "//modules/canbus/common:canbus_gflags", - "//modules/common/adapters:adapter_gflags", - "//modules/common/status", - "//modules/canbus/vehicle:abstract_vehicle_factory", - "//modules/drivers/canbus:sensor_canbus_lib", - ], -) - -cc_binary( - name = "libzhongyun_vehicle_factory_lib.so", - linkshared = True, - linkstatic = True, - deps = [":zhongyun_vehicle_factory"], -) - -cc_library( - name = "zhongyun_message_manager", - srcs = ["zhongyun_message_manager.cc"], - hdrs = ["zhongyun_message_manager.h"], - copts = CANBUS_COPTS, - deps = [ - "//modules/canbus_vehicle/zhongyun/proto:zhongyun_cc_proto", - "//modules/canbus_vehicle/zhongyun/protocol:canbus_zhongyun_protocol", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_library( - name = "zhongyun_controller", - srcs = ["zhongyun_controller.cc"], - hdrs = ["zhongyun_controller.h"], - copts = CANBUS_COPTS, - deps = [ - ":zhongyun_message_manager", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/canbus/vehicle:vehicle_controller_base", - "//modules/canbus_vehicle/zhongyun/protocol:canbus_zhongyun_protocol", - "//modules/drivers/canbus/can_comm:can_sender", - "//modules/drivers/canbus/can_comm:message_manager_base", - "//modules/drivers/canbus/common:canbus_common", - ], -) - -cc_test( - name = "zhongyun_message_manager_test", - size = "small", - srcs = ["zhongyun_message_manager_test.cc"], - data = ["//modules/canbus:test_data"], - deps = [ - ":zhongyun_message_manager", - "@com_google_googletest//:gtest_main", - ], -) - -cc_test( - name = "zhongyun_vehicle_factory_test", - size = "small", - srcs = ["zhongyun_vehicle_factory_test.cc"], - data = ["//modules/canbus:test_data"], - linkstatic = True, - deps = [ - ":zhongyun_vehicle_factory", - "@com_google_googletest//:gtest_main", - ], -) - -cc_test( - name = "zhongyun_controller_test", - size = "small", - srcs = ["zhongyun_controller_test.cc"], - data = ["//modules/canbus:test_data"], - deps = [ - ":zhongyun_controller", - "//modules/common/util", - "@com_google_googletest//:gtest_main", - ], -) - -install( - name = "install", - library_dest = "canbus-vehicle-zhongyun/lib", - data_dest = "canbus-vehicle-zhongyun", - data = [ - ":runtime_data", - ":cyberfile.xml", - ":canbus-vehicle-zhongyun.BUILD", - ], - targets = [ - ":libzhongyun_vehicle_factory_lib.so", - ], - deps = [ - ":pb_zhongyun", - ":pb_hdrs", - ], -) - -install( - name = "pb_hdrs", - data_dest = "canbus-vehicle-zhongyun/include", - data = [ - "//modules/canbus_vehicle/zhongyun/proto:zhongyun_cc_proto", - ], -) - -install_files( - name = "pb_zhongyun", - dest = "canbus-vehicle-zhongyun", - files = [ - "//modules/canbus_vehicle/zhongyun/proto:zhongyun_py_pb2", - ], -) - -filegroup( - name = "runtime_data", - srcs = glob([ - "testdata/**", - ]), -) - -install_src_files( - name = "install_src", - deps = [ - ":install_zhongyun_src", - ":install_zhongyun_hdrs" - ], -) - -install_src_files( - name = "install_zhongyun_src", - src_dir = ["."], - dest = "canbus-vehicle-zhongyun/src", - filter = "*", -) - -install_src_files( - name = "install_zhongyun_hdrs", - src_dir = ["."], - dest = "canbus-vehicle-zhongyun/include", - filter = "*.h", -) - -cpplint() diff --git a/modules/canbus_vehicle/zhongyun/canbus-vehicle-zhongyun.BUILD b/modules/canbus_vehicle/zhongyun/canbus-vehicle-zhongyun.BUILD deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/modules/canbus_vehicle/zhongyun/cyberfile.xml b/modules/canbus_vehicle/zhongyun/cyberfile.xml deleted file mode 100644 index cb8e6907407..00000000000 --- a/modules/canbus_vehicle/zhongyun/cyberfile.xml +++ /dev/null @@ -1,24 +0,0 @@ - - canbus-vehicle-zhongyun - local - - Dynamic loading for canbus module - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/canbus_vehicle/zhongyun - - cyber-dev - common-dev - canbus-dev - common-msgs-dev - drivers-dev - 3rd-gtest-dev - - \ No newline at end of file diff --git a/modules/canbus_vehicle/zhongyun/proto/BUILD b/modules/canbus_vehicle/zhongyun/proto/BUILD deleted file mode 100644 index e051caf10cb..00000000000 --- a/modules/canbus_vehicle/zhongyun/proto/BUILD +++ /dev/null @@ -1,25 +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") - -package(default_visibility = ["//visibility:public"]) - -cc_proto_library( - name = "zhongyun_cc_proto", - deps = [ - ":zhongyun_proto", - ], -) - -proto_library( - name = "zhongyun_proto", - srcs = ["zhongyun.proto"], -) - -py_proto_library( - name = "zhongyun_py_pb2", - deps = [ - ":zhongyun_proto", - ], -) diff --git a/modules/canbus_vehicle/zhongyun/testdata/zhongyun_canbus_conf_test.pb.txt b/modules/canbus_vehicle/zhongyun/testdata/zhongyun_canbus_conf_test.pb.txt deleted file mode 100644 index 9f6ec582558..00000000000 --- a/modules/canbus_vehicle/zhongyun/testdata/zhongyun_canbus_conf_test.pb.txt +++ /dev/null @@ -1,13 +0,0 @@ -vehicle_parameter { - brand: ZHONGYUN - max_enable_fail_attempt: 5 - driving_mode: COMPLETE_AUTO_DRIVE -} - -can_card_parameter { - brand:SOCKET_CAN_RAW - type: PCI_CARD - channel_id: CHANNEL_ID_ZERO -} - -enable_debug_mode: false diff --git a/modules/canbus_vehicle/zhongyun/zhongyun_vehicle_factory.cc b/modules/canbus_vehicle/zhongyun/zhongyun_vehicle_factory.cc deleted file mode 100644 index 8697b07bd85..00000000000 --- a/modules/canbus_vehicle/zhongyun/zhongyun_vehicle_factory.cc +++ /dev/null @@ -1,165 +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/canbus_vehicle/zhongyun/zhongyun_vehicle_factory.h" - -#include "cyber/common/log.h" -#include "modules/canbus/common/canbus_gflags.h" -#include "modules/canbus_vehicle/zhongyun/zhongyun_controller.h" -#include "modules/canbus_vehicle/zhongyun/zhongyun_message_manager.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common/util/util.h" -#include "modules/drivers/canbus/can_client/can_client_factory.h" - -using apollo::common::ErrorCode; -using apollo::control::ControlCommand; -using apollo::drivers::canbus::CanClientFactory; - -namespace apollo { -namespace canbus { - -bool ZhongyunVehicleFactory::Init(const CanbusConf *canbus_conf) { - // Init can client - auto can_factory = CanClientFactory::Instance(); - can_factory->RegisterCanClients(); - can_client_ = can_factory->CreateCANClient(canbus_conf->can_card_parameter()); - if (!can_client_) { - AERROR << "Failed to create can client."; - return false; - } - AINFO << "Can client is successfully created."; - - message_manager_ = this->CreateMessageManager(); - if (message_manager_ == nullptr) { - AERROR << "Failed to create message manager."; - return false; - } - AINFO << "Message manager is successfully created."; - - if (can_receiver_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_receiver_log()) != ErrorCode::OK) { - AERROR << "Failed to init can receiver."; - return false; - } - AINFO << "The can receiver is successfully initialized."; - - if (can_sender_.Init(can_client_.get(), message_manager_.get(), - canbus_conf->enable_sender_log()) != ErrorCode::OK) { - AERROR << "Failed to init can sender."; - return false; - } - AINFO << "The can sender is successfully initialized."; - - vehicle_controller_ = CreateVehicleController(); - if (vehicle_controller_ == nullptr) { - AERROR << "Failed to create vehicle controller."; - return false; - } - AINFO << "The vehicle controller is successfully created."; - - if (vehicle_controller_->Init(canbus_conf->vehicle_parameter(), &can_sender_, - message_manager_.get()) != ErrorCode::OK) { - AERROR << "Failed to init vehicle controller."; - return false; - } - - AINFO << "The vehicle controller is successfully" - << " initialized with canbus conf as : " - << canbus_conf->vehicle_parameter().ShortDebugString(); - - node_ = ::apollo::cyber::CreateNode("chassis_detail"); - - chassis_detail_writer_ = node_->CreateWriter<::apollo::canbus::Zhongyun>( - FLAGS_chassis_detail_topic); - - return true; -} - -bool ZhongyunVehicleFactory::Start() { - // 1. init and start the can card hardware - if (can_client_->Start() != ErrorCode::OK) { - AERROR << "Failed to start can client"; - return false; - } - AINFO << "Can client is started."; - - // 2. start receive first then send - if (can_receiver_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can receiver."; - return false; - } - AINFO << "Can receiver is started."; - - // 3. start send - if (can_sender_.Start() != ErrorCode::OK) { - AERROR << "Failed to start can sender."; - return false; - } - - // 4. start controller - if (!vehicle_controller_->Start()) { - AERROR << "Failed to start vehicle controller."; - return false; - } - - return true; -} - -void ZhongyunVehicleFactory::Stop() { - can_sender_.Stop(); - can_receiver_.Stop(); - can_client_->Stop(); - vehicle_controller_->Stop(); - AINFO << "Cleanup cansender, canreceiver, canclient, vehicle controller."; -} - -void ZhongyunVehicleFactory::UpdateCommand( - const apollo::control::ControlCommand *control_command) { - if (vehicle_controller_->Update(*control_command) != ErrorCode::OK) { - AERROR << "Failed to process callback function OnControlCommand because " - "vehicle_controller_->Update error."; - return; - } - can_sender_.Update(); -} - -Chassis ZhongyunVehicleFactory::publish_chassis() { - Chassis chassis = vehicle_controller_->chassis(); - ADEBUG << chassis.ShortDebugString(); - return chassis; -} - -void ZhongyunVehicleFactory::PublishChassisDetail() { - Zhongyun chassis_detail; - message_manager_->GetSensorData(&chassis_detail); - ADEBUG << chassis_detail.ShortDebugString(); - chassis_detail_writer_->Write(chassis_detail); -} - -std::unique_ptr> -ZhongyunVehicleFactory::CreateVehicleController() { - return std::unique_ptr>( - new zhongyun::ZhongyunController()); -} - -std::unique_ptr> -ZhongyunVehicleFactory::CreateMessageManager() { - return std::unique_ptr>( - new zhongyun::ZhongyunMessageManager()); -} - -} // namespace canbus -} // namespace apollo diff --git a/modules/canbus_vehicle/zhongyun/zhongyun_vehicle_factory.h b/modules/canbus_vehicle/zhongyun/zhongyun_vehicle_factory.h deleted file mode 100644 index 14ea4333f07..00000000000 --- a/modules/canbus_vehicle/zhongyun/zhongyun_vehicle_factory.h +++ /dev/null @@ -1,124 +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. - *****************************************************************************/ - -/** - * @file zhongyun_vehicle_factory.h - */ - -#pragma once - -#include - -#include "modules/canbus/proto/canbus_conf.pb.h" -#include "modules/canbus/proto/vehicle_parameter.pb.h" -#include "modules/canbus_vehicle/zhongyun/proto/zhongyun.pb.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -#include "cyber/cyber.h" -#include "modules/canbus/vehicle/abstract_vehicle_factory.h" -#include "modules/canbus/vehicle/vehicle_controller.h" -#include "modules/common/status/status.h" -#include "modules/drivers/canbus/can_client/can_client.h" -#include "modules/drivers/canbus/can_comm/can_receiver.h" -#include "modules/drivers/canbus/can_comm/can_sender.h" -#include "modules/drivers/canbus/can_comm/message_manager.h" - -/** - * @namespace apollo::canbus - * @brief apollo::canbus - */ -namespace apollo { -namespace canbus { - -/** - * @class ZhongyunVehicleFactory - * - * @brief this class is inherited from AbstractVehicleFactory. It can be used to - * create controller and message manager for zhongyun vehicle. - */ -class ZhongyunVehicleFactory : public AbstractVehicleFactory { - public: - /** - * @brief destructor - */ - virtual ~ZhongyunVehicleFactory() = default; - - /** - * @brief init vehicle factory - * @returns true if successfully initialized - */ - bool Init(const CanbusConf *canbus_conf) override; - - /** - * @brief start canclient, cansender, canreceiver, vehicle controller - * @returns true if successfully started - */ - bool Start() override; - - /** - * @brief create ch vehicle controller - * @returns a unique_ptr that points to the created controller - */ - void Stop() override; - - /** - * @brief update control command - */ - void UpdateCommand( - const apollo::control::ControlCommand *control_command) override; - - /** - * @brief publish chassis messages - */ - Chassis publish_chassis() override; - - /** - * @brief publish chassis for vehicle messages - */ - void PublishChassisDetail() override; - - private: - /** - * @brief create zhongyun vehicle controller - * @returns a unique_ptr that points to the created controller - */ - std::unique_ptr> - CreateVehicleController(); - - /** - * @brief create zhongyun message manager - * @returns a unique_ptr that points to the created message manager - */ - std::unique_ptr> - CreateMessageManager(); - - std::unique_ptr<::apollo::cyber::Node> node_ = nullptr; - std::unique_ptr can_client_; - CanSender<::apollo::canbus::Zhongyun> can_sender_; - apollo::drivers::canbus::CanReceiver<::apollo::canbus::Zhongyun> - can_receiver_; - std::unique_ptr> message_manager_; - std::unique_ptr> - vehicle_controller_; - - std::shared_ptr<::apollo::cyber::Writer<::apollo::canbus::Zhongyun>> - chassis_detail_writer_; -}; - -CYBER_REGISTER_VEHICLEFACTORY(ZhongyunVehicleFactory) - -} // namespace canbus -} // namespace apollo diff --git a/modules/common/BUILD b/modules/common/BUILD index b761b16e1c3..d16a81694cd 100644 --- a/modules/common/BUILD +++ b/modules/common/BUILD @@ -9,7 +9,6 @@ install( library_dest = "common/lib", data_dest = "common", data = [ - ":cyberfile.xml", "common.BUILD" ], deps = [ diff --git a/modules/common/cyberfile.xml b/modules/common/cyberfile.xml deleted file mode 100644 index 8ffdc37b677..00000000000 --- a/modules/common/cyberfile.xml +++ /dev/null @@ -1,33 +0,0 @@ - - common - local - - This module contains code that is not specific to any module but is useful for the functioning of Apollo. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/common - - 3rd-rules-python-dev - 3rd-grpc-dev - 3rd-gflags-dev - 3rd-bazel-skylib-dev - 3rd-absl-dev - libsqlite3-dev - 3rd-rules-proto-dev - 3rd-eigen3-dev - 3rd-gpus-dev - 3rd-osqp-dev - 3rd-boost-dev - 3rd-gtest-dev - cyber-dev - 3rd-py-dev - 3rd-nlohmann-json-dev - common-msgs-dev - diff --git a/modules/common/vehicle_state/vehicle_state_provider.cc b/modules/common/vehicle_state/vehicle_state_provider.cc index d6df5ac3410..ab7b0ac8174 100644 --- a/modules/common/vehicle_state/vehicle_state_provider.cc +++ b/modules/common/vehicle_state/vehicle_state_provider.cc @@ -66,7 +66,7 @@ Status VehicleStateProvider::Update( vehicle_state_.set_steering_percentage(chassis.steering_percentage()); } - static constexpr double kEpsilon = 1e-6; + static constexpr double kEpsilon = 0.1; if (std::abs(vehicle_state_.linear_velocity()) < kEpsilon) { vehicle_state_.set_kappa(0.0); } else { diff --git a/modules/common_msgs/BUILD b/modules/common_msgs/BUILD index d023b4d0366..89441e11a7d 100644 --- a/modules/common_msgs/BUILD +++ b/modules/common_msgs/BUILD @@ -8,7 +8,6 @@ install( name = "install", data_dest = "common-msgs", data = [ - ":cyberfile.xml", ":common-msgs.BUILD", ], deps = [ @@ -120,8 +119,8 @@ install_files( dest = "common-msgs/python/modules/common_msgs", files = [ "//modules/common_msgs/audio_msgs:audio_common_py_pb2", - "//modules/common_msgs/audio_msgs:audio_event_py_pb2", - "//modules/common_msgs/audio_msgs:audio_py_pb2", + "//modules/common_msgs/audio_msgs:audio_event_py_pb2", + "//modules/common_msgs/audio_msgs:audio_py_pb2", "//modules/common_msgs/chassis_msgs:chassis_detail_py_pb2", "//modules/common_msgs/chassis_msgs:chassis_py_pb2", "//modules/common_msgs/config_msgs:vehicle_config_py_pb2", diff --git a/modules/common_msgs/chassis_msgs/BUILD b/modules/common_msgs/chassis_msgs/BUILD index 962c2a81708..6e38efa0a52 100644 --- a/modules/common_msgs/chassis_msgs/BUILD +++ b/modules/common_msgs/chassis_msgs/BUILD @@ -5,6 +5,60 @@ load("//tools:python_rules.bzl", "py_proto_library") package(default_visibility = ["//visibility:public"]) +cc_proto_library( + name = "ge3_cc_proto", + deps = [ + ":ge3_proto", + ], +) + +proto_library( + name = "ge3_proto", + srcs = ["ge3.proto"], +) + +py_proto_library( + name = "ge3_py_pb2", + deps = [ + ":ge3_proto", + ], +) +cc_proto_library( + name = "wey_cc_proto", + deps = [ + ":wey_proto", + ], +) + +proto_library( + name = "wey_proto", + srcs = ["wey.proto"], +) + +py_proto_library( + name = "wey_py_pb2", + deps = [ + ":wey_proto", + ], +) +cc_proto_library( + name = "ch_cc_proto", + deps = [ + ":ch_proto", + ], +) + +proto_library( + name = "ch_proto", + srcs = ["ch.proto"], +) + +py_proto_library( + name = "ch_py_pb2", + deps = [ + ":ch_proto", + ], +) cc_proto_library( name = "chassis_cc_proto", deps = [ @@ -36,6 +90,42 @@ py_proto_library( ], ) +cc_proto_library( + name = "zhongyun_cc_proto", + deps = [ + ":zhongyun_proto", + ], +) + +proto_library( + name = "zhongyun_proto", + srcs = ["zhongyun.proto"], +) + +py_proto_library( + name = "zhongyun_py_pb2", + deps = [ + ":zhongyun_proto", + ], +) +cc_proto_library( + name = "neolix_edu_cc_proto", + deps = [ + ":neolix_edu_proto", + ], +) + +proto_library( + name = "neolix_edu_proto", + srcs = ["neolix_edu.proto"], +) + +py_proto_library( + name = "neolix_edu_py_pb2", + deps = [ + ":neolix_edu_proto", + ], +) cc_proto_library( name = "chassis_detail_cc_proto", deps = [ @@ -49,6 +139,14 @@ proto_library( deps = [ "//modules/common_msgs/basic_msgs:vehicle_id_proto", ":chassis_proto", + ":ch_proto", + ":devkit_proto", + ":ge3_proto", + ":lexus_proto", + ":neolix_edu_proto", + ":transit_proto", + ":wey_proto", + ":zhongyun_proto", ], ) @@ -58,5 +156,68 @@ py_proto_library( ":chassis_detail_proto", "//modules/common_msgs/basic_msgs:vehicle_id_py_pb2", ":chassis_py_pb2", + ":ch_py_pb2", + ":devkit_py_pb2", + ":ge3_py_pb2", + ":lexus_py_pb2", + ":neolix_edu_py_pb2", + ":transit_py_pb2", + ":wey_py_pb2", + ":zhongyun_py_pb2", ], -) \ No newline at end of file +) + +cc_proto_library( + name = "transit_cc_proto", + deps = [ + ":transit_proto", + ], +) + +proto_library( + name = "transit_proto", + srcs = ["transit.proto"], +) + +py_proto_library( + name = "transit_py_pb2", + deps = [ + ":transit_proto", + ], +) +cc_proto_library( + name = "lexus_cc_proto", + deps = [ + ":lexus_proto", + ], +) + +proto_library( + name = "lexus_proto", + srcs = ["lexus.proto"], +) + +py_proto_library( + name = "lexus_py_pb2", + deps = [ + ":lexus_proto", + ], +) +cc_proto_library( + name = "devkit_cc_proto", + deps = [ + ":devkit_proto", + ], +) + +proto_library( + name = "devkit_proto", + srcs = ["devkit.proto"], +) + +py_proto_library( + name = "devkit_py_pb2", + deps = [ + ":devkit_proto", + ], +) diff --git a/modules/canbus_vehicle/ch/proto/ch.proto b/modules/common_msgs/chassis_msgs/ch.proto similarity index 54% rename from modules/canbus_vehicle/ch/proto/ch.proto rename to modules/common_msgs/chassis_msgs/ch.proto index 353885c53c8..9f5a4d3c3e7 100644 --- a/modules/canbus_vehicle/ch/proto/ch.proto +++ b/modules/common_msgs/chassis_msgs/ch.proto @@ -4,7 +4,7 @@ package apollo.canbus; // Coolhigh vehicle starts from here message Throttle_command_110 { -// Control Message + // Control Message enum Throttle_pedal_en_ctrlType { THROTTLE_PEDAL_EN_CTRL_DISABLE = 0; THROTTLE_PEDAL_EN_CTRL_ENABLE = 1; @@ -16,7 +16,7 @@ message Throttle_command_110 { } message Brake_command_111 { -// Control Message + // Control Message enum Brake_pedal_en_ctrlType { BRAKE_PEDAL_EN_CTRL_DISABLE = 0; BRAKE_PEDAL_EN_CTRL_ENABLE = 1; @@ -28,7 +28,7 @@ message Brake_command_111 { } message Steer_command_112 { -// Control Message + // Control Message enum Steer_angle_en_ctrlType { STEER_ANGLE_EN_CTRL_DISABLE = 0; STEER_ANGLE_EN_CTRL_ENABLE = 1; @@ -40,25 +40,18 @@ message Steer_command_112 { } message Turnsignal_command_113 { -// Control Message - enum Low_beam_cmdType { - LOW_BEAM_CMD_OFF = 0; - LOW_BEAM_CMD_ON = 1; - } + // Control Message enum Turn_signal_cmdType { TURN_SIGNAL_CMD_NONE = 0; TURN_SIGNAL_CMD_LEFT = 1; TURN_SIGNAL_CMD_RIGHT = 2; - TURN_SIGNAL_CMD_HAZARD_WARNING_LAMPSTS = 3; } - // Lighting control(Command) [] [0|3] + // Lighting control(Command) [] [0|2] optional Turn_signal_cmdType turn_signal_cmd = 1; - // Lighting control(Command) [] [0|1] - optional Low_beam_cmdType low_beam_cmd = 2; } message Gear_command_114 { -// Control Message + // Control Message enum Gear_cmdType { GEAR_CMD_PARK = 1; GEAR_CMD_REVERSE = 2; @@ -79,18 +72,8 @@ message Control_command_115 { optional Ctrl_cmdType ctrl_cmd = 1; } -message Vehicle_mode_command_116 { -// Control Message - enum Vin_req_cmdType { - VIN_REQ_CMD_VIN_REQ_DISABLE = 0; - VIN_REQ_CMD_VIN_REQ_ENABLE = 1; - } - // Request VIN(Command) [] [0|1] - optional Vin_req_cmdType vin_req_cmd = 1; -} - message Throttle_status__510 { -// Report Message + // Report Message enum Throttle_pedal_en_stsType { THROTTLE_PEDAL_EN_STS_DISABLE = 0; THROTTLE_PEDAL_EN_STS_ENABLE = 1; @@ -115,11 +98,7 @@ message Throttle_status__510 { } message Brake_status__511 { -// Report Message - enum Overspd_envType { - OVERSPD_ENV_NOENV = 0; - OVERSPD_ENV_OVERSPEED_ENV = 1; - } + // Report Message enum Brake_pedal_en_stsType { BRAKE_PEDAL_EN_STS_DISABLE = 0; BRAKE_PEDAL_EN_STS_ENABLE = 1; @@ -141,11 +120,10 @@ message Brake_status__511 { BACK_BUMP_ENV_NOENV = 0; BACK_BUMP_ENV_BACK_BUMPER_ENV = 1; } - enum Brake_light_actualType { - BRAKE_LIGHT_ACTUAL_BRAKELIGHT_OFF = 0; - BRAKE_LIGHT_ACTUAL_BRAKELIGHT_ON = 1; + enum Overspd_envType { + OVERSPD_ENV_NOENV = 0; + OVERSPD_ENV_OVERSPEED_ENV = 1; } - // brake pedal enable bit(Status) [] [0|2] optional Brake_pedal_en_stsType brake_pedal_en_sts = 1; // Percentage of brake pedal(Status) [%] [0|100] @@ -160,12 +138,10 @@ message Brake_status__511 { optional Back_bump_envType back_bump_env = 6; // [] [0|1] optional Overspd_envType overspd_env = 7; - // [] [0|1] - optional Brake_light_actualType brake_light_actual = 8; } message Steer_status__512 { -// Report Message + // Report Message enum Steer_angle_en_stsType { STEER_ANGLE_EN_STS_DISABLE = 0; STEER_ANGLE_EN_STS_ENABLE = 1; @@ -190,25 +166,18 @@ message Steer_status__512 { } message Turnsignal_status__513 { -// Report Message - enum Low_beam_stsType { - LOW_BEAM_STS_ON = 0; - LOW_BEAM_STS_OFF = 1; - } + // Report Message enum Turn_signal_stsType { TURN_SIGNAL_STS_NONE = 0; TURN_SIGNAL_STS_LEFT = 1; TURN_SIGNAL_STS_RIGHT = 2; - TURN_SIGNAL_STS_HAZARD_WARNING_LAMPSTS_ON = 3; } - // Lighting control(Status) [] [0|3] + // Lighting control(Status) [] [0|2] optional Turn_signal_stsType turn_signal_sts = 1; - // Lighting control(Status) [] [0|1] - optional Low_beam_stsType low_beam_sts = 2; } message Gear_status_514 { -// Report Message + // Report Message enum Gear_stsType { GEAR_STS_PARK = 1; GEAR_STS_REVERSE = 2; @@ -220,49 +189,12 @@ message Gear_status_514 { } message Ecu_status_1_515 { -// Report Message + // Report Message enum Ctrl_stsType { CTRL_STS_OUT_OF_CONTROL = 0; CTRL_STS_UNDER_CONTROL = 1; } - enum Chassis_mcu_errType { - CHASSIS_MCU_ERR_NORMAL = 0; - CHASSIS_MCU_ERR_ERROR = 1; - } - enum Chassis_mcu_canType { - CHASSIS_MCU_CAN_NORMAL = 0; - CHASSIS_MCU_CAN_ERROR = 1; - } - enum Chassis_hw_lostType { - CHASSIS_HW_LOST_NORMAL = 0; - CHASSIS_HW_LOST_ERROR = 1; - } - enum Chassis_eps_errType { - CHASSIS_EPS_ERR_NORMAL = 0; - CHASSIS_EPS_ERR_ERROR = 1; - } - enum Chassis_eps_canType { - CHASSIS_EPS_CAN_NORMAL = 0; - CHASSIS_EPS_CAN_ERROR = 1; - } - enum Chassis_ehb_errType { - CHASSIS_EHB_ERR_NORMAL = 0; - CHASSIS_EHB_ERR_ERROR = 1; - } - enum Chassis_ehb_canType { - CHASSIS_EHB_CAN_NORMAL = 0; - CHASSIS_EHB_CAN_ERROR = 1; - } - enum Chassis_bms_canType { - CHASSIS_BMS_CAN_NORMAL = 0; - CHASSIS_BMS_CAN_ERROR = 1; - } - enum Chassis_ads_errType { - CHASSIS_ADS_ERR_NORMAL = 0; - CHASSIS_ADS_ERR_ADS_CAN_LOST = 1; - CHASSIS_ADS_ERR_ADS_CAN_RECOVERY = 2; - } - // Current speed (Steering status) [m/s] [-327.68|327.67] + // Current speed (Steering status) [m/s] [0|0] optional double speed = 1; // Current acceleration (Steering status) [m/s^2] [0|0] optional double acc_speed = 2; @@ -272,28 +204,10 @@ message Ecu_status_1_515 { optional int32 chassis_sts = 4; // Chassis error code (Chassis status) [] [0|65535] optional int32 chassis_err = 5; - // [] [0|1] - optional Chassis_mcu_errType chassis_mcu_err = 6; - // [] [0|1] - optional Chassis_mcu_canType chassis_mcu_can = 7; - // [] [0|1] - optional Chassis_hw_lostType chassis_hw_lost = 8; - // [] [0|1] - optional Chassis_eps_errType chassis_eps_err = 9; - // [] [0|1] - optional Chassis_eps_canType chassis_eps_can = 10; - // [] [0|1] - optional Chassis_ehb_errType chassis_ehb_err = 11; - // [] [0|1] - optional Chassis_ehb_canType chassis_ehb_can = 12; - // [] [0|1] - optional Chassis_bms_canType chassis_bms_can = 13; - // Chassis error code (Chassis status) [] [0|2] - optional Chassis_ads_errType chassis_ads_err = 14; } message Ecu_status_2_516 { -// Report Message + // Report Message // Percentage of battery remaining (BMS status) [%] [0|100] optional int32 battery_soc = 1; // Battery full capacity (BMS status) [Ah] [0|100] @@ -304,12 +218,10 @@ message Ecu_status_2_516 { optional double battery_current = 4; // Current battery temperature (BMS status) [℃] [-40|110] optional int32 battery_temperature = 5; - // Battery Low Soc Warn [] [0|1] - optional bool is_battery_soc_low = 6; } message Ecu_status_3_517 { -// Report Message + // Report Message // Ultrasonic detection distance 1 (Ultrasound status) [cm] [0|500] optional double ultrasound_dist_1 = 1; // Ultrasonic detection distance 2 (Ultrasound status) [cm] [0|500] @@ -328,102 +240,13 @@ message Ecu_status_3_517 { optional double ultrasound_dist_8 = 8; } -message Ecu_status_4_518 { -// Report Message - // Ultrasonic detection distance 9 (Ultrasound status) [cm] [0|500] - optional double ultrasound_dist_9 = 1; - // Ultrasonic detection distance 10 (Ultrasound status) [cm] [0|500] - optional double ultrasound_dist_10 = 2; - // Ultrasonic detection distance 11 (Ultrasound status) [cm] [0|500] - optional double ultrasound_dist_11 = 3; - // Ultrasonic detection distance 12 (Ultrasound status) [cm] [0|500] - optional double ultrasound_dist_12 = 4; - // Ultrasonic detection distance 13 (Ultrasound status) [cm] [0|500] - optional double ultrasound_dist_13 = 5; - // Ultrasonic detection distance 14 (Ultrasound status) [cm] [0|500] - optional double ultrasound_dist_14 = 6; - // Ultrasonic detection distance 15 (Ultrasound status) [cm] [0|500] - optional double ultrasound_dist_15 = 7; - // Ultrasonic detection distance 16 (Ultrasound status) [cm] [0|500] - optional double ultrasound_dist_16 = 8; -} - -message Vin_resp1_51b { -// Report Message - // VIN Response [] [0|255] to char - optional string vin08 = 1; - // VIN Response [] [0|255] to char - optional string vin07 = 2; - // VIN Response [] [0|255] to char - optional string vin06 = 3; - // VIN Response [] [0|255] to char - optional string vin05 = 4; - // VIN Response [] [0|255] to char - optional string vin04 = 5; - // VIN Response [] [0|255] to char - optional string vin03 = 6; - // VIN Response [] [0|255] to char - optional string vin02 = 7; - // VIN Response [] [0|255] to char - optional string vin01 = 8; -} - -message Vin_resp2_51c { -// Report Message - // VIN Response [] [0|0] to char - optional string vin16 = 1; - // VIN Response [] [0|0] to char - optional string vin15 = 2; - // VIN Response [] [0|0] to char - optional string vin14 = 3; - // VIN Response [] [0|0] to char - optional string vin13 = 4; - // VIN Response [] [0|0] to char - optional string vin12 = 5; - // VIN Response [] [0|0] to char - optional string vin11 = 6; - // VIN Response [] [0|0] to char - optional string vin10 = 7; - // VIN Response [] [0|0] to char - optional string vin09 = 8; -} - -message Vin_resp3_51d { -// Report Message - // VIN Response [] [0|0] to char - optional string vin17 = 1; -} - -message Wheelspeed_report_51e { -// Report Message - // wheel speed rear right [m/s] [-327.68|327.67] - optional double rr = 1; - // wheel speed rear left [m/s] [-327.68|327.67] - optional double rl = 2; - // wheel speed front right [m/s] [-327.68|327.67] - optional double fr = 3; - // wheel speed front left [m/s] [-327.68|327.67] - optional double fl = 4; -} - -// CheckResponseSignal -message CheckResponseSignal { - optional bool is_eps_online = 1 [default = false]; - optional bool is_epb_online = 2 [default = false]; - optional bool is_esp_online = 3 [default = false]; - optional bool is_vtog_online = 4 [default = false]; - optional bool is_scu_online = 5 [default = false]; - optional bool is_switch_online = 6 [default = false]; - optional bool is_vcu_online = 7 [default = false]; -} - message Ch { optional Throttle_command_110 throttle_command_110 = 1; // control message optional Brake_command_111 brake_command_111 = 2; // control message optional Steer_command_112 steer_command_112 = 3; // control message optional Turnsignal_command_113 turnsignal_command_113 = 4; // control message optional Gear_command_114 gear_command_114 = 5; // control message - optional Control_command_115 control_command_115 = 6 [deprecated = true]; // control message + optional Control_command_115 control_command_115 = 6; // control message optional Throttle_status__510 throttle_status__510 = 7; // report message optional Brake_status__511 brake_status__511 = 8; // report message optional Steer_status__512 steer_status__512 = 9; // report message @@ -432,11 +255,4 @@ message Ch { optional Ecu_status_1_515 ecu_status_1_515 = 12; // report message optional Ecu_status_2_516 ecu_status_2_516 = 13; // report message optional Ecu_status_3_517 ecu_status_3_517 = 14; // report message - optional Ecu_status_4_518 ecu_status_4_518 = 15; // report message - optional Vehicle_mode_command_116 vehicle_mode_command_116 = 16; // control message - optional Vin_resp1_51b vin_resp1_51b = 17; // report message - optional Vin_resp2_51c vin_resp2_51c = 18; // report message - optional Vin_resp3_51d vin_resp3_51d = 19; // report message - optional Wheelspeed_report_51e wheelspeed_report_51e = 20; // report message - optional CheckResponseSignal check_response = 100; } diff --git a/modules/common_msgs/chassis_msgs/chassis_detail.proto b/modules/common_msgs/chassis_msgs/chassis_detail.proto index c7509691679..9a4584c3c10 100644 --- a/modules/common_msgs/chassis_msgs/chassis_detail.proto +++ b/modules/common_msgs/chassis_msgs/chassis_detail.proto @@ -4,7 +4,14 @@ package apollo.canbus; import "modules/common_msgs/basic_msgs/vehicle_id.proto"; import "modules/common_msgs/chassis_msgs/chassis.proto"; - +import "modules/common_msgs/chassis_msgs/ch.proto"; +import "modules/common_msgs/chassis_msgs/devkit.proto"; +import "modules/common_msgs/chassis_msgs/ge3.proto"; +import "modules/common_msgs/chassis_msgs/lexus.proto"; +import "modules/common_msgs/chassis_msgs/neolix_edu.proto"; +import "modules/common_msgs/chassis_msgs/transit.proto"; +import "modules/common_msgs/chassis_msgs/wey.proto"; +import "modules/common_msgs/chassis_msgs/zhongyun.proto"; message ChassisDetail { enum Type { @@ -28,6 +35,17 @@ message ChassisDetail { optional CheckResponseSignal check_response = 15; optional License license = 16 [deprecated = true]; // License info optional Surround surround = 17; // Surround information + + optional Gem gem = 18; + optional Lexus lexus = 19; + optional Transit transit = 20; + optional Ge3 ge3 = 21; + optional Wey wey = 22; + optional Zhongyun zhongyun = 23; + optional Ch ch = 24; + optional Devkit devkit = 25; + optional Neolix_edu neolix_edu = 26; + // Reserve fields for other vehicles optional apollo.common.VehicleID vehicle_id = 101; } diff --git a/modules/canbus_vehicle/devkit/proto/devkit.proto b/modules/common_msgs/chassis_msgs/devkit.proto similarity index 63% rename from modules/canbus_vehicle/devkit/proto/devkit.proto rename to modules/common_msgs/chassis_msgs/devkit.proto index a08638e9d29..c5ee33743a8 100644 --- a/modules/canbus_vehicle/devkit/proto/devkit.proto +++ b/modules/common_msgs/chassis_msgs/devkit.proto @@ -16,8 +16,6 @@ message Throttle_command_100 { optional double throttle_pedal_target = 3; // [] [0|1] optional Throttle_en_ctrlType throttle_en_ctrl = 4; - // [m/s] [0|10.23] - optional double speed_target = 5; } message Brake_command_101 { @@ -53,7 +51,7 @@ message Steering_command_102 { // [deg] [-500|500] optional int32 steer_angle_target = 2; // [deg/s] [0|250] - optional int32 steer_angle_spd_target = 3; + optional int32 steer_angle_spd = 3; // [] [0|255] optional int32 checksum_102 = 4; } @@ -97,39 +95,6 @@ message Park_command_104 { optional Park_en_ctrlType park_en_ctrl = 3; } -message Vehicle_mode_command_105 { -// Control Message - enum Turn_light_ctrlType { - TURN_LIGHT_CTRL_TURNLAMP_OFF = 0; - TURN_LIGHT_CTRL_LEFT_TURNLAMP_ON = 1; - TURN_LIGHT_CTRL_RIGHT_TURNLAMP_ON = 2; - TURN_LIGHT_CTRL_HAZARD_WARNING_LAMPSTS_ON = 3; - } - enum Vin_reqType { - VIN_REQ_VIN_REQ_DISABLE = 0; - VIN_REQ_VIN_REQ_ENABLE = 1; - } - enum Drive_mode_ctrlType { - DRIVE_MODE_CTRL_THROTTLE_PADDLE_DRIVE = 0; - DRIVE_MODE_CTRL_SPEED_DRIVE = 1; - } - enum Steer_mode_ctrlType { - STEER_MODE_CTRL_STANDARD_STEER = 0; - STEER_MODE_CTRL_NON_DIRECTION_STEER = 1; - STEER_MODE_CTRL_SYNC_DIRECTION_STEER = 2; - } - // [] [0|255] - optional int32 checksum_105 = 1; - // [] [0|7] - optional Turn_light_ctrlType turn_light_ctrl = 2; - // [] [0|1] - optional Vin_reqType vin_req = 3; - // [] [0|7] - optional Drive_mode_ctrlType drive_mode_ctrl = 4; - // [] [0|7] - optional Steer_mode_ctrlType steer_mode_ctrl = 5; -} - message Throttle_report_500 { // Report Message enum Throttle_flt2Type { @@ -208,8 +173,6 @@ message Steering_report_502 { optional Steer_en_stateType steer_en_state = 4; // [deg] [-500|500] optional int32 steer_angle_actual = 5; - // [deg] [-500|500] - optional int32 steer_angle_rear_actual = 6; } message Gear_report_503 { @@ -255,29 +218,6 @@ message Vcu_report_505 { VEHICLE_MODE_STATE_EMERGENCY_MODE = 2; VEHICLE_MODE_STATE_STANDBY_MODE = 3; } - enum Aeb_modeType { - AEB_MODE_DISABLE = 0; - AEB_MODE_ENABLE = 1; - } - enum Brake_light_actualType { - BRAKE_LIGHT_ACTUAL_BRAKELIGHT_OFF = 0; - BRAKE_LIGHT_ACTUAL_BRAKELIGHT_ON = 1; - } - enum Turn_light_actualType { - TURN_LIGHT_ACTUAL_TURNLAMPSTS_OFF = 0; - TURN_LIGHT_ACTUAL_LEFT_TURNLAMPSTS_ON = 1; - TURN_LIGHT_ACTUAL_RIGHT_TURNLAMPSTS_ON = 2; - TURN_LIGHT_ACTUAL_HAZARD_WARNING_LAMPSTS_ON = 3; - } - enum Drive_mode_stsType { - DRIVE_MODE_STS_THROTTLE_PADDLE_DRIVE_MODE = 0; - DRIVE_MODE_STS_SPEED_DRIVE_MODE = 1; - } - enum Steer_mode_stsType { - STEER_MODE_STS_STANDARD_STEER_MODE = 0; - STEER_MODE_STS_NON_DIRECTION_STEER_MODE = 1; - STEER_MODE_STS_SYNC_DIRECTION_STEER_MODE = 2; - } enum Frontcrash_stateType { FRONTCRASH_STATE_NO_EVENT = 0; FRONTCRASH_STATE_CRASH_EVENT = 1; @@ -286,34 +226,22 @@ message Vcu_report_505 { BACKCRASH_STATE_NO_EVENT = 0; BACKCRASH_STATE_CRASH_EVENT = 1; } - enum Aeb_brake_stateType { - AEB_BRAKE_STATE_INACTIVE = 0; - AEB_BRAKE_STATE_ACTIVE = 1; + enum Aeb_stateType { + AEB_STATE_INACTIVE = 0; + AEB_STATE_ACTIVE = 1; } // [] [0|0] optional Vehicle_mode_stateType vehicle_mode_state = 1; - // describle the vehicle AEB mode whether was set [] [0|1] - optional Aeb_modeType aeb_mode = 2; - // [] [0|1] - optional Brake_light_actualType brake_light_actual = 3; // [] [0|0] - optional Turn_light_actualType turn_light_actual = 4; - // [] [0|255] - optional int32 chassis_errcode = 5; - // [] [0|7] - optional Drive_mode_stsType drive_mode_sts = 6; - // [] [0|7] - optional Steer_mode_stsType steer_mode_sts = 7; + optional Frontcrash_stateType frontcrash_state = 2; // [] [0|0] - optional Frontcrash_stateType frontcrash_state = 8; + optional Backcrash_stateType backcrash_state = 3; // [] [0|0] - optional Backcrash_stateType backcrash_state = 9; - // describe the vehicle e-brake command whether was triggered by AEB [] [0|0] - optional Aeb_brake_stateType aeb_brake_state = 10; + optional Aeb_stateType aeb_state = 4; // [m/s^2] [-10|10] - optional double acc = 11; - // [m/s] [-32.768|32.767] - optional double speed = 12; + optional double acc = 5; + // [m/s] [0|65.535] + optional double speed = 6; } message Wheelspeed_report_506 { @@ -390,85 +318,12 @@ message Ultr_sensor_5_511 { message Bms_report_512 { // Report Message - enum Battery_flt_lowtempType { - BATTERY_FLT_LOW_TEMP_NO_FAULT = 0; - BATTERY_FLT_LOW_TEMP_FAULT = 1; - } - enum Battery_flt_overtempType { - BATTERY_FLT_OVER_TEMP_NO_FAULT = 0; - BATTERY_FLT_OVER_TEMP_FAULT = 1; - } // Battery Total Current [A] [-3200|3200] optional double battery_current = 1; // Battery Total Voltage [V] [0|300] optional double battery_voltage = 2; - // Battery State of Charge percentage [%] [0|100] - optional int32 battery_soc_percentage = 3; - // Battery Low Soc Warn - optional bool is_battery_soc_low = 4; - // Battery inside temperature - optional double battery_inside_temperature = 5; - // Battery Below Low temp fault - optional Battery_flt_lowtempType battery_flt_low_temp = 6; - // Battery Over High Temp fault - optional Battery_flt_overtempType battery_flt_over_temp = 7; -} - -message Vin_resp1_514 { -// Report Message - // [] [0|255] to char - optional string vin07 = 1; - // [] [0|255] to char - optional string vin06 = 2; - // [] [0|255] to char - optional string vin05 = 3; - // [] [0|255] to char - optional string vin04 = 4; - // [] [0|255] to char - optional string vin03 = 5; - // [] [0|255] to char - optional string vin02 = 6; - // [] [0|255] to char - optional string vin01 = 7; - // [] [0|255] to char - optional string vin00 = 8; -} - -message Vin_resp2_515 { -// Report Message - // [] [0|255] to char - optional string vin15 = 1; - // [] [0|255] to char - optional string vin14 = 2; - // [] [0|255] to char - optional string vin13 = 3; - // [] [0|255] to char - optional string vin12 = 4; - // [] [0|255] to char - optional string vin11 = 5; - // [] [0|255] to char - optional string vin10 = 6; - // [] [0|255] to char - optional string vin09 = 7; - // [] [0|255] to char - optional string vin08 = 8; -} - -message Vin_resp3_516 { -// Report Message - // [] [0|255] to char - optional string vin16 = 1; -} - -// CheckResponseSignal -message CheckResponseSignal { - optional bool is_eps_online = 1 [default = false]; - optional bool is_epb_online = 2 [default = false]; - optional bool is_esp_online = 3 [default = false]; - optional bool is_vtog_online = 4 [default = false]; - optional bool is_scu_online = 5 [default = false]; - optional bool is_switch_online = 6 [default = false]; - optional bool is_vcu_online = 7 [default = false]; + // Battery Soc percentage [%] [0|100] + optional int32 battery_soc = 3; } message Devkit { @@ -490,10 +345,4 @@ message Devkit { optional Ultr_sensor_4_510 ultr_sensor_4_510 = 16; // report message optional Ultr_sensor_5_511 ultr_sensor_5_511 = 17; // report message optional Bms_report_512 bms_report_512 = 18; // report message - optional Vehicle_mode_command_105 vehicle_mode_command_105 = 19; // control message - optional Vin_resp1_514 vin_resp1_514 = 20; // report message - optional Vin_resp2_515 vin_resp2_515 = 21; // report message - optional Vin_resp3_516 vin_resp3_516 = 22; // report message - - optional CheckResponseSignal check_response = 100; } diff --git a/modules/canbus_vehicle/ge3/proto/ge3.proto b/modules/common_msgs/chassis_msgs/ge3.proto similarity index 97% rename from modules/canbus_vehicle/ge3/proto/ge3.proto rename to modules/common_msgs/chassis_msgs/ge3.proto index a284023419b..a0b314604e6 100644 --- a/modules/canbus_vehicle/ge3/proto/ge3.proto +++ b/modules/common_msgs/chassis_msgs/ge3.proto @@ -612,17 +612,6 @@ message Scu_eps_311 { optional Eps_drvmodeType eps_drvmode = 5; } -// CheckResponseSignal -message CheckResponseSignal { - optional bool is_eps_online = 1 [default = false]; - optional bool is_epb_online = 2 [default = false]; - optional bool is_esp_online = 3 [default = false]; - optional bool is_vtog_online = 4 [default = false]; - optional bool is_scu_online = 5 [default = false]; - optional bool is_switch_online = 6 [default = false]; - optional bool is_vcu_online = 7 [default = false]; -} - message Ge3 { optional Pc_bcm_201 pc_bcm_201 = 1; // control message optional Scu_bcs_3_308 scu_bcs_3_308 = 2; // report message @@ -640,5 +629,4 @@ message Ge3 { optional Scu_epb_310 scu_epb_310 = 14; // report message optional Scu_vcu_1_312 scu_vcu_1_312 = 15; // report message optional Scu_eps_311 scu_eps_311 = 16; // report message - optional CheckResponseSignal check_response = 100; } diff --git a/modules/canbus_vehicle/lexus/proto/lexus.proto b/modules/common_msgs/chassis_msgs/lexus.proto similarity index 98% rename from modules/canbus_vehicle/lexus/proto/lexus.proto rename to modules/common_msgs/chassis_msgs/lexus.proto index 3067666110c..3216e523757 100644 --- a/modules/canbus_vehicle/lexus/proto/lexus.proto +++ b/modules/common_msgs/chassis_msgs/lexus.proto @@ -1275,17 +1275,6 @@ message Rear_lights_rpt_418 { optional bool brake_lights_on = 4; } -// CheckResponseSignal -message CheckResponseSignal { - optional bool is_eps_online = 1 [default = false]; - optional bool is_epb_online = 2 [default = false]; - optional bool is_esp_online = 3 [default = false]; - optional bool is_vtog_online = 4 [default = false]; - optional bool is_scu_online = 5 [default = false]; - optional bool is_switch_online = 6 [default = false]; - optional bool is_vcu_online = 7 [default = false]; -} - message Lexus { optional Hazard_lights_rpt_214 hazard_lights_rpt_214 = 1; // report message optional Steering_cmd_12c steering_cmd_12c = 2; // report message @@ -1358,5 +1347,4 @@ message Lexus { 54; // report message optional Veh_dynamics_rpt_413 veh_dynamics_rpt_413 = 55; // report message optional Rear_lights_rpt_418 rear_lights_rpt_418 = 56; // report message - optional CheckResponseSignal check_response = 100; } diff --git a/modules/canbus_vehicle/neolix_edu/proto/neolix_edu.proto b/modules/common_msgs/chassis_msgs/neolix_edu.proto similarity index 88% rename from modules/canbus_vehicle/neolix_edu/proto/neolix_edu.proto rename to modules/common_msgs/chassis_msgs/neolix_edu.proto index 4f46a70f97b..00681d9aed9 100644 --- a/modules/canbus_vehicle/neolix_edu/proto/neolix_edu.proto +++ b/modules/common_msgs/chassis_msgs/neolix_edu.proto @@ -2,8 +2,6 @@ syntax = "proto2"; package apollo.canbus; -import "modules/common_msgs/chassis_msgs/chassis.proto"; - message Aeb_systemstate_11 { // Report Message // 0x00:read only;0x01:brake enable [] [0|1] @@ -141,13 +139,6 @@ message Vcu_brake_report_47 { CONTROL_MODE_RESP_REMOTE_CONTROL = 3; CONTROL_MODE_RESP_EMERGENCY_BRAKE = 4; } - enum Vcu_ehb_brakeType { - VCU_EHB_NORMAL_BRAKE = 0; - VCU_EHB_BACKUP_REMOTE_BRAKE = 1; - VCU_EHB_EMERGENCY_BUTTON_BRAKE = 2; - VCU_EHB_ULTR_BRAKE = 3; - VCU_EHB_BUMPER_BRAKE = 4; - } // 0x0:disable;0x1:enable [] [0|0] optional bool brake_enable_resp = 1; // 0x0:Standby;0x1:auto drive;0x2:net drive;0x3:remote control;0x4:emergency @@ -170,8 +161,6 @@ message Vcu_brake_report_47 { optional int32 vcu_brakerept_alivecounter = 9; // [] [0|0] optional int32 vcu_brakerept_checksum = 10; - // [] - optional Vcu_ehb_brakeType vcu_ehb_brake_state = 11; } message Vcu_eps_report_57 { @@ -469,57 +458,6 @@ message Aeb_frontwheelspeed_353 { optional double checksum_front = 11; } -message VehicleSpd { - optional double vehicle_spd = 1 [default = 0]; // unit:m/s -} - -// Battery -message Battery { - optional double battery_percent = 1; // unit:%, battery percentage left -} -message Safety { - optional int32 driving_mode = 1; -} - -message Gas { - optional double gas_pedal_position = 1 [default = 0]; // manual gas -} - -message Gear { - optional Chassis.GearPosition gear_state = 1; -} - -message Brake { - optional double brake_pedal_position = 1; -} - -// Electrical Power Steering -message Eps { - optional double steering_angle = 1; // unit:degree -} - -// Electrical Parking Brake -message Epb { - enum PBrakeType { - PBRAKE_OFF = 0; - PBRAKE_TRANSITION = 1; - PBRAKE_ON = 2; - PBRAKE_FAULT = 3; - } - optional PBrakeType parking_brake_status = 4; -} - -// CheckResponseSignal -message CheckResponseSignal { - optional bool is_eps_online = 1 [default = false]; - optional bool is_epb_online = 2 [default = false]; - optional bool is_esp_online = 3 [default = false]; - optional bool is_vtog_online = 4 [default = false]; - optional bool is_scu_online = 5 [default = false]; - optional bool is_switch_online = 6 [default = false]; - optional bool is_vcu_online = 7 [default = false]; -} - message Neolix_edu { optional Aeb_systemstate_11 aeb_systemstate_11 = 1; // report message optional Vcu_vehicle_fault_response_201 vcu_vehicle_fault_response_201 = @@ -548,13 +486,4 @@ message Neolix_edu { 20; // report message optional Aeb_frontwheelspeed_353 aeb_frontwheelspeed_353 = 21; // report message - optional VehicleSpd vehicle_spd = 50; - optional Battery battery = 51; // Battery info - optional Safety safety = 52; // safety - optional Gas gas = 53; // gas pedal - optional Gear gear = 54; // gear - optional Brake brake = 55; // brake pedal - optional Eps eps = 56; // Electronic Power Steering - optional Epb epb = 57; // Electronic parking brake - optional CheckResponseSignal check_response = 58; } diff --git a/modules/canbus_vehicle/transit/proto/transit.proto b/modules/common_msgs/chassis_msgs/transit.proto similarity index 96% rename from modules/canbus_vehicle/transit/proto/transit.proto rename to modules/common_msgs/chassis_msgs/transit.proto index 88137574eba..ec3cb9a2282 100644 --- a/modules/canbus_vehicle/transit/proto/transit.proto +++ b/modules/common_msgs/chassis_msgs/transit.proto @@ -323,17 +323,6 @@ message Llc_diag_brakecontrol_721 { optional double llc_dbg_brakefeedforward = 6; } -// CheckResponseSignal -message CheckResponseSignal { - optional bool is_eps_online = 1 [default = false]; - optional bool is_epb_online = 2 [default = false]; - optional bool is_esp_online = 3 [default = false]; - optional bool is_vtog_online = 4 [default = false]; - optional bool is_scu_online = 5 [default = false]; - optional bool is_switch_online = 6 [default = false]; - optional bool is_vcu_online = 7 [default = false]; -} - message Transit { optional Llc_vehiclelimits_24 llc_vehiclelimits_24 = 1; // report message optional Adc_motioncontrol1_10 adc_motioncontrol1_10 = 2; // control message @@ -353,5 +342,4 @@ message Transit { 11; // control message optional Llc_diag_brakecontrol_721 llc_diag_brakecontrol_721 = 12; // control message - optional CheckResponseSignal check_response = 100; } diff --git a/modules/canbus_vehicle/wey/proto/wey.proto b/modules/common_msgs/chassis_msgs/wey.proto similarity index 97% rename from modules/canbus_vehicle/wey/proto/wey.proto rename to modules/common_msgs/chassis_msgs/wey.proto index c067633b947..9af7e025301 100644 --- a/modules/canbus_vehicle/wey/proto/wey.proto +++ b/modules/common_msgs/chassis_msgs/wey.proto @@ -585,17 +585,6 @@ message Ads3_38e { optional RwindshieldwiperType rwindshieldwiper = 13; } -// CheckResponseSignal -message CheckResponseSignal { - optional bool is_eps_online = 1 [default = false]; - optional bool is_epb_online = 2 [default = false]; - optional bool is_esp_online = 3 [default = false]; - optional bool is_vtog_online = 4 [default = false]; - optional bool is_scu_online = 5 [default = false]; - optional bool is_switch_online = 6 [default = false]; - optional bool is_vcu_online = 7 [default = false]; -} - message Wey { optional Ads_shifter_115 ads_shifter_115 = 1; // control message optional Ads_eps_113 ads_eps_113 = 2; // control message @@ -611,5 +600,4 @@ message Wey { optional Fail_241 fail_241 = 12; // report message optional Fbs3_237 fbs3_237 = 13; // report message optional Ads3_38e ads3_38e = 14; // control message - optional CheckResponseSignal check_response = 100; } diff --git a/modules/canbus_vehicle/zhongyun/proto/zhongyun.proto b/modules/common_msgs/chassis_msgs/zhongyun.proto similarity index 92% rename from modules/canbus_vehicle/zhongyun/proto/zhongyun.proto rename to modules/common_msgs/chassis_msgs/zhongyun.proto index 6733460f3ae..2427b878e27 100644 --- a/modules/canbus_vehicle/zhongyun/proto/zhongyun.proto +++ b/modules/common_msgs/chassis_msgs/zhongyun.proto @@ -179,17 +179,6 @@ message Vehicle_state_feedback_2_c4 { optional double driven_torque_feedback = 2; } -// CheckResponseSignal -message CheckResponseSignal { - optional bool is_eps_online = 1 [default = false]; - optional bool is_epb_online = 2 [default = false]; - optional bool is_esp_online = 3 [default = false]; - optional bool is_vtog_online = 4 [default = false]; - optional bool is_scu_online = 5 [default = false]; - optional bool is_switch_online = 6 [default = false]; - optional bool is_vcu_online = 7 [default = false]; -} - message Zhongyun { optional Gear_control_a1 gear_control_a1 = 1; // control message optional Torque_control_a3 torque_control_a3 = 2; // control message @@ -203,5 +192,4 @@ message Zhongyun { optional Error_state_e1 error_state_e1 = 8; // report message optional Vehicle_state_feedback_2_c4 vehicle_state_feedback_2_c4 = 9; // report message - optional CheckResponseSignal check_response = 100; } diff --git a/modules/common_msgs/cyberfile.xml b/modules/common_msgs/cyberfile.xml deleted file mode 100644 index 1c0f57f9847..00000000000 --- a/modules/common_msgs/cyberfile.xml +++ /dev/null @@ -1,25 +0,0 @@ - - common-msgs - local - - This module contains code that is not specific to any module but is useful for the functioning of Apollo. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module-wrapper - //modules/common_msgs - - 3rd-rules-python-dev - 3rd-grpc-dev - 3rd-gpus-dev - 3rd-rules-proto-dev - 3rd-bazel-skylib-dev - - 3rd-protobuf-dev - - diff --git a/modules/common_msgs/routing_msgs/routing.proto b/modules/common_msgs/routing_msgs/routing.proto index 56791508cbd..49d2e80c003 100644 --- a/modules/common_msgs/routing_msgs/routing.proto +++ b/modules/common_msgs/routing_msgs/routing.proto @@ -41,6 +41,7 @@ message ParkingInfo { optional ParkingSpaceType parking_space_type = 3; // The four corner points are in order. optional apollo.hdmap.Polygon corner_point = 4; + // todo(@lijin):remove it from proto } message DeadEndInfo { diff --git a/modules/common_msgs/task_manager_msgs/task_manager.proto b/modules/common_msgs/task_manager_msgs/task_manager.proto index eb677592d26..dbce3f11781 100644 --- a/modules/common_msgs/task_manager_msgs/task_manager.proto +++ b/modules/common_msgs/task_manager_msgs/task_manager.proto @@ -26,8 +26,10 @@ message CycleRoutingTask { } message ParkingRoutingTask { - optional double lane_width = 1; - optional apollo.routing.RoutingRequest routing_request = 2; + optional string parking_space_id = 1; + // todo@lijin: remove 2,3 after code change + optional double lane_width = 2; + optional apollo.routing.RoutingRequest routing_request = 3; } message ParkGoRoutingTask { diff --git a/modules/contrib/cyber_bridge/BUILD b/modules/contrib/cyber_bridge/BUILD deleted file mode 100644 index bbcdd7de852..00000000000 --- a/modules/contrib/cyber_bridge/BUILD +++ /dev/null @@ -1,102 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library") -load("//tools/install:install.bzl", "install", "install_files", "install_src_files") -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -install( - name = "install", - data_dest = "cyber-bridge", - data = [ - ":cyberfile.xml", - ":cyber-bridge.BUILD", - ], - targets = [ - ":cyber_bridge", - ], - runtime_dest = "cyber-bridge/bin", - deps = [ - "//cyber:install", - ], -) - -install_src_files( - name = "install_src", - deps = [ - ":install_cyber-bridge_src", - ":install_cyber-bridge_hdrs" - ], -) - -install_src_files( - name = "install_cyber-bridge_src", - src_dir = ["."], - dest = "cyber-bridge/src", - filter = "*", -) - -install_src_files( - name = "install_cyber-bridge_hdrs", - src_dir = ["."], - dest = "cyber-bridge/include", - filter = "*.h", -) - -cc_binary( - name = "cyber_bridge", - srcs = ["bridge.cc"], - deps = [ - ":bridge_server", - "@boost", - "@com_github_gflags_gflags//:gflags", - ], -) - -cc_library( - name = "bridge_server", - srcs = ["server.cc"], - hdrs = ["server.h"], - deps = [ - ":bridge_client", - ], -) - -cc_library( - name = "bridge_client", - srcs = ["client.cc"], - deps = [ - ":bridge_clients", - ":bridge_node", - "@boost", - ], -) - -cc_library( - name = "bridge_clients", - srcs = ["clients.cc"], - hdrs = ["clients.h"], - deps = [ - ":bridge_client_header", - "@boost", - ], -) - -cc_library( - name = "bridge_node", - srcs = ["node.cc"], - hdrs = ["node.h"], - deps = [ - ":bridge_client_header", - ], -) - -cc_library( - name = "bridge_client_header", - hdrs = ["client.h"], - deps = [ - "//cyber", - "@boost", - ], -) - -cpplint() diff --git a/modules/contrib/cyber_bridge/LICENSE b/modules/contrib/cyber_bridge/LICENSE deleted file mode 100644 index 7783de532a3..00000000000 --- a/modules/contrib/cyber_bridge/LICENSE +++ /dev/null @@ -1,53 +0,0 @@ -Apache License - -Version 2.0, January 2004 - -http://www.apache.org/licenses/ - -TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION - -1. Definitions. - -"License" shall mean the terms and conditions for use, reproduction, and distribution as defined by Sections 1 through 9 of this document. - -"Licensor" shall mean the copyright owner or entity authorized by the copyright owner that is granting the License. - -"Legal Entity" shall mean the union of the acting entity and all other entities that control, are controlled by, or are under common control with that entity. For the purposes of this definition, "control" means (i) the power, direct or indirect, to cause the direction or management of such entity, whether by contract or otherwise, or (ii) ownership of fifty percent (50%) or more of the outstanding shares, or (iii) beneficial ownership of such entity. - -"You" (or "Your") shall mean an individual or Legal Entity exercising permissions granted by this License. - -"Source" form shall mean the preferred form for making modifications, including but not limited to software source code, documentation source, and configuration files. - -"Object" form shall mean any form resulting from mechanical transformation or translation of a Source form, including but not limited to compiled object code, generated documentation, and conversions to other media types. - -"Work" shall mean the work of authorship, whether in Source or Object form, made available under the License, as indicated by a copyright notice that is included in or attached to the work (an example is provided in the Appendix below). - -"Derivative Works" shall mean any work, whether in Source or Object form, that is based on (or derived from) the Work and for which the editorial revisions, annotations, elaborations, or other modifications represent, as a whole, an original work of authorship. For the purposes of this License, Derivative Works shall not include works that remain separable from, or merely link (or bind by name) to the interfaces of, the Work and Derivative Works thereof. - -"Contribution" shall mean any work of authorship, including the original version of the Work and any modifications or additions to that Work or Derivative Works thereof, that is intentionally submitted to Licensor for inclusion in the Work by the copyright owner or by an individual or Legal Entity authorized to submit on behalf of the copyright owner. For the purposes of this definition, "submitted" means any form of electronic, verbal, or written communication sent to the Licensor or its representatives, including but not limited to communication on electronic mailing lists, source code control systems, and issue tracking systems that are managed by, or on behalf of, the Licensor for the purpose of discussing and improving the Work, but excluding communication that is conspicuously marked or otherwise designated in writing by the copyright owner as "Not a Contribution." - -"Contributor" shall mean Licensor and any individual or Legal Entity on behalf of whom a Contribution has been received by Licensor and subsequently incorporated within the Work. - -2. Grant of Copyright License. Subject to the terms and conditions of this License, each Contributor hereby grants to You a perpetual, worldwide, non-exclusive, no-charge, royalty-free, irrevocable copyright license to reproduce, prepare Derivative Works of, publicly display, publicly perform, sublicense, and distribute the Work and such Derivative Works in Source or Object form. - -3. Grant of Patent License. Subject to the terms and conditions of this License, each Contributor hereby grants to You a perpetual, worldwide, non-exclusive, no-charge, royalty-free, irrevocable (except as stated in this section) patent license to make, have made, use, offer to sell, sell, import, and otherwise transfer the Work, where such license applies only to those patent claims licensable by such Contributor that are necessarily infringed by their Contribution(s) alone or by combination of their Contribution(s) with the Work to which such Contribution(s) was submitted. If You institute patent litigation against any entity (including a cross-claim or counterclaim in a lawsuit) alleging that the Work or a Contribution incorporated within the Work constitutes direct or contributory patent infringement, then any patent licenses granted to You under this License for that Work shall terminate as of the date such litigation is filed. - -4. Redistribution. You may reproduce and distribute copies of the Work or Derivative Works thereof in any medium, with or without modifications, and in Source or Object form, provided that You meet the following conditions: - -You must give any other recipients of the Work or Derivative Works a copy of this License; and -You must cause any modified files to carry prominent notices stating that You changed the files; and -You must retain, in the Source form of any Derivative Works that You distribute, all copyright, patent, trademark, and attribution notices from the Source form of the Work, excluding those notices that do not pertain to any part of the Derivative Works; and -If the Work includes a "NOTICE" text file as part of its distribution, then any Derivative Works that You distribute must include a readable copy of the attribution notices contained within such NOTICE file, excluding those notices that do not pertain to any part of the Derivative Works, in at least one of the following places: within a NOTICE text file distributed as part of the Derivative Works; within the Source form or documentation, if provided along with the Derivative Works; or, within a display generated by the Derivative Works, if and wherever such third-party notices normally appear. The contents of the NOTICE file are for informational purposes only and do not modify the License. You may add Your own attribution notices within Derivative Works that You distribute, alongside or as an addendum to the NOTICE text from the Work, provided that such additional attribution notices cannot be construed as modifying the License. - -You may add Your own copyright statement to Your modifications and may provide additional or different license terms and conditions for use, reproduction, or distribution of Your modifications, or for any such Derivative Works as a whole, provided Your use, reproduction, and distribution of the Work otherwise complies with the conditions stated in this License. -5. Submission of Contributions. Unless You explicitly state otherwise, any Contribution intentionally submitted for inclusion in the Work by You to the Licensor shall be under the terms and conditions of this License, without any additional terms or conditions. Notwithstanding the above, nothing herein shall supersede or modify the terms of any separate license agreement you may have executed with Licensor regarding such Contributions. - -6. Trademarks. This License does not grant permission to use the trade names, trademarks, service marks, or product names of the Licensor, except as required for reasonable and customary use in describing the origin of the Work and reproducing the content of the NOTICE file. - -7. Disclaimer of Warranty. Unless required by applicable law or agreed to in writing, Licensor provides the Work (and each Contributor provides its Contributions) on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied, including, without limitation, any warranties or conditions of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A PARTICULAR PURPOSE. You are solely responsible for determining the appropriateness of using or redistributing the Work and assume any risks associated with Your exercise of permissions under this License. - -8. Limitation of Liability. In no event and under no legal theory, whether in tort (including negligence), contract, or otherwise, unless required by applicable law (such as deliberate and grossly negligent acts) or agreed to in writing, shall any Contributor be liable to You for damages, including any direct, indirect, special, incidental, or consequential damages of any character arising as a result of this License or out of the use or inability to use the Work (including but not limited to damages for loss of goodwill, work stoppage, computer failure or malfunction, or any and all other commercial damages or losses), even if such Contributor has been advised of the possibility of such damages. - -9. Accepting Warranty or Additional Liability. While redistributing the Work or Derivative Works thereof, You may choose to offer, and charge a fee for, acceptance of support, warranty, indemnity, or other liability obligations and/or rights consistent with this License. However, in accepting such obligations, You may act only on Your own behalf and on Your sole responsibility, not on behalf of any other Contributor, and only if You agree to indemnify, defend, and hold each Contributor harmless for any liability incurred by, or claims asserted against, such Contributor by reason of your accepting any such warranty or additional liability. - -END OF TERMS AND CONDITIONS diff --git a/modules/contrib/cyber_bridge/README.md b/modules/contrib/cyber_bridge/README.md deleted file mode 100644 index d98439278f6..00000000000 --- a/modules/contrib/cyber_bridge/README.md +++ /dev/null @@ -1,50 +0,0 @@ -# Apollo Cyber bridge for the `master` branch - -This is bridge that exposes custom TCP socket for accepting and transmitting Cyber messages. - -# Building - -Run the build from the `/apollo` directory inside docker. - -``` -bazel build //modules/contrib/cyber_bridge -``` - -# Running - -From the `/apollo` directory, execute: - -``` -./bazel-bin/module/contrib/cyber_bridge/cyber_bridge -``` - -For extra logging: - -``` -GLOG_v=4 GLOG_logtostderr=1 ./bazel-bin/modules/contrib/cyber_bridge/cyber_bridge -``` - -Add extra `-port 9090` argument for custom port (9090 is default). - -# Example - -In one terminal launch `cyber_bridge`: - -``` -./bazel-bin/modules/contrib/cyber_bridge/cyber_bridge -``` - -In another terminal launch example talker: - -``` -./bazel-bin/cyber/python/cyber_py3/examples/talker -``` - -In one more terminal launch example listener: - -``` -./bazel-bin/cyber/python/cyber_py3/examples/listener -``` - -Now you should observe talker and listener sending & receiving message with incrementing integer. - diff --git a/modules/contrib/cyber_bridge/bridge.cc b/modules/contrib/cyber_bridge/bridge.cc deleted file mode 100644 index a07f314ad1a..00000000000 --- a/modules/contrib/cyber_bridge/bridge.cc +++ /dev/null @@ -1,34 +0,0 @@ -/** - * Copyright (c) 2019 LG Electronics, Inc. - * - * This software contains code licensed as described in LICENSE. - * - */ - -#include - -#include - -#include "cyber/common/log.h" -#include "cyber/init.h" -#include "modules/contrib/cyber_bridge/node.h" -#include "modules/contrib/cyber_bridge/server.h" - -// bazel build //cyber/bridge:cyber_bridge -// GLOG_v=4 GLOG_logtostderr=1 -// ./bazel-bin/modules/contrib/cyber_bridge/cyber_bridge - -int main(int argc, char* argv[]) { - google::ParseCommandLineFlags(&argc, &argv, true); - - apollo::cyber::Init(argv[0]); - - { - Node node; - - auto server = std::make_shared(&node); - server->run(); - } - - apollo::cyber::Clear(); -} diff --git a/modules/contrib/cyber_bridge/client.cc b/modules/contrib/cyber_bridge/client.cc deleted file mode 100644 index 73d260da5df..00000000000 --- a/modules/contrib/cyber_bridge/client.cc +++ /dev/null @@ -1,313 +0,0 @@ -/** - * Copyright (c) 2019 LG Electronics, Inc. - * - * This software contains code licensed as described in LICENSE. - * - */ -#include "modules/contrib/cyber_bridge/client.h" - -#include -#include -#include -#include - -#include "boost/bind.hpp" - -#include "cyber/common/log.h" -#include "cyber/message/protobuf_factory.h" -#include "modules/contrib/cyber_bridge/clients.h" -#include "modules/contrib/cyber_bridge/node.h" - -enum { - OP_REGISTER_DESC = 1, - OP_ADD_READER = 2, - OP_ADD_WRITER = 3, - OP_PUBLISH = 4, -}; - -Client::Client(Node* node, Clients* clients, boost::asio::ip::tcp::socket s) - : node(*node), clients(*clients), socket(std::move(s)) { - auto endpoint = socket.remote_endpoint(); - AINFO << "Client [" << endpoint.address() << ":" << endpoint.port() - << "] connected"; -} - -Client::~Client() {} - -void Client::start() { - socket.async_read_some( - boost::asio::buffer(temp, sizeof(temp)), - boost::bind(&Client::handle_read, shared_from_this(), - boost::asio::placeholders::error, - boost::asio::placeholders::bytes_transferred)); -} - -void Client::stop() { socket.close(); } - -void Client::handle_read(const boost::system::error_code& ec, - std::size_t size) { - if (!ec) { - ADEBUG << "Received " << size << " bytes"; - buffer.insert(buffer.end(), temp, temp + size); - - size_t size = buffer.size(); - - while (size >= sizeof(uint8_t)) { - if (buffer[0] == OP_REGISTER_DESC) { - handle_register_desc(); - } else if (buffer[0] == OP_ADD_READER) { - handle_add_reader(); - } else if (buffer[0] == OP_ADD_WRITER) { - handle_add_writer(); - } else if (buffer[0] == OP_PUBLISH) { - handle_publish(); - } else { - AERROR << "Unknown operation received from client (" - << uint32_t(buffer[0]) << "), disconnecting client"; - clients.stop(shared_from_this()); - return; - } - - if (size == buffer.size()) { - break; - } - size = buffer.size(); - } - - start(); - return; - } - - if (ec == boost::asio::error::eof) { - // remote side closed connection - clients.stop(shared_from_this()); - node.remove(shared_from_this()); - return; - } - - if (ec != boost::asio::error::operation_aborted) { - AERROR << "Client read failed, disconnecting" << ec; - clients.stop(shared_from_this()); - node.remove(shared_from_this()); - return; - } -} - -void Client::handle_write(const boost::system::error_code& ec) { - if (ec) { - if (ec != boost::asio::error::operation_aborted) { - AERROR << "Client write failed, disconnecting" << ec; - clients.stop(shared_from_this()); - node.remove(shared_from_this()); - } - return; - } - - std::lock_guard lock(publish_mutex); - writing.clear(); - if (!pending.empty()) { - writing.swap(pending); - boost::asio::async_write( - socket, boost::asio::buffer(writing.data(), writing.size()), - boost::bind(&Client::handle_write, shared_from_this(), - boost::asio::placeholders::error)); - } -} - -// [1] [count] [string] ... [string] -void Client::handle_register_desc() { - if (sizeof(uint8_t) + sizeof(uint32_t) > buffer.size()) { - ADEBUG << "handle_register_desc too short"; - return; - } - - uint32_t count = get32le(1); - - std::vector desc; - - bool complete = true; - size_t offset = sizeof(uint8_t) + sizeof(uint32_t); - for (uint32_t i = 0; i < count; i++) { - if (offset + sizeof(uint32_t) > buffer.size()) { - ADEBUG << "handle_register_desc too short"; - complete = false; - break; - } - - uint32_t size = get32le(offset); - offset += sizeof(uint32_t); - - if (offset + size > buffer.size()) { - ADEBUG << "handle_register_desc too short"; - complete = false; - break; - } - - desc.push_back(std::string(reinterpret_cast(&buffer[offset]), size)); - offset += size; - } - - if (complete) { - ADEBUG << "OP_REGISTER_DESC, count = " << count; - - auto factory = apollo::cyber::message::ProtobufFactory::Instance(); - for (const auto& s : desc) { - factory->RegisterPythonMessage(s); - } - - buffer.erase(buffer.begin(), buffer.begin() + offset); - } -} - -// [2] [channel] [type] -void Client::handle_add_reader() { - if (sizeof(uint8_t) + 2 * sizeof(uint32_t) > buffer.size()) { - ADEBUG << "handle_add_reader too short header"; - return; - } - - size_t offset = sizeof(uint8_t); - - uint32_t channel_length = get32le(offset); - offset += sizeof(uint32_t); - if (offset + channel_length > buffer.size()) { - ADEBUG << "handle_add_reader short1 " << offset + channel_length << " " - << buffer.size(); - return; - } - - std::string channel(reinterpret_cast(&buffer[offset]), channel_length); - offset += channel_length; - - uint32_t type_length = get32le(offset); - offset += sizeof(uint32_t); - if (offset + type_length > buffer.size()) { - ADEBUG << "handle_add_reader short2 " << offset + type_length << " " - << buffer.size(); - return; - } - - std::string type(reinterpret_cast(&buffer[offset]), type_length); - offset += type_length; - - ADEBUG << "OP_NEW_READER, channel = " << channel << ", type = " << type; - - node.add_reader(channel, type, shared_from_this()); - - buffer.erase(buffer.begin(), buffer.begin() + offset); -} - -// [3] [channel] [type] -void Client::handle_add_writer() { - if (sizeof(uint8_t) + 2 * sizeof(uint32_t) > buffer.size()) { - ADEBUG << "handle_new_writer too short header"; - return; - } - - size_t offset = sizeof(uint8_t); - - uint32_t channel_length = get32le(offset); - offset += sizeof(uint32_t); - if (offset + channel_length > buffer.size()) { - ADEBUG << "handle_new_writer short1 " << offset + channel_length << " " - << buffer.size(); - return; - } - - std::string channel(reinterpret_cast(&buffer[offset]), channel_length); - offset += channel_length; - - uint32_t type_length = get32le(offset); - offset += sizeof(uint32_t); - if (offset + type_length > buffer.size()) { - ADEBUG << "handle_new_writer short2 " << offset + type_length << " " - << buffer.size(); - return; - } - - std::string type(reinterpret_cast(&buffer[offset]), type_length); - offset += type_length; - - ADEBUG << "OP_NEW_WRITER, channel = " << channel << ", type = " << type; - - node.add_writer(channel, type, shared_from_this()); - - buffer.erase(buffer.begin(), buffer.begin() + offset); -} - -// [4] [channel] [message] -void Client::handle_publish() { - if (sizeof(uint8_t) + 2 * sizeof(uint32_t) > buffer.size()) { - return; - } - - size_t offset = sizeof(uint8_t); - - uint32_t channel_length = get32le(offset); - offset += sizeof(uint32_t); - if (offset + channel_length > buffer.size()) { - return; - } - - std::string channel(reinterpret_cast(&buffer[offset]), channel_length); - offset += channel_length; - - uint32_t message_length = get32le(offset); - offset += sizeof(uint32_t); - if (offset + message_length > buffer.size()) { - return; - } - - std::string message(reinterpret_cast(&buffer[offset]), message_length); - offset += message_length; - - ADEBUG << "OP_PUBLISH, channel = " << channel; - - node.publish(channel, message); - - buffer.erase(buffer.begin(), buffer.begin() + offset); -} - -void fill_data(std::vector* data, const std::string& channel, - const std::string& msg) { - data->reserve(data->size() + sizeof(uint8_t) + sizeof(uint32_t) + - channel.size() + sizeof(uint32_t) + msg.size()); - - data->push_back(OP_PUBLISH); - - data->push_back(uint8_t(channel.size() >> 0)); - data->push_back(uint8_t(channel.size() >> 8)); - data->push_back(uint8_t(channel.size() >> 16)); - data->push_back(uint8_t(channel.size() >> 24)); - const uint8_t* channel_data = - reinterpret_cast(channel.data()); - data->insert(data->end(), channel_data, channel_data + channel.size()); - - data->push_back(uint8_t(msg.size() >> 0)); - data->push_back(uint8_t(msg.size() >> 8)); - data->push_back(uint8_t(msg.size() >> 16)); - data->push_back(uint8_t(msg.size() >> 24)); - const uint8_t* msg_data = reinterpret_cast(msg.data()); - data->insert(data->end(), msg_data, msg_data + msg.size()); -} - -void Client::publish(const std::string& channel, const std::string& msg) { - std::lock_guard lock(publish_mutex); - if (writing.empty()) { - fill_data(&writing, channel, msg); - boost::asio::async_write( - socket, boost::asio::buffer(writing.data(), writing.size()), - boost::bind(&Client::handle_write, shared_from_this(), - boost::asio::placeholders::error)); - } else if (pending.size() < MAX_PENDING_SIZE) { - fill_data(&pending, channel, msg); - } else { - // If pending size is larger than MAX_PENDING_SIZE, discard the message. - AERROR << "Pending size too large. Discard message."; - } -} - -uint32_t Client::get32le(size_t offset) const { - return buffer[offset + 0] | (buffer[offset + 1] << 8) | - (buffer[offset + 2] << 16) | (buffer[offset + 3] << 24); -} diff --git a/modules/contrib/cyber_bridge/client.h b/modules/contrib/cyber_bridge/client.h deleted file mode 100644 index 4885f380607..00000000000 --- a/modules/contrib/cyber_bridge/client.h +++ /dev/null @@ -1,50 +0,0 @@ -/** - * Copyright (c) 2019 LG Electronics, Inc. - * - * This software contains code licensed as described in LICENSE. - * - */ -#pragma once - -#include -#include -#include - -#include "boost/asio.hpp" - -class Clients; -class Node; - -class Client : public std::enable_shared_from_this { - public: - Client(Node* node, Clients* clients, boost::asio::ip::tcp::socket socket); - ~Client(); - - void start(); - void stop(); - - void publish(const std::string& channel, const std::string& msg); - - private: - Node& node; - Clients& clients; - - boost::asio::ip::tcp::socket socket; - - uint8_t temp[1024 * 1024]; - std::vector buffer; - std::vector writing; - std::vector pending; - std::mutex publish_mutex; - const uint MAX_PENDING_SIZE = 1073741824; // 1GB - - void handle_read(const boost::system::error_code& ec, std::size_t length); - void handle_write(const boost::system::error_code& ec); - - void handle_register_desc(); - void handle_add_writer(); - void handle_add_reader(); - void handle_publish(); - - uint32_t get32le(size_t offset) const; -}; diff --git a/modules/contrib/cyber_bridge/clients.cc b/modules/contrib/cyber_bridge/clients.cc deleted file mode 100644 index 83777725385..00000000000 --- a/modules/contrib/cyber_bridge/clients.cc +++ /dev/null @@ -1,32 +0,0 @@ -/** - * Copyright (c) 2019 LG Electronics, Inc. - * - * This software contains code licensed as described in LICENSE. - * - */ -#include "modules/contrib/cyber_bridge/clients.h" - -#include - -#include "modules/contrib/cyber_bridge/client.h" - -Clients::Clients() {} - -Clients::~Clients() {} - -void Clients::start(std::shared_ptr client) { - clients.insert(client); - client->start(); -} - -void Clients::stop(std::shared_ptr client) { - clients.erase(client); - client->stop(); -} - -void Clients::stop_all() { - for (auto& client : clients) { - client->stop(); - } - clients.clear(); -} diff --git a/modules/contrib/cyber_bridge/clients.h b/modules/contrib/cyber_bridge/clients.h deleted file mode 100644 index 088850c294c..00000000000 --- a/modules/contrib/cyber_bridge/clients.h +++ /dev/null @@ -1,27 +0,0 @@ -/** - * Copyright (c) 2019 LG Electronics, Inc. - * - * This software contains code licensed as described in LICENSE. - * - */ -#pragma once - -#include -#include - -#include "boost/asio.hpp" - -class Client; - -class Clients { - public: - Clients(); - ~Clients(); - - void start(std::shared_ptr client); - void stop(std::shared_ptr client); - void stop_all(); - - private: - std::unordered_set> clients; -}; diff --git a/modules/contrib/cyber_bridge/cyber-bridge.BUILD b/modules/contrib/cyber_bridge/cyber-bridge.BUILD deleted file mode 100644 index f80657c1c6b..00000000000 --- a/modules/contrib/cyber_bridge/cyber-bridge.BUILD +++ /dev/null @@ -1,11 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_library") - -cc_library( - name = "cyber_bridge", - includes = ["include"], - hdrs = glob(["include/**/*"]), - srcs = glob(["lib/**/*.so*"]), - include_prefix = "modules/cyber_bridge", - strip_include_prefix = "include", - visibility = ["//visibility:public"], -) \ No newline at end of file diff --git a/modules/contrib/cyber_bridge/cyberfile.xml b/modules/contrib/cyber_bridge/cyberfile.xml deleted file mode 100644 index 042e5b2a926..00000000000 --- a/modules/contrib/cyber_bridge/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - cyber-bridge - local - - This is bridge that exposes custom TCP socket for accepting and transmitting Cyber messages. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/contrib/cyber_bridge - - diff --git a/modules/contrib/cyber_bridge/node.cc b/modules/contrib/cyber_bridge/node.cc deleted file mode 100644 index 72cb89c21ee..00000000000 --- a/modules/contrib/cyber_bridge/node.cc +++ /dev/null @@ -1,133 +0,0 @@ -/** - * Copyright (c) 2019 LG Electronics, Inc. - * - * This software contains code licensed as described in LICENSE. - * - */ - -#include "modules/contrib/cyber_bridge/node.h" - -#include - -#include "cyber/common/log.h" -#include "cyber/cyber.h" -#include "cyber/message/py_message.h" -#include "cyber/node/node.h" -#include "cyber/node/reader.h" -#include "cyber/node/writer.h" -#include "modules/contrib/cyber_bridge/client.h" - -using apollo::cyber::message::PyMessageWrap; - -Node::Node() : node(apollo::cyber::CreateNode("bridge")) {} - -Node::~Node() {} - -void Node::remove(std::shared_ptr client) { - for (auto it = writers.begin(); it != writers.end(); /* empty */) { - if (it->second.clients.find(client) != it->second.clients.end()) { - ADEBUG << "Removing client writer"; - it->second.clients.erase(client); - if (it->second.clients.empty()) { - ADEBUG << "Removing Cyber writer"; - it = writers.erase(it); - } else { - it++; - } - } else { - it++; - } - } - - std::lock_guard lock(mutex); - - for (auto it = readers.begin(); it != readers.end(); /* empty */) { - if (it->second.clients.find(client) != it->second.clients.end()) { - ADEBUG << "Removing client reader"; - it->second.clients.erase(client); - if (it->second.clients.empty()) { - ADEBUG << "Removing Cyber reader"; - it = readers.erase(it); - } else { - it++; - } - } else { - it++; - } - } -} - -void Node::add_reader(const std::string& channel, const std::string& type, - std::shared_ptr client) { - auto rit = readers.find(channel); - if (rit != readers.end()) { - ADEBUG << "Adding client to existing " << channel; - rit->second.clients.insert(client); - return; - } - - auto cb = [this, channel](const std::shared_ptr& msg) { - ADEBUG << "New message on " << channel; - - const std::string& data = msg->data(); - - std::lock_guard lock(mutex); - - auto it = readers.find(channel); - if (it != readers.end()) { - for (auto client : it->second.clients) { - client->publish(channel, data); - } - } - }; - - ADEBUG << "Adding new reader to " << channel; - Reader reader; - reader.reader = node->CreateReader(channel, cb); - reader.clients.insert(client); - - std::lock_guard lock(mutex); - readers.insert(std::make_pair(channel, reader)); -} - -void Node::add_writer(const std::string& channel, const std::string& type, - std::shared_ptr client) { - auto wit = writers.find(channel); - if (wit != writers.end()) { - wit->second.clients.insert(client); - return; - } - - Writer writer; - writer.type = type; - - apollo::cyber::message::ProtobufFactory::Instance()->GetDescriptorString( - type, &writer.desc); - if (writer.desc.empty()) { - AWARN << "Cannot find proto descriptor for message type " << type; - return; - } - - apollo::cyber::proto::RoleAttributes role; - role.set_channel_name(channel); - role.set_message_type(type); - role.set_proto_desc(writer.desc); - - auto qos_profile = role.mutable_qos_profile(); - qos_profile->set_depth(1); - writer.writer = node->CreateWriter(role); - writer.clients.insert(client); - - writers.insert(std::make_pair(channel, writer)); -} - -void Node::publish(const std::string& channel, const std::string& data) { - auto writer = writers.find(channel); - if (writer == writers.end()) { - AWARN << "No writer registered on channel " << channel; - return; - } - - auto message = std::make_shared(data, writer->second.type); - writer->second.writer->Write(message); -} diff --git a/modules/contrib/cyber_bridge/node.h b/modules/contrib/cyber_bridge/node.h deleted file mode 100644 index 5a383dffda4..00000000000 --- a/modules/contrib/cyber_bridge/node.h +++ /dev/null @@ -1,69 +0,0 @@ -/** - * Copyright (c) 2019 LG Electronics, Inc. - * - * This software contains code licensed as described in LICENSE. - * - */ -#pragma once - -#include -#include -#include -#include -#include - -namespace apollo { -namespace cyber { -class Node; -template -class Writer; -template -class Reader; - -namespace message { -class PyMessageWrap; -} -} // namespace cyber -} // namespace apollo - -class Client; - -class Node { - public: - Node(); - ~Node(); - - void remove(std::shared_ptr client); - - void add_reader(const std::string& channel, const std::string& type, - std::shared_ptr client); - void add_writer(const std::string& channel, const std::string& type, - std::shared_ptr client); - - void publish(const std::string& channel, const std::string& data); - - private: - std::unique_ptr node; - std::mutex mutex; - - struct Writer { - std::string desc; - std::string type; - std::shared_ptr< - apollo::cyber::Writer> - writer; - std::unordered_set> clients; - }; - - struct Reader { - std::shared_ptr< - apollo::cyber::Reader> - reader; - std::unordered_set> clients; - }; - - typedef std::unordered_map Writers; - typedef std::unordered_map Readers; - Writers writers; - Readers readers; -}; diff --git a/modules/contrib/cyber_bridge/server.cc b/modules/contrib/cyber_bridge/server.cc deleted file mode 100644 index eaa558c854d..00000000000 --- a/modules/contrib/cyber_bridge/server.cc +++ /dev/null @@ -1,74 +0,0 @@ -/** - * Copyright (c) 2019 LG Electronics, Inc. - * - * This software contains code licensed as described in LICENSE. - * - */ -#include "modules/contrib/cyber_bridge/server.h" - -#include - -#include -#include -#include -#include - -#include "boost/bind.hpp" -#include "cyber/common/log.h" -#include "gflags/gflags.h" -#include "modules/contrib/cyber_bridge/client.h" - -DEFINE_int32(port, 9090, "tcp listen port"); - -Server::Server(Node* node) - : node(*node), - signals(io), - endpoint(boost::asio::ip::tcp::v4(), (uint16_t)FLAGS_port), - acceptor(io, endpoint), - socket(io) { - signals.add(SIGTERM); - signals.add(SIGINT); -} - -Server::~Server() {} - -void Server::run() { - signals.async_wait(boost::bind(&Server::stop, shared_from_this(), - boost::asio::placeholders::error, - boost::asio::placeholders::signal_number)); - - begin_accept(); - - io.run(); -} - -void Server::stop(const boost::system::error_code& ec, int signal_number) { - if (ec) { - AERROR << "Error waiting on signals: " << ec.message(); - } else { - AINFO << "Signal " << signal_number << " received, stopping server"; - } - acceptor.close(); - clients.stop_all(); -} - -void Server::begin_accept() { - acceptor.async_accept(socket, - boost::bind(&Server::end_accept, shared_from_this(), - boost::asio::placeholders::error)); -} - -void Server::end_accept(const boost::system::error_code& ec) { - if (!acceptor.is_open()) { - return; - } - - if (ec) { - AERROR << "Error accepting connection: " << ec.message(); - } else { - auto client = std::make_shared(&node, &clients, std::move(socket)); - clients.start(client); - } - - begin_accept(); -} diff --git a/modules/contrib/cyber_bridge/server.h b/modules/contrib/cyber_bridge/server.h deleted file mode 100644 index 6f3e0797671..00000000000 --- a/modules/contrib/cyber_bridge/server.h +++ /dev/null @@ -1,38 +0,0 @@ -/** - * Copyright (c) 2019 LG Electronics, Inc. - * - * This software contains code licensed as described in LICENSE. - * - */ -#pragma once - -#include - -#include "boost/asio.hpp" -#include "modules/contrib/cyber_bridge/clients.h" - -class Node; - -class Server : public std::enable_shared_from_this { - public: - explicit Server(Node* node); - ~Server(); - - void run(); - - private: - Node& node; - Clients clients; - - boost::asio::io_service io; - boost::asio::signal_set signals; - - boost::asio::ip::tcp::endpoint endpoint; - boost::asio::ip::tcp::acceptor acceptor; - boost::asio::ip::tcp::socket socket; - - void stop(const boost::system::error_code& error, int signal_number); - - void begin_accept(); - void end_accept(const boost::system::error_code& ec); -}; diff --git a/modules/contrib/e2e/README.md b/modules/contrib/e2e/README.md deleted file mode 100644 index c0f21f11ac0..00000000000 --- a/modules/contrib/e2e/README.md +++ /dev/null @@ -1 +0,0 @@ -You can download the e2e (aka. End-To-End) module here [e2e-1.5.zip](https://github.com/ApolloAuto/apollo/releases/download/v1.5.0/e2e-1.5.zip) diff --git a/modules/contrib/elo/README.md b/modules/contrib/elo/README.md deleted file mode 100755 index 4fd61457d8f..00000000000 --- a/modules/contrib/elo/README.md +++ /dev/null @@ -1,156 +0,0 @@ -### Download - -You can download the elo (aka Ego Localization) module here [elo-1.5.zip](https://github.com/ApolloAuto/apollo/releases/download/v1.5.0/elo-1.5.zip) - -### 1. Introduction - -Baidu ego localization system is an accurate ego localization solution for self-driving. By combining sensor information, Global navigation satellite systems (GNSS), and Baidu HD Map into one system, Baidu ego localization system is able to offer a localization solution with high accuracy. - -GNSS positioning observes range measurements from orbiting GNSS satellites, while GNSS in general has some restrictions that it may not be available for high accuracy requirements of self-driving. Baidu ego localization system combines sensor information with HD Map and GNSS solution to provide high-accuracy localization solution. System extracts features from sensors and Baidu HD Map for feature matching. After feature matching, system is able to locate current vehicle in HD Map. Motion compensation is proposed to compensate current localization solution. - -![components of Baidu ego localization system](flowchart.jpg) - -The main components of Baidu ego localization system is introduced as follow: -* Sensors: include vision sensors (in-vehicle cameras, industrial camera CCDs and other image collecting sensors) and position sensors (include GPS, GLONASS, Beidou and other GNSS). -* HD Map: HD Map provides road information within specific area. -* Real-time location feature: Baidu ego localization system applies deep neural network architecture `ENet` (see: [ENet: A Deep Neural Network Architecture for Real-Time Semantic Segmentation](https://arxiv.org/abs/1606.02147)) to extract lane lines and mark features by sensor for feature matching. -* Pre-stored location feature: obtains lane lines and mark features provided by HD Map. -* Feature matching: Baidu ego localization system locates current ego vehicle in HD Map by feature matching. -* Motion compensation: compensates current frame and adjusts the matching result via historical information. - -### 2. Requirements: software - -#### a. External dependencies - -* Requirements for `cmake 2.8.7` or higher (see: [cmake installation instructions](https://cmake.org/Wiki/CMake)) - -* Requirements for `OpenCV 3.X` (see: [OpenCV installation instructions](http://docs.opencv.org/master/df/d65/tutorial_table_of_content_introduction.html)) - -* Recommended requirements for `Protobuf` (see: [github](https://github.com/google/protobuf)) - -* Recommended requirements for `CUDA` (see: [CUDA installation instructions](http://docs.nvidia.com/cuda/index.html#installation-guides)) - -* Recommended requirements for `Eigen 3` (see: [Eigen installation instructions](http://eigen.tuxfamily.org/dox/)) - -* Recommended requirements for `jsoncpp` (see: [github](https://github.com/open-source-parsers/jsoncpp)) - -#### b. Internal dependencies - -* Requirements for `modified Caffe` (`lib/libcaffe.so`) - -* Requirements for `HD Map database` (`config/hadmap/hadmap.db`) - -### 3. Requirements: hardware - -Deployed on NVIDIA Drive PX2 (PDK 4.1.4.0). - -### 4. Data format - -* Input file: - - Note that optimum solution from SPAN-CPT (`ground_truth_longitude` and `ground_truth_latitude`) are provided to make comparison with solution from Baidu ego localization system. - - ``` - image_name longitude latitude ground_truth_longitude ground_truth_latitude - ``` -* Config file: - - ``` - # effective image rectangle: top-left corner point, width and height of resulting cropped image in BGR format, pixel - top-left_corner_point_x top-left_corner_point_y width height - - # width and height of ENet input image, pixel - segmented_image_width segmented_image_height - - # camera parameters: principal point, focal length and rotation angle of camera related to vehicle coordinate system, pixel and radian - principal_point_x principal_point_y focal_length_x focal_length_y pitch yaw roll - - # center point of image, pixel - center_point_x center_point_y - - # ENet parameters file - enet_para_path - - # ENet structure file - enet_structure_path - - # camera parameters: translation of camera related to vehicle coordinate system, pixel - translation_x translation_y - - # database of HD Map - database_path - ``` - Sample config parameters - - ``` - 510 808 1410 1068 - 448 224 - 948.617 628.628 1918.64 1924.48 -3.9 0.6 0 - 960 604 - ../data/model/model_binary.caffemodel - ../data/model/net.prototxt - 0 150 - ../data/hadmap/hadmap.xml - ``` -* Output format: - - ``` - image_name - [+] Begin Localization - [-] End Localization, misc time: runtime #### - [INFO] GROUNDTRUTH (ground_truth_longitude, ground_truth_latitude) LOCALIZATION (localization_longitude, localization_latitude) - ``` - Sample output: - ``` - 20170628_000039131.jpg - [+] Begin Localization - [-] End Localization, misc time: 91.95475700ms #### - [INFO] GROUNDTRUTH (133.02665542, 25.40116628) LOCALIZATION (133.02666082, 25.40117062) - ``` - -### 5. Installation - -* Install and build dependencies in `2. Recommended requirements: software`, then do the following steps. - -* a. System software dependencies can be installed with: - - ```Shell - sudo apt-get install cmake libhdf5-dev liblmdb-dev libleveldb-dev libatlas-dev libatlas-base-dev libgflags-dev libgoogle-glog-dev libopencv-dev libmatio-dev libcurl4-openssl-dev - ``` - -* b. Find the `elo` in `modules`: - - We'll call the directory `elo` into `P_ROOT` - -* c. Compile and run localization: - - ```Shell - cd $P_ROOT - mkdir build - cd build - cmake .. - make - ./localization_test config_file input_file image_path - ``` - -### 6. Demo - -* Hardware description: - - image: SEKONIX SF3323, 30 Hz; - - GNSS: U-Blox M8, 8 Hz; - - SPAN-CPT: 10 Hz; - -* Test data path: - - [testdata.zip](http://data.apollo.auto) - - unzip testdata in /data folder. - -* To run the localization demo in testdata1: - - ```Shell - ./localization_test ../config/apollo_release.config ../data/testdata1/test_list.txt ../data/testdata1/image/ - ``` diff --git a/modules/contrib/elo/flowchart.jpg b/modules/contrib/elo/flowchart.jpg deleted file mode 100755 index 8daa84b1ea1..00000000000 Binary files a/modules/contrib/elo/flowchart.jpg and /dev/null differ diff --git a/modules/contrib/lgsvl_msgs/CHANGELOG.rst b/modules/contrib/lgsvl_msgs/CHANGELOG.rst deleted file mode 100644 index 087712ada66..00000000000 --- a/modules/contrib/lgsvl_msgs/CHANGELOG.rst +++ /dev/null @@ -1,12 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package lgsvl_msgs -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.0.1 (2018-12-18) ------------------- -* add changelog -* update initial version number -* add license -* add Ros package for ground truth messages -* initial commit -* Contributors: David Uhm diff --git a/modules/contrib/lgsvl_msgs/LICENSE b/modules/contrib/lgsvl_msgs/LICENSE deleted file mode 100644 index 7783de532a3..00000000000 --- a/modules/contrib/lgsvl_msgs/LICENSE +++ /dev/null @@ -1,53 +0,0 @@ -Apache License - -Version 2.0, January 2004 - -http://www.apache.org/licenses/ - -TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION - -1. Definitions. - -"License" shall mean the terms and conditions for use, reproduction, and distribution as defined by Sections 1 through 9 of this document. - -"Licensor" shall mean the copyright owner or entity authorized by the copyright owner that is granting the License. - -"Legal Entity" shall mean the union of the acting entity and all other entities that control, are controlled by, or are under common control with that entity. For the purposes of this definition, "control" means (i) the power, direct or indirect, to cause the direction or management of such entity, whether by contract or otherwise, or (ii) ownership of fifty percent (50%) or more of the outstanding shares, or (iii) beneficial ownership of such entity. - -"You" (or "Your") shall mean an individual or Legal Entity exercising permissions granted by this License. - -"Source" form shall mean the preferred form for making modifications, including but not limited to software source code, documentation source, and configuration files. - -"Object" form shall mean any form resulting from mechanical transformation or translation of a Source form, including but not limited to compiled object code, generated documentation, and conversions to other media types. - -"Work" shall mean the work of authorship, whether in Source or Object form, made available under the License, as indicated by a copyright notice that is included in or attached to the work (an example is provided in the Appendix below). - -"Derivative Works" shall mean any work, whether in Source or Object form, that is based on (or derived from) the Work and for which the editorial revisions, annotations, elaborations, or other modifications represent, as a whole, an original work of authorship. For the purposes of this License, Derivative Works shall not include works that remain separable from, or merely link (or bind by name) to the interfaces of, the Work and Derivative Works thereof. - -"Contribution" shall mean any work of authorship, including the original version of the Work and any modifications or additions to that Work or Derivative Works thereof, that is intentionally submitted to Licensor for inclusion in the Work by the copyright owner or by an individual or Legal Entity authorized to submit on behalf of the copyright owner. For the purposes of this definition, "submitted" means any form of electronic, verbal, or written communication sent to the Licensor or its representatives, including but not limited to communication on electronic mailing lists, source code control systems, and issue tracking systems that are managed by, or on behalf of, the Licensor for the purpose of discussing and improving the Work, but excluding communication that is conspicuously marked or otherwise designated in writing by the copyright owner as "Not a Contribution." - -"Contributor" shall mean Licensor and any individual or Legal Entity on behalf of whom a Contribution has been received by Licensor and subsequently incorporated within the Work. - -2. Grant of Copyright License. Subject to the terms and conditions of this License, each Contributor hereby grants to You a perpetual, worldwide, non-exclusive, no-charge, royalty-free, irrevocable copyright license to reproduce, prepare Derivative Works of, publicly display, publicly perform, sublicense, and distribute the Work and such Derivative Works in Source or Object form. - -3. Grant of Patent License. Subject to the terms and conditions of this License, each Contributor hereby grants to You a perpetual, worldwide, non-exclusive, no-charge, royalty-free, irrevocable (except as stated in this section) patent license to make, have made, use, offer to sell, sell, import, and otherwise transfer the Work, where such license applies only to those patent claims licensable by such Contributor that are necessarily infringed by their Contribution(s) alone or by combination of their Contribution(s) with the Work to which such Contribution(s) was submitted. If You institute patent litigation against any entity (including a cross-claim or counterclaim in a lawsuit) alleging that the Work or a Contribution incorporated within the Work constitutes direct or contributory patent infringement, then any patent licenses granted to You under this License for that Work shall terminate as of the date such litigation is filed. - -4. Redistribution. You may reproduce and distribute copies of the Work or Derivative Works thereof in any medium, with or without modifications, and in Source or Object form, provided that You meet the following conditions: - -You must give any other recipients of the Work or Derivative Works a copy of this License; and -You must cause any modified files to carry prominent notices stating that You changed the files; and -You must retain, in the Source form of any Derivative Works that You distribute, all copyright, patent, trademark, and attribution notices from the Source form of the Work, excluding those notices that do not pertain to any part of the Derivative Works; and -If the Work includes a "NOTICE" text file as part of its distribution, then any Derivative Works that You distribute must include a readable copy of the attribution notices contained within such NOTICE file, excluding those notices that do not pertain to any part of the Derivative Works, in at least one of the following places: within a NOTICE text file distributed as part of the Derivative Works; within the Source form or documentation, if provided along with the Derivative Works; or, within a display generated by the Derivative Works, if and wherever such third-party notices normally appear. The contents of the NOTICE file are for informational purposes only and do not modify the License. You may add Your own attribution notices within Derivative Works that You distribute, alongside or as an addendum to the NOTICE text from the Work, provided that such additional attribution notices cannot be construed as modifying the License. - -You may add Your own copyright statement to Your modifications and may provide additional or different license terms and conditions for use, reproduction, or distribution of Your modifications, or for any such Derivative Works as a whole, provided Your use, reproduction, and distribution of the Work otherwise complies with the conditions stated in this License. -5. Submission of Contributions. Unless You explicitly state otherwise, any Contribution intentionally submitted for inclusion in the Work by You to the Licensor shall be under the terms and conditions of this License, without any additional terms or conditions. Notwithstanding the above, nothing herein shall supersede or modify the terms of any separate license agreement you may have executed with Licensor regarding such Contributions. - -6. Trademarks. This License does not grant permission to use the trade names, trademarks, service marks, or product names of the Licensor, except as required for reasonable and customary use in describing the origin of the Work and reproducing the content of the NOTICE file. - -7. Disclaimer of Warranty. Unless required by applicable law or agreed to in writing, Licensor provides the Work (and each Contributor provides its Contributions) on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied, including, without limitation, any warranties or conditions of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A PARTICULAR PURPOSE. You are solely responsible for determining the appropriateness of using or redistributing the Work and assume any risks associated with Your exercise of permissions under this License. - -8. Limitation of Liability. In no event and under no legal theory, whether in tort (including negligence), contract, or otherwise, unless required by applicable law (such as deliberate and grossly negligent acts) or agreed to in writing, shall any Contributor be liable to You for damages, including any direct, indirect, special, incidental, or consequential damages of any character arising as a result of this License or out of the use or inability to use the Work (including but not limited to damages for loss of goodwill, work stoppage, computer failure or malfunction, or any and all other commercial damages or losses), even if such Contributor has been advised of the possibility of such damages. - -9. Accepting Warranty or Additional Liability. While redistributing the Work or Derivative Works thereof, You may choose to offer, and charge a fee for, acceptance of support, warranty, indemnity, or other liability obligations and/or rights consistent with this License. However, in accepting such obligations, You may act only on Your own behalf and on Your sole responsibility, not on behalf of any other Contributor, and only if You agree to indemnify, defend, and hold each Contributor harmless for any liability incurred by, or claims asserted against, such Contributor by reason of your accepting any such warranty or additional liability. - -END OF TERMS AND CONDITIONS diff --git a/modules/contrib/lgsvl_msgs/README.md b/modules/contrib/lgsvl_msgs/README.md deleted file mode 100644 index 2008b238940..00000000000 --- a/modules/contrib/lgsvl_msgs/README.md +++ /dev/null @@ -1,19 +0,0 @@ -# Protobuf Package lgsvl_msgs for LG SVL Automotive Simulator - -This repository contains protobuf message definitions for lgsvl_msgs to subscribe protobuf messages being published by LG SVL Automotive Simulator via cyber bridge. - - -```text - - - detection2d.proto # 2D detection including id, label, score, and 2D bounding box - - detection2darray.proto # A list of 2D detections - - detection3d.proto # 3D detection including id, label, score, and 3D bounding box - - detection3darray.proto # A list of 3D detections -``` - - -# Copyright and License - -Copyright (c) 2018 LG Electronics, Inc. - -This software contains code licensed as described in LICENSE. diff --git a/modules/contrib/lgsvl_msgs/proto/BUILD b/modules/contrib/lgsvl_msgs/proto/BUILD deleted file mode 100644 index 5d281bdaf98..00000000000 --- a/modules/contrib/lgsvl_msgs/proto/BUILD +++ /dev/null @@ -1,107 +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") - -package(default_visibility = ["//visibility:public"]) - -cc_proto_library( - name = "detection3d_cc_proto", - deps = [ - ":detection3d_proto", - ], -) - -proto_library( - name = "detection3d_proto", - srcs = ["detection3d.proto"], - deps = [ - "//modules/common_msgs/basic_msgs:header_proto", - "//modules/common_msgs/basic_msgs:geometry_proto", - ":detection2d_proto", - ], -) - -py_proto_library( - name = "detection3d_py_pb2", - deps = [ - ":detection3d_proto", - "//modules/common_msgs/basic_msgs:header_py_pb2", - "//modules/common_msgs/basic_msgs:geometry_py_pb2", - ":detection2d_py_pb2", - ], -) - -cc_proto_library( - name = "detection3darray_cc_proto", - deps = [ - ":detection3darray_proto", - ], -) - -proto_library( - name = "detection3darray_proto", - srcs = ["detection3darray.proto"], - deps = [ - "//modules/common_msgs/basic_msgs:header_proto", - ":detection3d_proto", - ], -) - -py_proto_library( - name = "detection3darray_py_pb2", - deps = [ - ":detection3darray_proto", - "//modules/common_msgs/basic_msgs:header_py_pb2", - ":detection3d_py_pb2", - ], -) - -cc_proto_library( - name = "detection2d_cc_proto", - deps = [ - ":detection2d_proto", - ], -) - -proto_library( - name = "detection2d_proto", - srcs = ["detection2d.proto"], - deps = [ - "//modules/common_msgs/basic_msgs:header_proto", - ], -) - -py_proto_library( - name = "detection2d_py_pb2", - deps = [ - ":detection2d_proto", - "//modules/common_msgs/basic_msgs:header_py_pb2", - ], -) - -cc_proto_library( - name = "detection2darray_cc_proto", - deps = [ - ":detection2darray_proto", - ], -) - -proto_library( - name = "detection2darray_proto", - srcs = ["detection2darray.proto"], - deps = [ - "//modules/common_msgs/basic_msgs:header_proto", - ":detection2d_proto", - ], -) - -py_proto_library( - name = "detection2darray_py_pb2", - deps = [ - ":detection2darray_proto", - "//modules/common_msgs/basic_msgs:header_py_pb2", - ":detection2d_py_pb2", - ], -) - diff --git a/modules/contrib/lgsvl_msgs/proto/detection2d.proto b/modules/contrib/lgsvl_msgs/proto/detection2d.proto deleted file mode 100644 index 6cbe784c7d5..00000000000 --- a/modules/contrib/lgsvl_msgs/proto/detection2d.proto +++ /dev/null @@ -1,31 +0,0 @@ -syntax = "proto3"; -import "modules/common_msgs/basic_msgs/header.proto"; - -package apollo.contrib.lgsvl_msgs; - -message BoundingBox2D { - float x = 1; - float y = 2; - float width = 3; - float height = 4; -} - -message Vector3 { - double x = 1; - double y = 2; - double z = 3; -} - -message Twist { - Vector3 linear = 1; - Vector3 angular = 2; -} - -message Detection2D { - apollo.common.Header header = 1; - uint32 id = 2; - string label = 3; - double score = 4; - BoundingBox2D bbox = 5; - Twist velocity = 6; -} diff --git a/modules/contrib/lgsvl_msgs/proto/detection2darray.proto b/modules/contrib/lgsvl_msgs/proto/detection2darray.proto deleted file mode 100644 index 9b24eb54b52..00000000000 --- a/modules/contrib/lgsvl_msgs/proto/detection2darray.proto +++ /dev/null @@ -1,10 +0,0 @@ -syntax = "proto3"; -import "modules/common_msgs/basic_msgs/header.proto"; -import "modules/contrib/lgsvl_msgs/proto/detection2d.proto"; - -package apollo.contrib.lgsvl_msgs; - -message Detection2DArray { - apollo.common.Header header = 1; - repeated Detection2D detections = 2; -} diff --git a/modules/contrib/lgsvl_msgs/proto/detection3d.proto b/modules/contrib/lgsvl_msgs/proto/detection3d.proto deleted file mode 100644 index f5750937734..00000000000 --- a/modules/contrib/lgsvl_msgs/proto/detection3d.proto +++ /dev/null @@ -1,25 +0,0 @@ -syntax = "proto3"; -import "modules/common_msgs/basic_msgs/header.proto"; -import "modules/common_msgs/basic_msgs/geometry.proto"; -import "modules/contrib/lgsvl_msgs/proto/detection2d.proto"; - -package apollo.contrib.lgsvl_msgs; - -message Pose { - apollo.common.Point3D position = 1; - apollo.common.Quaternion orientation = 2; -} - -message BoundingBox3D { - Pose position = 1; - Vector3 size = 2; -} - -message Detection3D { - apollo.common.Header header = 1; - uint32 id = 2; - string label = 3; - double score = 4; - BoundingBox3D bbox = 5; - Twist velocity = 6; -} diff --git a/modules/contrib/lgsvl_msgs/proto/detection3darray.proto b/modules/contrib/lgsvl_msgs/proto/detection3darray.proto deleted file mode 100644 index acbe2c7f7c6..00000000000 --- a/modules/contrib/lgsvl_msgs/proto/detection3darray.proto +++ /dev/null @@ -1,10 +0,0 @@ -syntax = "proto3"; -import "modules/common_msgs/basic_msgs/header.proto"; -import "modules/contrib/lgsvl_msgs/proto/detection3d.proto"; - -package apollo.contrib.lgsvl_msgs; - -message Detection3DArray { - apollo.common.Header header = 1; - repeated Detection3D detections = 2; -} diff --git a/modules/control/BUILD b/modules/control/BUILD index a3827ca407a..60755be21d0 100644 --- a/modules/control/BUILD +++ b/modules/control/BUILD @@ -65,7 +65,6 @@ install( data_dest = "control", data = [ ":runtime_data", - ":cyberfile.xml", "control.BUILD", ], targets = [ @@ -97,7 +96,7 @@ install( "//modules/control/proto:mpc_controller_conf_cc_proto", "//modules/control/proto:mrac_conf_cc_proto", "//modules/control/proto:pid_conf_cc_proto", - "//modules/control/proto:preprocessor_cc_proto", + "//modules/control/proto:preprocessor_cc_proto", ], ) diff --git a/modules/control/common/control_gflags.cc b/modules/control/common/control_gflags.cc index 2500d834026..79eb2d2eaea 100644 --- a/modules/control/common/control_gflags.cc +++ b/modules/control/common/control_gflags.cc @@ -117,6 +117,12 @@ DEFINE_bool( DEFINE_bool(use_control_submodules, false, "use control submodules instead of controller agent"); +DEFINE_bool(use_acceleration_lookup_limit, false, + "use acceleration lookup limit within vehicle max acceleration"); + DEFINE_bool( - use_acceleration_lookup_limit, false, - "use acceleration lookup limit within vehicle max acceleration for D-KIT"); + use_preview_reference_check, true, + "use preview refenence acceleration and speed for near the stop stage"); + +DEFINE_double(steer_cmd_interval, 20.0, + "Steer cmd interval of current and previous in percentage."); diff --git a/modules/control/common/control_gflags.h b/modules/control/common/control_gflags.h index e1d9fedff8a..2ecabf7ccc5 100644 --- a/modules/control/common/control_gflags.h +++ b/modules/control/common/control_gflags.h @@ -80,3 +80,7 @@ DECLARE_bool(enable_gear_drive_negative_speed_protection); DECLARE_bool(use_control_submodules); DECLARE_bool(use_acceleration_lookup_limit); + +DECLARE_bool(use_preview_reference_check); + +DECLARE_double(steer_cmd_interval); diff --git a/modules/control/controller/lon_controller.cc b/modules/control/controller/lon_controller.cc index 8b09cfb6a86..7970ceb513d 100644 --- a/modules/control/controller/lon_controller.cc +++ b/modules/control/controller/lon_controller.cc @@ -19,6 +19,7 @@ #include #include "absl/strings/str_cat.h" + #include "cyber/common/log.h" #include "cyber/time/clock.h" #include "cyber/time/time.h" @@ -276,39 +277,54 @@ Status LonController::ComputeControlCommand( double acceleration_cmd = acceleration_cmd_closeloop + debug->preview_acceleration_reference() + FLAGS_enable_slope_offset * debug->slope_offset_compensation(); - debug->set_is_full_stop(false); - GetPathRemain(debug); + // Check the steer command in reverse trajectory if the current steer target + // is larger than previous target, free the acceleration command, wait for + // the current steer target if ((trajectory_message_->trajectory_type() == apollo::planning::ADCTrajectory::UNKNOWN) && - std::abs(cmd->steering_target() - chassis->steering_percentage()) > 20) { + std::abs(cmd->steering_target() - chassis->steering_percentage()) > + FLAGS_steer_cmd_interval) { acceleration_cmd = 0; - ADEBUG << "Steering not reached"; - debug->set_is_full_stop(true); + ADEBUG << "Steer cmd interval is larger than " << FLAGS_steer_cmd_interval; speed_pid_controller_.Reset_integral(); station_pid_controller_.Reset_integral(); } + debug->set_is_full_stop(false); + GetPathRemain(debug); // At near-stop stage, replace the brake control command with the standstill // acceleration if the former is even softer than the latter - if (((trajectory_message_->trajectory_type() == - apollo::planning::ADCTrajectory::NORMAL) || - (trajectory_message_->trajectory_type() == - apollo::planning::ADCTrajectory::SPEED_FALLBACK)) && - ((std::fabs(debug->preview_acceleration_reference()) <= - control_conf_->max_acceleration_when_stopped() && + if ((trajectory_message_->trajectory_type() == + apollo::planning::ADCTrajectory::NORMAL) || + (trajectory_message_->trajectory_type() == + apollo::planning::ADCTrajectory::SPEED_FALLBACK) || + (trajectory_message_->trajectory_type() == + apollo::planning::ADCTrajectory::UNKNOWN)) { + if (FLAGS_use_preview_reference_check && + (std::fabs(debug->preview_acceleration_reference()) <= + control_conf_->max_acceleration_when_stopped()) && std::fabs(debug->preview_speed_reference()) <= - vehicle_param_.max_abs_speed_when_stopped()) || - std::abs(debug->path_remain()) < - control_conf_->max_path_remain_when_stopped())) { + vehicle_param_.max_abs_speed_when_stopped()) { + debug->set_is_full_stop(true); + ADEBUG << "Into full stop within preview acc and reference speed, " + << "is_full_stop is " << debug->is_full_stop(); + } + if (std::abs(debug->path_remain()) < + control_conf_->max_path_remain_when_stopped()) { + debug->set_is_full_stop(true); + ADEBUG << "Into full stop within path remain, " + << "is_full_stop is " << debug->is_full_stop(); + } + } + + if (debug->is_full_stop()) { acceleration_cmd = (chassis->gear_location() == canbus::Chassis::GEAR_REVERSE) ? std::max(acceleration_cmd, -lon_controller_conf.standstill_acceleration()) : std::min(acceleration_cmd, lon_controller_conf.standstill_acceleration()); - ADEBUG << "Stop location reached"; - debug->set_is_full_stop(true); speed_pid_controller_.Reset_integral(); station_pid_controller_.Reset_integral(); } @@ -543,7 +559,7 @@ void LonController::GetPathRemain(SimpleLongitudinalDebug *debug) { while (stop_index < trajectory_message_->trajectory_point_size()) { auto ¤t_trajectory_point = trajectory_message_->trajectory_point(stop_index); - if (current_trajectory_point.v() < kSpeedThreshold && + if (current_trajectory_point.v() > -kSpeedThreshold && current_trajectory_point.a() < kBackwardAccThreshold && current_trajectory_point.a() > 0.0) { break; @@ -551,6 +567,7 @@ void LonController::GetPathRemain(SimpleLongitudinalDebug *debug) { ++stop_index; } } + ADEBUG << "stop_index is, " << stop_index; if (stop_index == trajectory_message_->trajectory_point_size()) { --stop_index; if (fabs(trajectory_message_->trajectory_point(stop_index).v()) < diff --git a/modules/control/cyberfile.xml b/modules/control/cyberfile.xml deleted file mode 100644 index 9639f3dbdaf..00000000000 --- a/modules/control/cyberfile.xml +++ /dev/null @@ -1,35 +0,0 @@ - - control - local - - Based on the planning trajectory and the car's current status, the Control module uses different control - algorithms to generate a comfortable driving experience.The Control module can work both in normal and navigation modes. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/control - - cyber-dev - common-dev - localization-dev - common-msgs-dev - 3rd-gflags-dev - 3rd-gtest-dev - 3rd-eigen3-dev - 3rd-absl-dev - 3rd-osqp-dev - - bazel-extend-tools-dev - 3rd-rules-python-dev - 3rd-grpc-dev - 3rd-bazel-skylib-dev - 3rd-rules-proto-dev - 3rd-py-dev - - diff --git a/modules/data/BUILD b/modules/data/BUILD deleted file mode 100644 index 90c42c9b179..00000000000 --- a/modules/data/BUILD +++ /dev/null @@ -1,40 +0,0 @@ -load("//tools/install:install.bzl", "install", "install_files", "install_src_files") - -package(default_visibility = ["//visibility:public"]) - -# filegroup( -# name = "conf_data", -# srcs = glob([ -# "tools/smart_recorder/proto/*" -# ]), -# ) - -install( - name = "install", - runtime_dest = "data/bin", - # data_dest = "data/addition_data", - # data = [ - # ":conf_data" - # ], - targets = [ - "//modules/data/tools/smart_recorder:smart_recorder", - ], - deps = [ - "//modules/data/proto:py_pb_data", - "//modules/data/tools/smart_recorder/proto:py_pb_data_tools", - "//modules/data/tools/smart_recorder/conf:conf_data", - ":cyberfile_data" - ], -) - -install( - name = "cyberfile_data", - data = [ - ":cyberfile.xml" - ], - data_dest = "data" -) - -install_src_files( - name = "install_src" -) diff --git a/modules/data/cyberfile.xml b/modules/data/cyberfile.xml deleted file mode 100644 index 0c33acf92c2..00000000000 --- a/modules/data/cyberfile.xml +++ /dev/null @@ -1,22 +0,0 @@ - - apollo-data - local - - This module provides binary which tools of apollo may use. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - pure-binary - //modules/data - - cyber-dev - common-dev - dreamview-dev - 3rd-absl-dev - - \ No newline at end of file diff --git a/modules/data/proto/BUILD b/modules/data/proto/BUILD deleted file mode 100644 index 5c5a2ab8e2e..00000000000 --- a/modules/data/proto/BUILD +++ /dev/null @@ -1,66 +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 = "frame_cc_proto", - deps = [ - ":frame_proto", - ], -) - -proto_library( - name = "frame_proto", - srcs = ["frame.proto"], -) - -py_proto_library( - name = "frame_py_pb2", - deps = [ - ":frame_proto", - ], -) -cc_proto_library( - name = "static_info_cc_proto", - deps = [ - ":static_info_proto", - ], -) - -proto_library( - name = "static_info_proto", - srcs = ["static_info.proto"], - deps = [ - "//modules/canbus/proto:canbus_conf_proto", - "//modules/common_msgs/chassis_msgs:chassis_proto", - "//modules/common_msgs/config_msgs:vehicle_config_proto", - "//modules/control/proto:control_conf_proto", - "//modules/common_msgs/routing_msgs:routing_proto", - ], -) - -py_proto_library( - name = "static_info_py_pb2", - deps = [ - ":static_info_proto", - "//modules/canbus/proto:canbus_conf_py_pb2", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/config_msgs:vehicle_config_py_pb2", - "//modules/control/proto:control_conf_py_pb2", - "//modules/common_msgs/routing_msgs:routing_py_pb2", - ], -) - -install_files( - name = "py_pb_data", - dest = "data/python/modules/data/proto", - files = [ - "static_info_py_pb2", - "frame_py_pb2" - ] -) - diff --git a/modules/data/proto/frame.proto b/modules/data/proto/frame.proto deleted file mode 100644 index 4370157b7a5..00000000000 --- a/modules/data/proto/frame.proto +++ /dev/null @@ -1,75 +0,0 @@ -syntax = "proto2"; - -message Vector3 { - optional double x = 1; - optional double y = 2; - optional double z = 3; -} - -message Vector4 { - optional double x = 1; - optional double y = 2; - optional double z = 3; - optional double i = 4; - optional bool is_ground = 5 [default = false]; -} - -message Quaternion { - optional double x = 1; - optional double y = 2; - optional double z = 3; - optional double w = 4; -} - -message GPSPose { - optional double lat = 1; - optional double lon = 2; - optional double bearing = 3; - optional double x = 4; - optional double y = 5; - optional double z = 6; - optional double qw = 7; - optional double qx = 8; - optional double qy = 9; - optional double qz = 10; -} - -message CameraImage { - optional double timestamp = 1; - optional string image_url = 2; - optional Vector3 position = 3; - optional Quaternion heading = 4; - optional double fx = 5; - optional double fy = 6; - optional double cx = 7; - optional double cy = 8; - optional double skew = 9; - optional double k1 = 10; - optional double k2 = 11; - optional double k3 = 12; - optional double p1 = 13; - optional double p2 = 14; - optional string channel = 15; -} - -message RadarPoint { - enum RadarType { - FRONT = 1; - REAR = 2; - } - optional Vector3 position = 1; - optional Vector3 direction = 2; - optional RadarType type = 3; -} - -message Frame { - optional Vector3 device_position = 1; - optional Quaternion device_heading = 2; - optional GPSPose device_gps_pose = 3; - repeated Vector4 points = 4; - repeated RadarPoint radar_points = 5; - repeated CameraImage images = 6; - optional double timestamp = 7; - optional int32 frame_seq = 8; - optional string data_file = 9; -} diff --git a/modules/data/proto/static_info.proto b/modules/data/proto/static_info.proto deleted file mode 100644 index 4dcc977e2fc..00000000000 --- a/modules/data/proto/static_info.proto +++ /dev/null @@ -1,69 +0,0 @@ -syntax = "proto2"; - -package apollo.data; - -import "modules/canbus/proto/canbus_conf.proto"; -import "modules/common_msgs/chassis_msgs/chassis.proto"; -import "modules/common_msgs/config_msgs/vehicle_config.proto"; -import "modules/control/proto/control_conf.proto"; -import "modules/common_msgs/routing_msgs/routing.proto"; - -message VehicleInfo { - optional string name = 1; - enum Brand { - LINCOLN = 1; - FORD = 2; - LEXUS = 3; - } - optional Brand brand = 2; - enum Model { - // Lincoln model - MKZ = 1; - TRANSIT = 2; - RX450H = 3; - } - optional Model model = 3; - optional apollo.canbus.License license = 4 [deprecated = true]; - optional apollo.canbus.CanbusConf canbus_conf = 5; - optional apollo.common.VehicleConfig vehicle_config = 6; - optional apollo.control.ControlConf control_config = 7; -} - -message EnvironmentInfo { - optional string map_name = 1 [deprecated = true]; - optional float temperature = 2; // Temperature in degrees Celsius. - // TODO(xiaoxq): weather, rare condition, etc. -} - -message HardwareInfo { - // Entries of hardware config file path and its content. - map configs = 1; -} - -message SoftwareInfo { - optional string docker_image = 1 [deprecated = true]; - optional string commit_id = 2; - optional string mode = 3 [deprecated = true]; - // Entries of software config file path and its content. - map configs = 4; - optional apollo.routing.RoutingRequest latest_routing_request = 5; -} - -message UserInfo { - optional string entity = 1; // Company, university, organization, etc. - optional string driver = 2; - optional string co_driver = 3; -} - -message StaticInfo { - optional VehicleInfo vehicle = 1; - optional EnvironmentInfo environment = 2; - optional HardwareInfo hardware = 3; - optional SoftwareInfo software = 4; - optional UserInfo user = 5; -} - -message StaticInfoConf { - repeated string hardware_configs = 1; - repeated string software_configs = 2; -} diff --git a/modules/data/tools/smart_recorder/BUILD b/modules/data/tools/smart_recorder/BUILD deleted file mode 100644 index 733149c431b..00000000000 --- a/modules/data/tools/smart_recorder/BUILD +++ /dev/null @@ -1,177 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library") -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -cc_binary( - name = "smart_recorder", - srcs = ["smart_recorder.cc"], - linkstatic = True, - deps = [ - ":post_record_processor", - ":realtime_record_processor", - ":smart_recorder_gflags", - ], -) - -cc_library( - name = "post_record_processor", - srcs = ["post_record_processor.cc"], - hdrs = ["post_record_processor.h"], - deps = [ - ":channel_pool", - ":record_processor", - "//cyber", - ], -) - -cc_library( - name = "realtime_record_processor", - srcs = ["realtime_record_processor.cc"], - hdrs = ["realtime_record_processor.h"], - deps = [ - ":channel_pool", - ":record_processor", - "//cyber", - "//cyber/tools/cyber_recorder:recorder", - "//modules/common_msgs/monitor_msgs:smart_recorder_status_cc_proto", - "//modules/monitor/common:monitor_manager", - ], -) - -cc_library( - name = "record_processor", - srcs = ["record_processor.cc"], - hdrs = ["record_processor.h"], - deps = [ - ":bumper_crash_trigger", - ":drive_event_trigger", - ":emergency_mode_trigger", - ":hard_brake_trigger", - ":interval_pool", - ":regular_interval_trigger", - ":small_topics_trigger", - ":swerve_trigger", - "//cyber", - "//modules/common/util", - ], -) - -cc_library( - name = "smart_recorder_gflags", - srcs = ["smart_recorder_gflags.cc"], - hdrs = ["smart_recorder_gflags.h"], - deps = [ - "@com_github_gflags_gflags//:gflags", - ], -) - -cc_library( - name = "drive_event_trigger", - srcs = ["drive_event_trigger.cc"], - hdrs = ["drive_event_trigger.h"], - deps = [ - ":trigger_base", - "//modules/common/adapters:adapter_gflags", - "//modules/common_msgs/basic_msgs:drive_event_cc_proto", - ], -) - -cc_library( - name = "emergency_mode_trigger", - srcs = ["emergency_mode_trigger.cc"], - hdrs = ["emergency_mode_trigger.h"], - deps = [ - ":trigger_base", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/common/adapters:adapter_gflags", - "//modules/common_msgs/control_msgs:control_cmd_cc_proto", - ], -) - -cc_library( - name = "bumper_crash_trigger", - srcs = ["bumper_crash_trigger.cc"], - hdrs = ["bumper_crash_trigger.h"], - deps = [ - ":trigger_base", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/common/adapters:adapter_gflags", - ], -) - -cc_library( - name = "hard_brake_trigger", - srcs = ["hard_brake_trigger.cc"], - hdrs = ["hard_brake_trigger.h"], - deps = [ - ":trigger_base", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/common/adapters:adapter_gflags", - "//modules/common_msgs/control_msgs:control_cmd_cc_proto", - ], -) - -cc_library( - name = "small_topics_trigger", - srcs = ["small_topics_trigger.cc"], - hdrs = ["small_topics_trigger.h"], - deps = [ - ":channel_pool", - ":trigger_base", - ], -) - -cc_library( - name = "swerve_trigger", - srcs = ["swerve_trigger.cc"], - hdrs = ["swerve_trigger.h"], - deps = [ - ":trigger_base", - "//modules/common_msgs/chassis_msgs:chassis_cc_proto", - "//modules/common/adapters:adapter_gflags", - "//modules/common_msgs/control_msgs:control_cmd_cc_proto", - ], -) - -cc_library( - name = "regular_interval_trigger", - srcs = ["regular_interval_trigger.cc"], - hdrs = ["regular_interval_trigger.h"], - deps = [ - ":trigger_base", - ], -) - -cc_library( - name = "trigger_base", - srcs = ["trigger_base.cc"], - hdrs = ["trigger_base.h"], - deps = [ - ":interval_pool", - "//cyber", - "//modules/data/tools/smart_recorder/proto:smart_recorder_triggers_cc_proto", - ], -) - -cc_library( - name = "interval_pool", - srcs = ["interval_pool.cc"], - hdrs = ["interval_pool.h"], - deps = [ - "//cyber", - "@com_google_absl//:absl", - ], -) - -cc_library( - name = "channel_pool", - srcs = ["channel_pool.cc"], - hdrs = ["channel_pool.h"], - deps = [ - "//cyber", - "//modules/common/adapters:adapter_gflags", - ], -) - -cpplint() diff --git a/modules/data/tools/smart_recorder/README.md b/modules/data/tools/smart_recorder/README.md deleted file mode 100644 index fee373cecd4..00000000000 --- a/modules/data/tools/smart_recorder/README.md +++ /dev/null @@ -1,20 +0,0 @@ -# Smart Recorder - -## Introduction -Smart Recorder is targeting to reduce the recording data size. Instead of recording all the topics all the time, it selectively records by the following way. - -1. All the small topics all the time. These include "/apollo/localization/pose", "/apollo/canbus/chassis" and so on, which are samll in size. -2. Large topics only in specified scenarios. These include sensor data include all "PointCloud" and "Camera" topics, which are large in size. The specific scenarios are configurable, as well as the time range for recording when the specified scenario occurs. - - -## How to use - -1. Build apollo -2. python3 /apollo/scripts/record_message.py --help - - -## How to add new scenarios - -1. Configure the new scenario in conf/smart_recorder_config.pb.txt, including time range, name, description and etc. -2. Add new class inherit from base class "TriggerBase", and implement interface "Pull" -3. Add the instance of the new class into triggers pool inside function "ProcessRecord::InitTriggers" \ No newline at end of file diff --git a/modules/data/tools/smart_recorder/bumper_crash_trigger.cc b/modules/data/tools/smart_recorder/bumper_crash_trigger.cc deleted file mode 100644 index 81b7ced68a2..00000000000 --- a/modules/data/tools/smart_recorder/bumper_crash_trigger.cc +++ /dev/null @@ -1,66 +0,0 @@ -/****************************************************************************** - * Copyright 2022 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/data/tools/smart_recorder/bumper_crash_trigger.h" - -#include "cyber/common/log.h" -#include "modules/common/adapters/adapter_gflags.h" - -namespace apollo { -namespace data { - -using apollo::canbus::Chassis; - -BumperCrashTrigger::BumperCrashTrigger() - : previous_check_event_trigger_(false) { - trigger_name_ = "BumperCrashTrigger"; -} - -void BumperCrashTrigger::Pull(const cyber::record::RecordMessage& msg) { - if (!trigger_obj_->enabled()) { - return; - } - if (msg.channel_name == FLAGS_chassis_topic) { - apollo::canbus::Chassis chassis_msg; - chassis_msg.ParseFromString(msg.content); - bool is_front_bumper_trigger = false; - bool is_back_bumper_trigger = false; - - if (chassis_msg.has_front_bumper_event()) { - if (chassis_msg.front_bumper_event() == canbus::Chassis::BUMPER_PRESSED) { - is_front_bumper_trigger = true; - } - } - if (chassis_msg.has_back_bumper_event()) { - if (chassis_msg.back_bumper_event() == canbus::Chassis::BUMPER_PRESSED) { - is_back_bumper_trigger = true; - } - } - bool check_event_trigger - = is_front_bumper_trigger || is_back_bumper_trigger; - - if (check_event_trigger && (!previous_check_event_trigger_)) { - AINFO << "Chassis has crash event."; - AINFO << "crash bumper trigger is pulled: " << msg.time << " - " - << msg.channel_name; - TriggerIt(msg.time); - } - previous_check_event_trigger_ = check_event_trigger; - } -} - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/bumper_crash_trigger.h b/modules/data/tools/smart_recorder/bumper_crash_trigger.h deleted file mode 100644 index b400cdc45d4..00000000000 --- a/modules/data/tools/smart_recorder/bumper_crash_trigger.h +++ /dev/null @@ -1,46 +0,0 @@ -/****************************************************************************** - * Copyright 2022 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 "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/data/tools/smart_recorder/proto/smart_recorder_triggers.pb.h" -#include "modules/data/tools/smart_recorder/trigger_base.h" - -namespace apollo { -namespace data { - -/** - * @class BumperCrashTrigger - * @brief BumperCrash trigger that fires when emergency mode is engaged - */ -class BumperCrashTrigger : public TriggerBase { - public: - BumperCrashTrigger(); - - void Pull(const cyber::record::RecordMessage& msg) override; - bool ShouldRestore(const cyber::record::RecordMessage& msg) const override { - return false; - }; - - virtual ~BumperCrashTrigger() = default; - - private: - bool previous_check_event_trigger_; -}; - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/channel_pool.cc b/modules/data/tools/smart_recorder/channel_pool.cc deleted file mode 100644 index 5878a186ed0..00000000000 --- a/modules/data/tools/smart_recorder/channel_pool.cc +++ /dev/null @@ -1,98 +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/data/tools/smart_recorder/channel_pool.h" - -#include - -#include "modules/common/adapters/adapter_gflags.h" - -namespace apollo { -namespace data { - -ChannelPool::ChannelPool() { - small_channels_ = {FLAGS_chassis_topic, - FLAGS_chassis_detail_topic, - FLAGS_control_command_topic, - FLAGS_pad_topic, - FLAGS_drive_event_topic, - FLAGS_guardian_topic, - FLAGS_hmi_status_topic, - FLAGS_localization_topic, - FLAGS_localization_gnss_topic, - FLAGS_localization_lidar_topic, - FLAGS_localization_msf_status, - FLAGS_monitor_topic, - FLAGS_system_status_topic, - FLAGS_navigation_topic, - FLAGS_perception_obstacle_topic, - FLAGS_traffic_light_detection_topic, - FLAGS_planning_trajectory_topic, - FLAGS_prediction_topic, - FLAGS_relative_map_topic, - FLAGS_routing_request_topic, - FLAGS_routing_response_topic, - FLAGS_routing_response_history_topic, - FLAGS_gnss_best_pose_topic, - FLAGS_imu_topic, - FLAGS_gnss_status_topic, - FLAGS_raw_imu_topic, - FLAGS_ins_stat_topic, - FLAGS_gps_topic, - FLAGS_gnss_raw_data_topic, - FLAGS_gnss_rtk_eph_topic, - FLAGS_gnss_rtk_obs_topic, - FLAGS_heading_topic, - FLAGS_tf_topic, - FLAGS_tf_static_topic, - FLAGS_recorder_status_topic, - FLAGS_latency_recording_topic, - FLAGS_latency_reporting_topic}; - large_channels_ = {FLAGS_camera_front_12mm_compressed_topic, - FLAGS_camera_front_6mm_compressed_topic, - FLAGS_camera_left_fisheye_compressed_topic, - FLAGS_camera_right_fisheye_compressed_topic, - FLAGS_camera_rear_6mm_compressed_topic, - FLAGS_camera_front_12mm_video_compressed_topic, - FLAGS_camera_front_6mm_video_compressed_topic, - FLAGS_camera_left_fisheye_video_compressed_topic, - FLAGS_camera_right_fisheye_video_compressed_topic, - FLAGS_camera_rear_6mm_video_compressed_topic, - FLAGS_front_radar_topic, - FLAGS_rear_radar_topic, - FLAGS_pointcloud_16_topic, - FLAGS_pointcloud_16_raw_topic, - FLAGS_pointcloud_16_front_left_raw_topic, - FLAGS_pointcloud_16_front_right_raw_topic, - FLAGS_lidar_16_front_center_topic, - FLAGS_lidar_16_front_up_topic, - FLAGS_lidar_16_rear_left_topic, - FLAGS_lidar_16_rear_right_topic, - FLAGS_lidar_16_fusion_topic, - FLAGS_lidar_16_fusion_compensator_topic, - FLAGS_pointcloud_64_topic, - FLAGS_lidar_128_topic, - FLAGS_pointcloud_128_topic, - FLAGS_mobileye_topic, - FLAGS_conti_radar_topic, - FLAGS_delphi_esr_topic}; - std::set_union(std::begin(small_channels_), std::end(small_channels_), - std::begin(large_channels_), std::end(large_channels_), - std::inserter(all_channels_, std::begin(all_channels_))); -} - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/channel_pool.h b/modules/data/tools/smart_recorder/channel_pool.h deleted file mode 100644 index 74685f711b1..00000000000 --- a/modules/data/tools/smart_recorder/channel_pool.h +++ /dev/null @@ -1,47 +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 "cyber/common/macros.h" - -namespace apollo { -namespace data { - -/** - * @class ChannelPool - * @brief Provides helper functions to offer different channels - */ -class ChannelPool { - public: - // Getters - const std::set& GetSmallChannels() { return small_channels_; } - const std::set& GetLargeChannels() { return large_channels_; } - const std::set& GetAllChannels() { return all_channels_; } - - private: - std::set small_channels_; - std::set large_channels_; - std::set all_channels_; - - DECLARE_SINGLETON(ChannelPool) -}; - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/conf/BUILD b/modules/data/tools/smart_recorder/conf/BUILD deleted file mode 100644 index bb08f8eddbf..00000000000 --- a/modules/data/tools/smart_recorder/conf/BUILD +++ /dev/null @@ -1,12 +0,0 @@ -load("//tools/install:install.bzl", "install", "install_files", "install_src_files") - -package(default_visibility = ["//visibility:public"]) - - -install( - name = "conf_data", - data = [ - ":smart_recorder_config.pb.txt" - ], - data_dest = "data/addition_data/tools/smart_recorder/conf" -) \ No newline at end of file diff --git a/modules/data/tools/smart_recorder/conf/smart_recorder_config.pb.txt b/modules/data/tools/smart_recorder/conf/smart_recorder_config.pb.txt deleted file mode 100644 index b276e3be6b8..00000000000 --- a/modules/data/tools/smart_recorder/conf/smart_recorder_config.pb.txt +++ /dev/null @@ -1,64 +0,0 @@ -segment_setting { - size_segment: 1024 - time_segment: 60 -} -max_backward_time: 100 -min_restore_chunk: 10 -trigger_log_file_path: "/apollo/data/smart_recorder/smart_recorder_triggers" -reused_record_num: 7 - -triggers { - trigger_name: "DriveEventTrigger" - enabled: false - backward_time: 30.0 - forward_time: 5.0 - description: "triggered by DriveEvent messages" -} - -triggers { - trigger_name: "EmergencyModeTrigger" - enabled: true - backward_time: 25.0 - forward_time: 10.0 - description: "triggered when mode changes from auto to driver engagement" -} - -triggers { - trigger_name: "HardBrakeTrigger" - enabled: false - backward_time: 25.0 - forward_time: 10.0 - description: "triggered when hard brake happened" -} - -triggers { - trigger_name: "SmallTopicsTrigger" - enabled: false - backward_time: 0 - forward_time: 0 - description: "record the messages from topics that are small in size" -} - -triggers { - trigger_name: "RegularIntervalTrigger" - enabled: false - backward_time: 15 - forward_time: 15 - description: "regularly triggered every certain time interval" -} - -triggers { - trigger_name: "SwerveTrigger" - enabled: false - backward_time: 15 - forward_time: 15 - description: "triggered when swerve happened" -} - -triggers { - trigger_name: "BumperCrashTrigger" - enabled: true - backward_time: 60.0 - forward_time: 30.0 - description: "triggered when bumper was pressed by car crashed happened" -} diff --git a/modules/data/tools/smart_recorder/drive_event_trigger.cc b/modules/data/tools/smart_recorder/drive_event_trigger.cc deleted file mode 100644 index 12d33aad95e..00000000000 --- a/modules/data/tools/smart_recorder/drive_event_trigger.cc +++ /dev/null @@ -1,47 +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/data/tools/smart_recorder/drive_event_trigger.h" - -#include "cyber/common/log.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common_msgs/basic_msgs/drive_event.pb.h" - -namespace apollo { -namespace data { - -using apollo::common::DriveEvent; - -DriveEventTrigger::DriveEventTrigger() { trigger_name_ = "DriveEventTrigger"; } - -void DriveEventTrigger::Pull(const cyber::record::RecordMessage& msg) { - if (!trigger_obj_->enabled()) { - return; - } - // Simply check the channel - if (msg.channel_name == FLAGS_drive_event_topic) { - DriveEvent drive_event_msg; - drive_event_msg.ParseFromString(msg.content); - const uint64_t header_time = static_cast( - SecondsToNanoSeconds(drive_event_msg.header().timestamp_sec())); - AINFO << "drive event trigger is pulled: " << header_time << " - " - << msg.channel_name; - TriggerIt(header_time); - } -} - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/drive_event_trigger.h b/modules/data/tools/smart_recorder/drive_event_trigger.h deleted file mode 100644 index 08277984b24..00000000000 --- a/modules/data/tools/smart_recorder/drive_event_trigger.h +++ /dev/null @@ -1,42 +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 "modules/data/tools/smart_recorder/proto/smart_recorder_triggers.pb.h" -#include "modules/data/tools/smart_recorder/trigger_base.h" - -namespace apollo { -namespace data { - -/** - * @class DriveEventTrigger - * @brief DriveEvent trigger that records drive events - */ -class DriveEventTrigger : public TriggerBase { - public: - DriveEventTrigger(); - - void Pull(const cyber::record::RecordMessage& msg) override; - bool ShouldRestore(const cyber::record::RecordMessage& msg) const override { - return false; - }; - - virtual ~DriveEventTrigger() = default; -}; - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/emergency_mode_trigger.cc b/modules/data/tools/smart_recorder/emergency_mode_trigger.cc deleted file mode 100644 index 3ac5ee0ff72..00000000000 --- a/modules/data/tools/smart_recorder/emergency_mode_trigger.cc +++ /dev/null @@ -1,50 +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/data/tools/smart_recorder/emergency_mode_trigger.h" - -#include "cyber/common/log.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -namespace apollo { -namespace data { - -using apollo::canbus::Chassis; - -EmergencyModeTrigger::EmergencyModeTrigger() { - trigger_name_ = "EmergencyModeTrigger"; -} - -void EmergencyModeTrigger::Pull(const cyber::record::RecordMessage& msg) { - if (!trigger_obj_->enabled()) { - return; - } - if (msg.channel_name == FLAGS_chassis_topic) { - apollo::canbus::Chassis chassis_msg; - chassis_msg.ParseFromString(msg.content); - if (cur_driving_mode_ == Chassis::COMPLETE_AUTO_DRIVE && - chassis_msg.driving_mode() == Chassis::EMERGENCY_MODE) { - AINFO << "emergency mode trigger is pulled: " << msg.time << " - " - << msg.channel_name; - TriggerIt(msg.time); - } - cur_driving_mode_ = chassis_msg.driving_mode(); - } -} - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/emergency_mode_trigger.h b/modules/data/tools/smart_recorder/emergency_mode_trigger.h deleted file mode 100644 index dd024315920..00000000000 --- a/modules/data/tools/smart_recorder/emergency_mode_trigger.h +++ /dev/null @@ -1,47 +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 "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/data/tools/smart_recorder/proto/smart_recorder_triggers.pb.h" -#include "modules/data/tools/smart_recorder/trigger_base.h" - -namespace apollo { -namespace data { - -/** - * @class EmergencyModeTrigger - * @brief EmergencyMode trigger that fires when emergency mode is engaged - */ -class EmergencyModeTrigger : public TriggerBase { - public: - EmergencyModeTrigger(); - - void Pull(const cyber::record::RecordMessage& msg) override; - bool ShouldRestore(const cyber::record::RecordMessage& msg) const override { - return false; - }; - - virtual ~EmergencyModeTrigger() = default; - - private: - apollo::canbus::Chassis::DrivingMode cur_driving_mode_ = - apollo::canbus::Chassis::COMPLETE_MANUAL; -}; - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/hard_brake_trigger.cc b/modules/data/tools/smart_recorder/hard_brake_trigger.cc deleted file mode 100644 index c56ff4ffbe2..00000000000 --- a/modules/data/tools/smart_recorder/hard_brake_trigger.cc +++ /dev/null @@ -1,91 +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/data/tools/smart_recorder/hard_brake_trigger.h" - -#include -#include - -#include "cyber/common/log.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -namespace apollo { -namespace data { - -using apollo::canbus::Chassis; - -HardBrakeTrigger::HardBrakeTrigger() { trigger_name_ = "HardBrakeTrigger"; } - -void HardBrakeTrigger::Pull(const cyber::record::RecordMessage& msg) { - if (!trigger_obj_->enabled()) { - return; - } - - if (msg.channel_name == FLAGS_chassis_topic) { - Chassis chassis_msg; - chassis_msg.ParseFromString(msg.content); - const float speed = chassis_msg.speed_mps(); - - if (IsNoisy(speed)) { - return; - } - - EnqueueMessage(speed); - - if (IsHardBrake()) { - AINFO << "hard break trigger is pulled: " << msg.time << " - " - << msg.channel_name; - TriggerIt(msg.time); - } - } -} - -bool HardBrakeTrigger::IsNoisy(const float speed) const { - const float pre_speed_mps = - (current_speed_queue_.empty() ? 0.0f : current_speed_queue_.back()); - return fabs(pre_speed_mps - speed) > noisy_diff_; -} - -bool HardBrakeTrigger::IsHardBrake() const { - if (current_speed_queue_.size() < queue_size_ || - history_speed_queue_.size() < queue_size_) { - return false; - } - const float delta = - (history_total_ - current_total_) / static_cast(queue_size_); - return delta > max_delta_; -} - -void HardBrakeTrigger::EnqueueMessage(const float speed) { - current_speed_queue_.emplace_back(speed); - current_total_ += speed; - if (current_speed_queue_.size() > queue_size_) { - const float current_front = current_speed_queue_.front(); - current_speed_queue_.pop_front(); - current_total_ -= current_front; - - history_speed_queue_.emplace_back(current_front); - history_total_ += current_front; - if (history_speed_queue_.size() > queue_size_) { - history_total_ -= history_speed_queue_.front(); - history_speed_queue_.pop_front(); - } - } -} - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/hard_brake_trigger.h b/modules/data/tools/smart_recorder/hard_brake_trigger.h deleted file mode 100644 index 0adf790c26f..00000000000 --- a/modules/data/tools/smart_recorder/hard_brake_trigger.h +++ /dev/null @@ -1,59 +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 "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/data/tools/smart_recorder/proto/smart_recorder_triggers.pb.h" -#include "modules/data/tools/smart_recorder/trigger_base.h" - -namespace apollo { -namespace data { - -/** - * @class HardBrakeTrigger - * @brief HardBrake trigger that fires when hard break is engaged - */ -class HardBrakeTrigger : public TriggerBase { - public: - HardBrakeTrigger(); - - void Pull(const cyber::record::RecordMessage& msg) override; - bool ShouldRestore(const cyber::record::RecordMessage& msg) const override { - return false; - }; - - virtual ~HardBrakeTrigger() = default; - - private: - bool IsHardBrake() const; - bool IsNoisy(const float speed) const; - void EnqueueMessage(const float speed); - - private: - const size_t queue_size_ = 10; - const float max_delta_ = 10.0f; - const float noisy_diff_ = 20.0f; - std::deque history_speed_queue_; - std::deque current_speed_queue_; - float history_total_; - float current_total_; -}; - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/interval_pool.cc b/modules/data/tools/smart_recorder/interval_pool.cc deleted file mode 100644 index 2105b7babce..00000000000 --- a/modules/data/tools/smart_recorder/interval_pool.cc +++ /dev/null @@ -1,120 +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/data/tools/smart_recorder/interval_pool.h" - -#include -#include -#include - -#include "cyber/common/log.h" - -namespace apollo { -namespace data { - -IntervalPool::IntervalPool() {} - -void IntervalPool::AddInterval(const Interval& interval) { - if (pool_.empty() || interval.begin_time > pool_iter_->end_time) { - pool_.push_back(interval); - pool_iter_ = std::prev(pool_.end()); - return; - } - pool_iter_->begin_time = - std::min(interval.begin_time, pool_iter_->begin_time); - pool_iter_->end_time = std::max(interval.end_time, pool_iter_->end_time); -} - -void IntervalPool::AddInterval(const uint64_t begin_time, - const uint64_t end_time) { - struct Interval interval; - interval.begin_time = begin_time; - interval.end_time = end_time; - AddInterval(interval); -} - -void IntervalPool::ReorgIntervals() { - // Sort the intervals by begin_time ascending - std::sort(pool_.begin(), pool_.end(), - [](const Interval& x, const Interval& y) { - return x.begin_time < y.begin_time; - }); - pool_iter_ = pool_.begin(); - accu_end_values_.clear(); -} - -bool IntervalPool::MessageFallIntoRange(const uint64_t msg_time) { - // For each message comes for checking, the logic is: - // 1. Add end_time of any intervals whose begin_time is smaller - // than message time to the helper set - // 2. Now if the helper set is not empty, means some range is still - // in progress, returns true - // 3. After this, remove end_time equals to message time from the set, - // which means these ranges are done being used - // This way range groups iterate along with messages, time complexity O(N) - while (pool_iter_ != pool_.end() && msg_time >= pool_iter_->begin_time) { - accu_end_values_.insert(pool_iter_->end_time); - ++pool_iter_; - } - bool found = !accu_end_values_.empty(); - accu_end_values_.erase(msg_time); - return found; -} - -void IntervalPool::Reset() { - pool_.clear(); - pool_iter_ = pool_.begin(); - accu_end_values_.clear(); -} - -void IntervalPool::PrintIntervals() const { - auto idx = 0; - for (const auto& interval : pool_) { - AINFO << "Interval " << ++idx << ": " << interval.begin_time << " - " - << interval.end_time; - } -} - -void IntervalPool::LogIntervalEvent(const std::string& name, - const std::string& description, - const uint64_t msg_time, - const uint64_t backward_time, - const uint64_t forward_time) const { - std::ofstream logfile(interval_event_log_file_path_, - std::ios::out | std::ios::app); - if (!logfile) { - AERROR << "Failed to write " << interval_event_log_file_path_; - return; - } - logfile << std::fixed << std::setprecision(9); - logfile << "name=" << name << ", description=\"" << description << "\"" - << ", msg_time=" << msg_time << ", interval_range=[" - << msg_time - backward_time << ":" << msg_time + forward_time << "]" - << std::endl; -} - -Interval IntervalPool::GetNextInterval() const { - if (pool_.empty()) { - struct Interval interval; - interval.begin_time = 0; - interval.end_time = 0; - return interval; - } - return *pool_iter_; -} - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/interval_pool.h b/modules/data/tools/smart_recorder/interval_pool.h deleted file mode 100644 index f795fd08249..00000000000 --- a/modules/data/tools/smart_recorder/interval_pool.h +++ /dev/null @@ -1,67 +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 -#include - -#include "absl/strings/str_cat.h" -#include "cyber/common/macros.h" - -namespace apollo { -namespace data { - -struct Interval { - uint64_t begin_time; - uint64_t end_time; -}; - -/** - * @class IntervalPool - * @brief The intervals collection class that organizes the intervals - */ -class IntervalPool { - public: - void AddInterval(const Interval& interval); - void AddInterval(const uint64_t begin_time, const uint64_t end_time); - void ReorgIntervals(); - bool MessageFallIntoRange(const uint64_t msg_time); - void Reset(); - void PrintIntervals() const; - Interval GetNextInterval() const; - void SetIntervalEventLogFilePath(const std::string& path, - const std::string& task_id) { - interval_event_log_file_path_ = absl::StrCat(path, "_", task_id); - } - void LogIntervalEvent(const std::string& name, const std::string& description, - const uint64_t msg_time, const uint64_t backward_time, - const uint64_t forward_time) const; - - private: - std::vector pool_; - std::vector::iterator pool_iter_; - std::set accu_end_values_; - std::string interval_event_log_file_path_; - - DECLARE_SINGLETON(IntervalPool) -}; - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/post_record_processor.cc b/modules/data/tools/smart_recorder/post_record_processor.cc deleted file mode 100644 index ac097546b6b..00000000000 --- a/modules/data/tools/smart_recorder/post_record_processor.cc +++ /dev/null @@ -1,126 +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/data/tools/smart_recorder/post_record_processor.h" - -#include - -#include -#include -#include - -#include "absl/strings/str_cat.h" -#include "cyber/common/file.h" -#include "cyber/common/log.h" -#include "cyber/record/record_reader.h" -#include "cyber/record/record_viewer.h" - -#include "modules/data/tools/smart_recorder/channel_pool.h" -#include "modules/data/tools/smart_recorder/interval_pool.h" - -namespace apollo { -namespace data { - -using cyber::common::DirectoryExists; -using cyber::record::RecordReader; -using cyber::record::RecordViewer; -using cyber::record::RecordWriter; - -bool PostRecordProcessor::Init(const SmartRecordTrigger& trigger_conf) { - if (!DirectoryExists(source_record_dir_)) { - AERROR << "source record dir does not exist: " << source_record_dir_; - return false; - } - LoadSourceRecords(); - if (source_record_files_.empty()) { - AERROR << "source record dir does not have any records: " - << source_record_dir_; - return false; - } - if (!RecordProcessor::Init(trigger_conf)) { - AERROR << "base init failed"; - return false; - } - return true; -} - -bool PostRecordProcessor::Process() { - // First scan, get intervals - for (const std::string& record : source_record_files_) { - const auto reader = std::make_shared( - absl::StrCat(source_record_dir_, "/", record)); - RecordViewer viewer(reader, 0, - std::numeric_limits::max(), - ChannelPool::Instance()->GetAllChannels()); - AINFO << record << ":" << viewer.begin_time() << " - " << viewer.end_time(); - for (const auto& msg : viewer) { - for (const auto& trigger : triggers_) { - trigger->Pull(msg); - } - } - } - // Second scan, restore messages based on intervals in the first scan - IntervalPool::Instance()->ReorgIntervals(); - IntervalPool::Instance()->PrintIntervals(); - for (const std::string& record : source_record_files_) { - const auto reader = std::make_shared( - absl::StrCat(source_record_dir_, "/", record)); - RecordViewer viewer(reader, 0, - std::numeric_limits::max(), - ChannelPool::Instance()->GetAllChannels()); - for (const auto& msg : viewer) { - // If the message fall into generated intervals, - // or required by any triggers, restore it - if (IntervalPool::Instance()->MessageFallIntoRange(msg.time) || - ShouldRestore(msg)) { - writer_->WriteChannel(msg.channel_name, - reader->GetMessageType(msg.channel_name), - reader->GetProtoDesc(msg.channel_name)); - writer_->WriteMessage(msg.channel_name, msg.content, msg.time); - } - } - } - return true; -} - -std::string PostRecordProcessor::GetDefaultOutputFile() const { - std::string src_file_name = source_record_files_.front(); - const std::string record_flag(".record"); - src_file_name.resize(src_file_name.size() - src_file_name.find(record_flag) + - record_flag.size() + 1); - return absl::StrCat(restored_output_dir_, "/", src_file_name); -} - -void PostRecordProcessor::LoadSourceRecords() { - DIR* dirp = opendir(source_record_dir_.c_str()); - if (dirp == nullptr) { - AERROR << "failed to open source dir: " << source_record_dir_; - return; - } - struct dirent* dp = nullptr; - while ((dp = readdir(dirp)) != nullptr) { - const std::string file_name = dp->d_name; - if (dp->d_type == DT_REG && - file_name.find(".record") != std::string::npos) { - source_record_files_.push_back(file_name); - } - } - closedir(dirp); - std::sort(source_record_files_.begin(), source_record_files_.end()); -} - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/post_record_processor.h b/modules/data/tools/smart_recorder/post_record_processor.h deleted file mode 100644 index 83bf553189c..00000000000 --- a/modules/data/tools/smart_recorder/post_record_processor.h +++ /dev/null @@ -1,49 +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/data/tools/smart_recorder/proto/smart_recorder_triggers.pb.h" -#include "modules/data/tools/smart_recorder/record_processor.h" - -namespace apollo { -namespace data { - -/** - * @class PostRecordProcessor - * @brief Post processor against recorded tasks that have been completed - */ -class PostRecordProcessor : public RecordProcessor { - public: - PostRecordProcessor(const std::string& source_record_dir, - const std::string& restored_output_dir) - : RecordProcessor(source_record_dir, restored_output_dir) {} - bool Init(const SmartRecordTrigger& trigger_conf) override; - bool Process() override; - std::string GetDefaultOutputFile() const override; - virtual ~PostRecordProcessor() = default; - - private: - void LoadSourceRecords(); - - std::vector source_record_files_; -}; - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/proto/BUILD b/modules/data/tools/smart_recorder/proto/BUILD deleted file mode 100644 index 96c9114800d..00000000000 --- a/modules/data/tools/smart_recorder/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 = "smart_recorder_triggers_cc_proto", - deps = [ - ":smart_recorder_triggers_proto", - ], -) - -proto_library( - name = "smart_recorder_triggers_proto", - srcs = ["smart_recorder_triggers.proto"], -) - -py_proto_library( - name = "smart_recorder_triggers_py_pb2", - deps = [ - ":smart_recorder_triggers_proto", - ], -) - -install_files( - name = "py_pb_data_tools", - dest = "data/python/modules/data/tools/smart_recorder/proto", - files = [ - "smart_recorder_triggers_py_pb2", - ] -) \ No newline at end of file diff --git a/modules/data/tools/smart_recorder/proto/smart_recorder_triggers.proto b/modules/data/tools/smart_recorder/proto/smart_recorder_triggers.proto deleted file mode 100644 index a5bad2e0a54..00000000000 --- a/modules/data/tools/smart_recorder/proto/smart_recorder_triggers.proto +++ /dev/null @@ -1,26 +0,0 @@ -syntax = "proto2"; - -package apollo.data; - -message RecordSegmentSetting { - // Segmentation of restored records in size or time - optional int32 size_segment = 1 [default = 500]; - optional int32 time_segment = 2 [default = 180]; -} - -message Trigger { - optional string trigger_name = 1; - optional bool enabled = 2; - optional double backward_time = 3; - optional double forward_time = 4; - optional string description = 5; -} - -message SmartRecordTrigger { - optional RecordSegmentSetting segment_setting = 1; - repeated Trigger triggers = 2; - optional double max_backward_time = 3 [default = 30.0]; - optional double min_restore_chunk = 4 [default = 5.0]; - optional string trigger_log_file_path = 5; - optional int32 reused_record_num = 6 [default = 10]; -} diff --git a/modules/data/tools/smart_recorder/realtime_record_processor.cc b/modules/data/tools/smart_recorder/realtime_record_processor.cc deleted file mode 100644 index a54fc7c7113..00000000000 --- a/modules/data/tools/smart_recorder/realtime_record_processor.cc +++ /dev/null @@ -1,325 +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/data/tools/smart_recorder/realtime_record_processor.h" - -#include - -#include -#include -#include -#include -#include -#include - -#include "cyber/common/file.h" -#include "cyber/common/log.h" -#include "cyber/init.h" -#include "cyber/record/file/record_file_reader.h" -#include "cyber/record/record_message.h" -#include "cyber/record/record_viewer.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/monitor/common/monitor_manager.h" - -#include "modules/data/tools/smart_recorder/channel_pool.h" -#include "modules/data/tools/smart_recorder/interval_pool.h" - -using Time = ::apollo::cyber::Time; - -namespace apollo { -namespace data { - -namespace { - -using apollo::common::Header; -using apollo::monitor::MonitorManager; -using cyber::CreateNode; -using cyber::common::EnsureDirectory; -using cyber::common::GetFileName; -using cyber::common::PathExists; -using cyber::common::RemoveAllFiles; -using cyber::record::HeaderBuilder; -using cyber::record::Recorder; -using cyber::record::RecordFileReader; -using cyber::record::RecordMessage; -using cyber::record::RecordReader; -using cyber::record::RecordViewer; - -std::string GetNextRecordFileName(const std::string& record_path) { - static constexpr int kSuffixLen = 5; - const std::string kInitialSequence = "00000"; - if (record_path.empty()) { - return kInitialSequence; - } - std::stringstream record_suffix; - record_suffix.fill('0'); - record_suffix.width(kSuffixLen); - record_suffix << std::stoi(record_path.substr(record_path.size() - kSuffixLen, - kSuffixLen)) + - 1; - return record_suffix.str(); -} - -bool IsRecordValid(const std::string& record_path) { - if (!PathExists(record_path)) { - return false; - } - const std::unique_ptr file_reader(new RecordFileReader()); - if (!file_reader->Open(record_path)) { - AERROR << "failed to open record file for checking header: " << record_path; - return false; - } - const bool is_complete = file_reader->GetHeader().is_complete(); - file_reader->Close(); - return is_complete; -} - -} // namespace - -RealtimeRecordProcessor::RealtimeRecordProcessor( - const std::string& source_record_dir, - const std::string& restored_output_dir) - : RecordProcessor(source_record_dir, restored_output_dir) { - default_output_filename_ = restored_output_dir_; - default_output_filename_.erase( - std::remove(default_output_filename_.begin(), - default_output_filename_.end(), '-'), - default_output_filename_.end()); - default_output_filename_ = - GetFileName(absl::StrCat(default_output_filename_, ".record"), false); -} - -bool RealtimeRecordProcessor::Init(const SmartRecordTrigger& trigger_conf) { - // Init input/output, for realtime processor create both - // input and output dir if they do not exist - if (!EnsureDirectory(source_record_dir_) || - !EnsureDirectory(restored_output_dir_)) { - AERROR << "unable to init input/output dir: " << source_record_dir_ << "/" - << restored_output_dir_; - return false; - } - if (!RemoveAllFiles(source_record_dir_)) { - AERROR << "unable to clear input dir: " << source_record_dir_; - return false; - } - // Init recorder - cyber::Init("smart_recorder"); - smart_recorder_node_ = CreateNode(absl::StrCat("smart_recorder_", getpid())); - if (smart_recorder_node_ == nullptr) { - AERROR << "create smart recorder node failed: " << getpid(); - return false; - } - recorder_status_writer_ = - smart_recorder_node_->CreateWriter( - FLAGS_recorder_status_topic); - max_backward_time_ = trigger_conf.max_backward_time(); - min_restore_chunk_ = trigger_conf.min_restore_chunk(); - std::vector all_channels; - std::vector black_channels; - const std::set& all_channels_set = - ChannelPool::Instance()->GetAllChannels(); - std::copy(all_channels_set.begin(), all_channels_set.end(), - std::back_inserter(all_channels)); - recorder_ = std::make_shared( - absl::StrCat(source_record_dir_, "/", default_output_filename_), false, - all_channels, black_channels, HeaderBuilder::GetHeader()); - // Init base - if (!RecordProcessor::Init(trigger_conf)) { - AERROR << "base init failed"; - return false; - } - reused_record_num_ = trigger_conf.reused_record_num(); - record_files_.clear(); - return true; -} - -bool RealtimeRecordProcessor::Process() { - // Recorder goes first - recorder_->Start(); - PublishStatus(RecordingState::RECORDING, "smart recorder started"); - MonitorManager::Instance()->LogBuffer().INFO("SmartRecorder is recording..."); - std::shared_ptr monitor_thread = - std::make_shared([this]() { this->MonitorStatus(); }); - // Now fast reader follows and reacts for any events - std::string record_path; - do { - if (!GetNextValidRecord(&record_path)) { - AINFO << "record reader " << record_path << " reached end, exit now"; - break; - } - auto reader = std::make_shared(record_path); - RecordViewer viewer(reader, 0, std::numeric_limits::max(), - ChannelPool::Instance()->GetAllChannels()); - AINFO << "checking " << record_path << ": " << viewer.begin_time() << " - " - << viewer.end_time(); - if (restore_reader_time_ == 0) { - restore_reader_time_ = viewer.begin_time(); - GetNextValidRecord(&restore_path_); - } - for (const auto& msg : viewer) { - for (const auto& trigger : triggers_) { - trigger->Pull(msg); - } - // Slow reader restores the events if any - RestoreMessage(msg.time); - } - } while (!is_terminating_); - // Try restore the rest of messages one last time - RestoreMessage(std::numeric_limits::max()); - if (monitor_thread && monitor_thread->joinable()) { - monitor_thread->join(); - monitor_thread = nullptr; - } - PublishStatus(RecordingState::STOPPED, "smart recorder stopped"); - MonitorManager::Instance()->LogBuffer().INFO("SmartRecorder is stopped"); - return true; -} - -void RealtimeRecordProcessor::ProcessRestoreRecord( - const std::string& record_path) { - // Get all the record files - std::string record_source_path = ""; - record_source_path = record_path + "/"; - std::vector files = - cyber::common::ListSubPaths(record_source_path, DT_REG); - std::smatch result; - std::regex record_file_name_regex("[1-9][0-9]{13}\\.record\\.[0-9]{5}"); - for (const auto& file : files) { - if (std::regex_match(file, result, record_file_name_regex)) { - if (std::find(record_files_.begin(), record_files_.end(), file) == - record_files_.end()) { - record_files_.emplace_back(file); - } - } - } - // Sort the files in name order. - std::sort(record_files_.begin(), record_files_.end(), - [](const std::string& a, const std::string& b) { return a < b; }); - // Delete the overdue files by num. - if (record_files_.size() > reused_record_num_) { - if (0 != - std::remove((record_source_path + (*record_files_.begin())).c_str())) { - AWARN << "Failed to delete file: " << *record_files_.begin(); - } - record_files_.erase(record_files_.begin()); - } -} - -void RealtimeRecordProcessor::MonitorStatus() { - int status_counter = 0; - while (!cyber::IsShutdown()) { - static constexpr int kCheckingFrequency = 100; - static constexpr int kPublishStatusFrequency = 30; - std::this_thread::sleep_for(std::chrono::milliseconds(kCheckingFrequency)); - if (++status_counter % kPublishStatusFrequency == 0) { - status_counter = 0; - PublishStatus(RecordingState::RECORDING, "smart recorder recording"); - // AINFO << "smart recorder recording status check every 3000ms a time."; - ProcessRestoreRecord(source_record_dir_); - } - } - recorder_->Stop(); - is_terminating_ = true; - AINFO << "wait for a while trying to complete the restore work"; - static constexpr int kMessageInterval = 1000; - int interval_counter = 0; - while (++interval_counter * kMessageInterval < recorder_wait_time_) { - MonitorManager::Instance()->LogBuffer().WARN( - "SmartRecorder is terminating..."); - std::this_thread::sleep_for(std::chrono::milliseconds(kMessageInterval)); - } -} - -void RealtimeRecordProcessor::PublishStatus(const RecordingState state, - const std::string& message) const { - SmartRecorderStatus status; - Header* status_headerpb = status.mutable_header(); - status_headerpb->set_timestamp_sec(Time::Now().ToSecond()); - status.set_recording_state(state); - status.set_state_message(message); - AINFO << "send message with state " << state << ", " << message; - recorder_status_writer_->Write(status); -} - -bool RealtimeRecordProcessor::GetNextValidRecord( - std::string* record_path) const { - *record_path = absl::StrCat(source_record_dir_, "/", default_output_filename_, - ".", GetNextRecordFileName(*record_path)); - while (!is_terminating_ && !IsRecordValid(*record_path)) { - AINFO << "next record unavailable, wait " << recorder_wait_time_ << " ms"; - std::this_thread::sleep_for(std::chrono::milliseconds(recorder_wait_time_)); - } - return IsRecordValid(*record_path); -} - -void RealtimeRecordProcessor::RestoreMessage(const uint64_t message_time) { - // Check and restore messages, logic is: - // 1. If new events got triggered, restore reader proceeds all the way to the - // event's end - // 2. If no events got triggered, but given message leads the restore reader - // by more than max value, proceeds to the max value point - // 3. Otherwise, do nothing - const struct Interval interval = IntervalPool::Instance()->GetNextInterval(); - const uint64_t target_end = std::max( - interval.end_time, - message_time - static_cast(max_backward_time_ * 1000000000UL)); - const bool small_channels_only = restore_reader_time_ >= interval.end_time; - if (small_channels_only && - target_end <= - restore_reader_time_ + - static_cast(min_restore_chunk_ * 1000000000UL)) { - return; - } - do { - if (!IsRecordValid(restore_path_)) { - AWARN << "invalid restore path " << restore_path_ << ", exit"; - break; - } - AINFO << "target restoring " << restore_path_ << ": " - << restore_reader_time_ << " - " << target_end; - auto reader = std::make_shared(restore_path_); - restore_reader_time_ = - std::max(restore_reader_time_, reader->GetHeader().begin_time()); - if (restore_reader_time_ > target_end || - reader->GetHeader().begin_time() >= reader->GetHeader().end_time()) { - AWARN << "record " << restore_path_ << " begin_time beyond target, exit"; - break; - } - RecordViewer viewer(reader, restore_reader_time_, target_end, - ChannelPool::Instance()->GetAllChannels()); - AINFO << "actual restoring " << restore_path_ << ": " << viewer.begin_time() - << " - " << viewer.end_time(); - for (const auto& msg : viewer) { - if ((!small_channels_only && msg.time >= interval.begin_time && - msg.time <= interval.end_time) || - ShouldRestore(msg)) { - if (writer_->IsNewChannel(msg.channel_name)) { - writer_->WriteChannel(msg.channel_name, - reader->GetMessageType(msg.channel_name), - reader->GetProtoDesc(msg.channel_name)); - } - writer_->WriteMessage(msg.channel_name, msg.content, msg.time); - } - } - restore_reader_time_ = std::min(reader->GetHeader().end_time(), target_end); - if (target_end >= reader->GetHeader().end_time()) { - GetNextValidRecord(&restore_path_); - } - } while (restore_reader_time_ < target_end); -} - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/realtime_record_processor.h b/modules/data/tools/smart_recorder/realtime_record_processor.h deleted file mode 100644 index 6b4107f3f4a..00000000000 --- a/modules/data/tools/smart_recorder/realtime_record_processor.h +++ /dev/null @@ -1,74 +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 "absl/strings/str_cat.h" -#include "cyber/cyber.h" -#include "cyber/record/record_reader.h" -#include "cyber/tools/cyber_recorder/recorder.h" -#include "modules/common_msgs/monitor_msgs/smart_recorder_status.pb.h" -#include "modules/data/tools/smart_recorder/proto/smart_recorder_triggers.pb.h" -#include "modules/data/tools/smart_recorder/record_processor.h" - -namespace apollo { -namespace data { - -/** - * @class RealtimeRecordProcessor - * @brief Realtime processor against recorded tasks that are being recorded - */ -class RealtimeRecordProcessor : public RecordProcessor { - public: - RealtimeRecordProcessor(const std::string& source_record_dir, - const std::string& restored_output_dir); - bool Init(const SmartRecordTrigger& trigger_conf) override; - bool Process() override; - std::string GetDefaultOutputFile() const override { - return absl::StrCat(restored_output_dir_, "/", default_output_filename_); - }; - void MonitorStatus(); - virtual ~RealtimeRecordProcessor() = default; - - private: - bool GetNextValidRecord(std::string* record_path) const; - void RestoreMessage(const uint64_t message_time); - void PublishStatus(const RecordingState state, - const std::string& message) const; - void ProcessRestoreRecord(const std::string& record_path); - double GetDuration(const std::string& record_file); - - std::shared_ptr recorder_ = nullptr; - std::shared_ptr smart_recorder_node_ = nullptr; - std::shared_ptr> recorder_status_writer_ = - nullptr; - std::vector record_files_; - std::string default_output_filename_; - std::string restore_path_; - uint32_t reused_record_num_ = 0; - uint64_t restore_reader_time_ = 0; - double max_backward_time_ = 30.0; - double min_restore_chunk_ = 5.0; - bool is_terminating_ = false; - const int recorder_wait_time_ = 5000; -}; - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/record_processor.cc b/modules/data/tools/smart_recorder/record_processor.cc deleted file mode 100644 index 7cba45634a7..00000000000 --- a/modules/data/tools/smart_recorder/record_processor.cc +++ /dev/null @@ -1,107 +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/data/tools/smart_recorder/record_processor.h" - -#include "cyber/common/file.h" -#include "cyber/common/log.h" - -#include "modules/data/tools/smart_recorder/bumper_crash_trigger.h" -#include "modules/data/tools/smart_recorder/drive_event_trigger.h" -#include "modules/data/tools/smart_recorder/emergency_mode_trigger.h" -#include "modules/data/tools/smart_recorder/hard_brake_trigger.h" -#include "modules/data/tools/smart_recorder/interval_pool.h" -#include "modules/data/tools/smart_recorder/regular_interval_trigger.h" -#include "modules/data/tools/smart_recorder/small_topics_trigger.h" -#include "modules/data/tools/smart_recorder/swerve_trigger.h" - -namespace apollo { -namespace data { - -using cyber::common::DirectoryExists; -using cyber::common::EnsureDirectory; -using cyber::common::GetFileName; -using cyber::record::RecordWriter; - -RecordProcessor::RecordProcessor(const std::string& source_record_dir, - const std::string& restored_output_dir) - : source_record_dir_(source_record_dir), - restored_output_dir_(restored_output_dir) {} - -bool RecordProcessor::Init(const SmartRecordTrigger& trigger_conf) { - // Init input/output - if (!DirectoryExists(source_record_dir_)) { - AERROR << "source record dir does not exist: " << source_record_dir_; - return false; - } - if (!EnsureDirectory(restored_output_dir_)) { - AERROR << "unable to open output dir: " << restored_output_dir_; - return false; - } - // Init triggers - if (!InitTriggers(trigger_conf)) { - AERROR << "unable to init triggers"; - return false; - } - // Init writer - static constexpr uint64_t kMBToKB = 1024UL; - writer_.reset(new RecordWriter()); - writer_->SetIntervalOfFileSegmentation( - trigger_conf.segment_setting().time_segment()); - writer_->SetSizeOfFileSegmentation( - trigger_conf.segment_setting().size_segment() * kMBToKB); - const std::string output_file = GetDefaultOutputFile(); - AINFO << "output file path: " << output_file; - if (!writer_->Open(output_file)) { - AERROR << "failed to open file for writing: " << output_file; - return false; - } - // Init intervals pool - IntervalPool::Instance()->Reset(); - IntervalPool::Instance()->SetIntervalEventLogFilePath( - trigger_conf.trigger_log_file_path(), GetFileName(restored_output_dir_)); - return true; -} - -bool RecordProcessor::InitTriggers(const SmartRecordTrigger& trigger_conf) { - triggers_.push_back(std::unique_ptr(new DriveEventTrigger)); - triggers_.push_back(std::unique_ptr(new EmergencyModeTrigger)); - triggers_.push_back(std::unique_ptr(new HardBrakeTrigger)); - triggers_.push_back(std::unique_ptr(new SmallTopicsTrigger)); - triggers_.push_back(std::unique_ptr(new RegularIntervalTrigger)); - triggers_.push_back(std::unique_ptr(new SwerveTrigger)); - triggers_.push_back(std::unique_ptr(new BumperCrashTrigger)); - for (const auto& trigger : triggers_) { - if (!trigger->Init(trigger_conf)) { - AERROR << "unable to initiate trigger and collect channels"; - return false; - } - } - return true; -} - -bool RecordProcessor::ShouldRestore( - const cyber::record::RecordMessage& msg) const { - for (const auto& trigger : triggers_) { - if (trigger->ShouldRestore(msg)) { - return true; - } - } - return false; -} - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/record_processor.h b/modules/data/tools/smart_recorder/record_processor.h deleted file mode 100644 index 257198cd4c8..00000000000 --- a/modules/data/tools/smart_recorder/record_processor.h +++ /dev/null @@ -1,56 +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 "cyber/record/record_message.h" -#include "cyber/record/record_writer.h" - -#include "modules/data/tools/smart_recorder/proto/smart_recorder_triggers.pb.h" -#include "modules/data/tools/smart_recorder/trigger_base.h" - -namespace apollo { -namespace data { - -/** - * @class RecordProcessor - * @brief Process messages and apply the rules based on configured triggers - */ -class RecordProcessor { - public: - RecordProcessor(const std::string& source_record_dir, - const std::string& restored_output_dir); - virtual bool Init(const SmartRecordTrigger& trigger_conf); - virtual bool Process() = 0; - virtual std::string GetDefaultOutputFile() const = 0; - virtual ~RecordProcessor() { writer_->Close(); } - - protected: - bool InitTriggers(const SmartRecordTrigger& trigger_conf); - bool ShouldRestore(const cyber::record::RecordMessage& msg) const; - - const std::string source_record_dir_; - const std::string restored_output_dir_; - std::vector> triggers_; - std::unique_ptr writer_ = nullptr; -}; - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/regular_interval_trigger.cc b/modules/data/tools/smart_recorder/regular_interval_trigger.cc deleted file mode 100644 index 2b571065184..00000000000 --- a/modules/data/tools/smart_recorder/regular_interval_trigger.cc +++ /dev/null @@ -1,45 +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/data/tools/smart_recorder/regular_interval_trigger.h" - -#include "cyber/common/log.h" - -namespace apollo { -namespace data { - -RegularIntervalTrigger::RegularIntervalTrigger() { - trigger_name_ = "RegularIntervalTrigger"; -} - -void RegularIntervalTrigger::Pull(const cyber::record::RecordMessage& msg) { - if (!trigger_obj_->enabled()) { - return; - } - if (current_recording_time_ == 0) { - current_recording_time_ = msg.time; - return; - } - if (msg.time - current_recording_time_ > - SecondsToNanoSeconds(recording_interval_)) { - current_recording_time_ = msg.time; - AINFO << "regular interval trigger is pulled: " << msg.time; - TriggerIt(msg.time); - } -} - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/regular_interval_trigger.h b/modules/data/tools/smart_recorder/regular_interval_trigger.h deleted file mode 100644 index f17984d384a..00000000000 --- a/modules/data/tools/smart_recorder/regular_interval_trigger.h +++ /dev/null @@ -1,47 +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 "modules/data/tools/smart_recorder/proto/smart_recorder_triggers.pb.h" -#include "modules/data/tools/smart_recorder/trigger_base.h" - -namespace apollo { -namespace data { - -/** - * @class EmergencyModeTrigger - * @brief EmergencyMode trigger that fires when emergency mode is engaged - */ -class RegularIntervalTrigger : public TriggerBase { - public: - RegularIntervalTrigger(); - - void Pull(const cyber::record::RecordMessage& msg) override; - bool ShouldRestore(const cyber::record::RecordMessage& msg) const override { - return false; - }; - - virtual ~RegularIntervalTrigger() = default; - - private: - // Trigger the recording every 300 seconds (5 minutes) - const double recording_interval_ = 300.0; - uint64_t current_recording_time_ = 0UL; -}; - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/small_topics_trigger.cc b/modules/data/tools/smart_recorder/small_topics_trigger.cc deleted file mode 100644 index 66555c6f9df..00000000000 --- a/modules/data/tools/smart_recorder/small_topics_trigger.cc +++ /dev/null @@ -1,42 +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/data/tools/smart_recorder/small_topics_trigger.h" - -#include -#include - -#include "cyber/common/log.h" - -#include "modules/data/tools/smart_recorder/channel_pool.h" - -namespace apollo { -namespace data { - -SmallTopicsTrigger::SmallTopicsTrigger() { - trigger_name_ = "SmallTopicsTrigger"; -} - -bool SmallTopicsTrigger::ShouldRestore( - const cyber::record::RecordMessage& msg) const { - const std::set& small_channels = - ChannelPool::Instance()->GetSmallChannels(); - return trigger_obj_->enabled() && - small_channels.find(msg.channel_name) != small_channels.end(); -} - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/small_topics_trigger.h b/modules/data/tools/smart_recorder/small_topics_trigger.h deleted file mode 100644 index 110d815c759..00000000000 --- a/modules/data/tools/smart_recorder/small_topics_trigger.h +++ /dev/null @@ -1,42 +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 "modules/data/tools/smart_recorder/proto/smart_recorder_triggers.pb.h" -#include "modules/data/tools/smart_recorder/trigger_base.h" - -namespace apollo { -namespace data { - -/** - * @class SmallTopicsTrigger - * @brief - * A specialized trigger that does not trigger anything but indicates - * what small topics need to be restored - */ -class SmallTopicsTrigger : public TriggerBase { - public: - SmallTopicsTrigger(); - - void Pull(const cyber::record::RecordMessage& msg) override{}; - bool ShouldRestore(const cyber::record::RecordMessage& msg) const override; - - virtual ~SmallTopicsTrigger() = default; -}; - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/smart_recorder.cc b/modules/data/tools/smart_recorder/smart_recorder.cc deleted file mode 100644 index 2a8bc087f45..00000000000 --- a/modules/data/tools/smart_recorder/smart_recorder.cc +++ /dev/null @@ -1,64 +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 - -#include "gflags/gflags.h" - -#include "absl/strings/str_cat.h" -#include "cyber/common/file.h" -#include "cyber/common/log.h" - -#include "modules/data/tools/smart_recorder/post_record_processor.h" -#include "modules/data/tools/smart_recorder/realtime_record_processor.h" -#include "modules/data/tools/smart_recorder/smart_recorder_gflags.h" - -using apollo::cyber::common::GetProtoFromFile; -using apollo::data::PostRecordProcessor; -using apollo::data::RealtimeRecordProcessor; -using apollo::data::RecordProcessor; -using apollo::data::SmartRecordTrigger; - -int main(int argc, char** argv) { - google::ParseCommandLineFlags(&argc, &argv, true); - if (FLAGS_restored_output_dir.empty()) { - FLAGS_restored_output_dir = - absl::StrCat(FLAGS_source_records_dir, "_restored"); - } - AINFO << "input dir: " << FLAGS_source_records_dir - << ". output dir: " << FLAGS_restored_output_dir - << ". config file: " << FLAGS_smart_recorder_config_filename - << ". program name: " << argv[0]; - SmartRecordTrigger trigger_conf; - ACHECK(GetProtoFromFile(FLAGS_smart_recorder_config_filename, &trigger_conf)) - << "Failed to load triggers config file " - << FLAGS_smart_recorder_config_filename; - auto processor = std::unique_ptr(new RealtimeRecordProcessor( - FLAGS_source_records_dir, FLAGS_restored_output_dir)); - if (!FLAGS_real_time_trigger) { - processor = std::unique_ptr(new PostRecordProcessor( - FLAGS_source_records_dir, FLAGS_restored_output_dir)); - } - if (!processor->Init(trigger_conf)) { - AERROR << "failed to init record processor"; - return -1; - } - if (!processor->Process()) { - AERROR << "failed to process records"; - return -1; - } - return 0; -} diff --git a/modules/data/tools/smart_recorder/smart_recorder_gflags.cc b/modules/data/tools/smart_recorder/smart_recorder_gflags.cc deleted file mode 100644 index 8ba172a6a17..00000000000 --- a/modules/data/tools/smart_recorder/smart_recorder_gflags.cc +++ /dev/null @@ -1,25 +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/data/tools/smart_recorder/smart_recorder_gflags.h" - -DEFINE_string(source_records_dir, "", "The source dir with original records."); -DEFINE_string(restored_output_dir, "", "The output dir after processing."); -DEFINE_string(smart_recorder_config_filename, - "/apollo/modules/data/tools/smart_recorder/conf/" - "smart_recorder_config.pb.txt", - "The config file."); -DEFINE_bool(real_time_trigger, true, "Whether to use realtime trigger."); diff --git a/modules/data/tools/smart_recorder/smart_recorder_gflags.h b/modules/data/tools/smart_recorder/smart_recorder_gflags.h deleted file mode 100644 index 9b371de5829..00000000000 --- a/modules/data/tools/smart_recorder/smart_recorder_gflags.h +++ /dev/null @@ -1,24 +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(source_records_dir); -DECLARE_string(restored_output_dir); -DECLARE_string(smart_recorder_config_filename); -DECLARE_bool(real_time_trigger); diff --git a/modules/data/tools/smart_recorder/swerve_trigger.cc b/modules/data/tools/smart_recorder/swerve_trigger.cc deleted file mode 100644 index ec729366e2a..00000000000 --- a/modules/data/tools/smart_recorder/swerve_trigger.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 "modules/data/tools/smart_recorder/swerve_trigger.h" - -#include -#include - -#include "cyber/common/log.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common_msgs/control_msgs/control_cmd.pb.h" - -namespace apollo { -namespace data { - -using apollo::canbus::Chassis; -constexpr float MAX_STEER_PER = 100.0; -constexpr float MIN_STEER_PER = -100.0; - -SwerveTrigger::SwerveTrigger() { trigger_name_ = "SwerveTrigger"; } - -void SwerveTrigger::Pull(const cyber::record::RecordMessage& msg) { - if (!trigger_obj_->enabled()) { - return; - } - - if (msg.channel_name == FLAGS_chassis_topic) { - Chassis chassis_msg; - chassis_msg.ParseFromString(msg.content); - const float steer_per = chassis_msg.steering_percentage(); - - if (IsNoisy(steer_per)) { - return; - } - - EnqueueMessage(steer_per); - - if (IsSwerve()) { - AINFO << "swerve trigger is pulled: " << msg.time << " - " - << msg.channel_name; - TriggerIt(msg.time); - } - } -} - -bool SwerveTrigger::IsNoisy(const float steer) const { - if (steer > MAX_STEER_PER || steer < MIN_STEER_PER) { - return true; - } - const float pre_steer_mps = - (current_steer_queue_.empty() ? 0.0f : current_steer_queue_.back()); - return fabs(pre_steer_mps - steer) > noisy_diff_; -} - -bool SwerveTrigger::IsSwerve() const { - if (current_steer_queue_.size() < queue_size_ || - history_steer_queue_.size() < queue_size_) { - return false; - } - const float delta = - (history_total_ - current_total_) / static_cast(queue_size_); - return delta > max_delta_; -} - -// TODO(Leisheng Mu): reuse the code with hard_brake_trigger in next iteration -void SwerveTrigger::EnqueueMessage(const float steer) { - current_steer_queue_.emplace_back(steer); - current_total_ += steer; - if (current_steer_queue_.size() > queue_size_) { - const float current_front = current_steer_queue_.front(); - current_steer_queue_.pop_front(); - current_total_ -= current_front; - - history_steer_queue_.emplace_back(current_front); - history_total_ += current_front; - if (history_steer_queue_.size() > queue_size_) { - history_total_ -= history_steer_queue_.front(); - history_steer_queue_.pop_front(); - } - } -} - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/swerve_trigger.h b/modules/data/tools/smart_recorder/swerve_trigger.h deleted file mode 100644 index 5870990562a..00000000000 --- a/modules/data/tools/smart_recorder/swerve_trigger.h +++ /dev/null @@ -1,59 +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 "modules/common_msgs/chassis_msgs/chassis.pb.h" -#include "modules/data/tools/smart_recorder/proto/smart_recorder_triggers.pb.h" -#include "modules/data/tools/smart_recorder/trigger_base.h" - -namespace apollo { -namespace data { - -/** - * @class SwerveTrigger - * @brief Swerve trigger that fires when swerve is engaged - */ -class SwerveTrigger : public TriggerBase { - public: - SwerveTrigger(); - - void Pull(const cyber::record::RecordMessage& msg) override; - bool ShouldRestore(const cyber::record::RecordMessage& msg) const override { - return false; - }; - - virtual ~SwerveTrigger() = default; - - private: - bool IsSwerve() const; - bool IsNoisy(const float steer) const; - void EnqueueMessage(const float steer); - - private: - const size_t queue_size_ = 10; - const float max_delta_ = 10.0f; - const float noisy_diff_ = 20.0f; - std::deque history_steer_queue_; - std::deque current_steer_queue_; - float history_total_; - float current_total_; -}; - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/trigger_base.cc b/modules/data/tools/smart_recorder/trigger_base.cc deleted file mode 100644 index 8d70480da2d..00000000000 --- a/modules/data/tools/smart_recorder/trigger_base.cc +++ /dev/null @@ -1,73 +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/data/tools/smart_recorder/trigger_base.h" - -#include "cyber/common/log.h" -#include "modules/data/tools/smart_recorder/interval_pool.h" - -namespace apollo { -namespace data { - -bool TriggerBase::Init(const SmartRecordTrigger& trigger_conf) { - LockTrigger(trigger_conf); - if (trigger_obj_ == nullptr) { - AERROR << "failed to lock trigger " << GetTriggerName(); - return false; - } - return true; -} - -uint64_t TriggerBase::SecondsToNanoSeconds(const double seconds) const { - static constexpr uint64_t kSecondsToNanoSecondsFactor = 1000000000UL; - return static_cast(kSecondsToNanoSecondsFactor * seconds); -} - -void TriggerBase::LockTrigger(const SmartRecordTrigger& trigger_conf) { - for (const auto& trigger : trigger_conf.triggers()) { - if (trigger.trigger_name() == trigger_name_) { - trigger_obj_.reset(new Trigger(trigger)); - break; - } - } -} - -uint64_t TriggerBase::GetValidValueInRange(const double desired_value, - const double min_limit, - const double max_limit) const { - return SecondsToNanoSeconds(desired_value < min_limit - ? min_limit - : desired_value > max_limit ? max_limit - : desired_value); -} - -void TriggerBase::TriggerIt(const uint64_t msg_time) const { - static constexpr float kMaxBackwardTime = 80.0; - static constexpr float kMaxForwardTime = 80.0; - static constexpr uint64_t kZero = 0.0; - const uint64_t backward_time = GetValidValueInRange( - trigger_obj_->backward_time(), kZero, kMaxBackwardTime); - const uint64_t forward_time = GetValidValueInRange( - trigger_obj_->forward_time(), kZero, kMaxForwardTime); - IntervalPool::Instance()->AddInterval(msg_time - backward_time, - msg_time + forward_time); - IntervalPool::Instance()->LogIntervalEvent( - trigger_obj_->trigger_name(), trigger_obj_->description(), msg_time, - backward_time, forward_time); -} - -} // namespace data -} // namespace apollo diff --git a/modules/data/tools/smart_recorder/trigger_base.h b/modules/data/tools/smart_recorder/trigger_base.h deleted file mode 100644 index bf5b1c245d3..00000000000 --- a/modules/data/tools/smart_recorder/trigger_base.h +++ /dev/null @@ -1,67 +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 "cyber/record/record_message.h" -#include "modules/data/tools/smart_recorder/proto/smart_recorder_triggers.pb.h" - -namespace apollo { -namespace data { - -/** - * @class TriggerBase - * @brief Base class of triggers that defines interfaces - */ -class TriggerBase { - public: - TriggerBase() = default; - - // Init the trigger using configuration - virtual bool Init(const SmartRecordTrigger& trigger_conf); - - // Decide if the current trigger needs to be caught by input message, - // and if yes record the time interval - virtual void Pull(const cyber::record::RecordMessage& msg) = 0; - - // Decide if the current message needs to be restored - virtual bool ShouldRestore(const cyber::record::RecordMessage& msg) const = 0; - - const std::string& GetTriggerName() const { return trigger_name_; } - - uint64_t SecondsToNanoSeconds(const double seconds) const; - - virtual ~TriggerBase() = default; - - protected: - void TriggerIt(const uint64_t msg_time) const; - uint64_t GetValidValueInRange(const double desired_value, - const double min_limit, - const double max_limit) const; - - std::string trigger_name_; - std::unique_ptr trigger_obj_ = nullptr; - - private: - void LockTrigger(const SmartRecordTrigger& trigger_conf); -}; - -} // namespace data -} // namespace apollo diff --git a/modules/dreamview/BUILD b/modules/dreamview/BUILD index afa06b59151..624966ef4c0 100644 --- a/modules/dreamview/BUILD +++ b/modules/dreamview/BUILD @@ -42,13 +42,12 @@ install( data = [ ":dreamview_conf", ":frontend", - "cyberfile.xml", "dreamview.BUILD" ], targets = ["dreamview"], deps = [ ":pb_dreamview", - ":pb_hdrs", + ":pb_hdrs", "//modules/dreamview/backend/common:install", "//modules/dreamview/backend/hmi:install", "//modules/dreamview/backend/map:install", diff --git a/modules/dreamview/backend/simulation_world/simulation_world_service.cc b/modules/dreamview/backend/simulation_world/simulation_world_service.cc index 2540e7709d2..bec36283464 100644 --- a/modules/dreamview/backend/simulation_world/simulation_world_service.cc +++ b/modules/dreamview/backend/simulation_world/simulation_world_service.cc @@ -30,6 +30,7 @@ #include "cyber/time/clock.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/common/configs/vehicle_config_helper.h" +#include "modules/common/math/polygon2d.h" #include "modules/common/math/quaternion.h" #include "modules/common/util/map_util.h" #include "modules/common/util/points_downsampler.h" @@ -261,6 +262,14 @@ SimulationWorldService::SimulationWorldService(const MapService *map_service, auto_driving_car->set_height(vehicle_param.height()); auto_driving_car->set_width(vehicle_param.width()); auto_driving_car->set_length(vehicle_param.length()); + auto_driving_car->set_front_edge_to_center( + vehicle_param.front_edge_to_center()); + auto_driving_car->set_back_edge_to_center( + vehicle_param.back_edge_to_center()); + auto_driving_car->set_right_edge_to_center( + vehicle_param.left_edge_to_center()); + auto_driving_car->set_left_edge_to_center( + vehicle_param.right_edge_to_center()); } void SimulationWorldService::InitReaders() { @@ -418,6 +427,26 @@ void SimulationWorldService::UpdateLatencies() { UpdateLatency("control", control_command_reader_.get()); } +void SimulationWorldService::UpdateADCBoundingbox(double x, double y) { + Object *auto_driving_car = world_.mutable_auto_driving_car(); + auto_driving_car->clear_polygon_point(); + double right_x = x + auto_driving_car->left_edge_to_center(); + double left_x = x - auto_driving_car->right_edge_to_center(); + double top_y = y + auto_driving_car->front_edge_to_center(); + double bottom_y = y - auto_driving_car->back_edge_to_center(); + PolygonPoint *top_left_corner = auto_driving_car->add_polygon_point(); + PolygonPoint *top_right_corner = auto_driving_car->add_polygon_point(); + PolygonPoint *bottom_right_corner = auto_driving_car->add_polygon_point(); + PolygonPoint *bottom_left_corner = auto_driving_car->add_polygon_point(); + top_left_corner->set_x(left_x); + top_left_corner->set_y(top_y); + top_right_corner->set_x(right_x); + top_right_corner->set_y(top_y); + bottom_left_corner->set_x(left_x); + bottom_left_corner->set_y(bottom_y); + bottom_right_corner->set_x(right_x); + bottom_right_corner->set_y(bottom_y); +} void SimulationWorldService::GetWireFormatString( double radius, std::string *sim_world, std::string *sim_world_with_planning_data) { @@ -483,6 +512,10 @@ void SimulationWorldService::UpdateSimulationWorld( // message header. It is done on both the SimulationWorld object // itself and its auto_driving_car() field. auto_driving_car->set_timestamp_sec(localization.header().timestamp_sec()); + + // updates bounding box with postion + UpdateADCBoundingbox(pose.position().x() + map_service_->GetXOffset(), + pose.position().y() + map_service_->GetYOffset()); ready_to_push_.store(true); } @@ -584,6 +617,7 @@ Object &SimulationWorldService::CreateWorldObjectIfAbsent( SetObstacleType(obstacle.type(), obstacle.sub_type(), &world_obj); SetObstacleSensorMeasurements(obstacle, &world_obj); SetObstacleSource(obstacle, &world_obj); + SetObstacleDistanceToAdc(obstacle, &world_obj); } return obj_map_[id]; } @@ -672,6 +706,28 @@ void SimulationWorldService::SetObstacleSource( return; } +void SimulationWorldService::SetObstacleDistanceToAdc( + const apollo::perception::PerceptionObstacle &obstacle, + Object *world_object) { + if (world_object == nullptr) { + return; + } + std::vector obstacle_points; + std::vector adc_polygon_points; + for (auto &polygon_pt : world_object->polygon_point()) { + obstacle_points.emplace_back(polygon_pt.x(), polygon_pt.y()); + } + for (auto &polygon_pt : world_.auto_driving_car().polygon_point()) { + adc_polygon_points.emplace_back(polygon_pt.x(), polygon_pt.y()); + } + world_object->clear_distance_to_adc(); + if (obstacle_points.size() > 2 && adc_polygon_points.size() > 2) { + world_object->set_distance_to_adc(std::fabs( + apollo::common::math::Polygon2d(obstacle_points) + .DistanceTo(apollo::common::math::Polygon2d(adc_polygon_points)))); + } +} + template <> void SimulationWorldService::UpdateSimulationWorld( const PerceptionObstacles &obstacles) { diff --git a/modules/dreamview/backend/simulation_world/simulation_world_service.h b/modules/dreamview/backend/simulation_world/simulation_world_service.h index 3d5c278f888..abeedaeedfc 100644 --- a/modules/dreamview/backend/simulation_world/simulation_world_service.h +++ b/modules/dreamview/backend/simulation_world/simulation_world_service.h @@ -187,6 +187,12 @@ class SimulationWorldService { Object *world_object); void SetObstacleSource(const apollo::perception::PerceptionObstacle &obstacle, Object *world_object); + /** + * @brief Set the distance beetween the auto driving car polygon and the obstacle polygon. + */ + void SetObstacleDistanceToAdc( + const apollo::perception::PerceptionObstacle &obstacle, + Object *world_object); void UpdatePlanningTrajectory( const apollo::planning::ADCTrajectory &trajectory); void UpdateRSSInfo(const apollo::planning::ADCTrajectory &trajectory); @@ -301,6 +307,17 @@ class SimulationWorldService { */ void UpdateLatencies(); + /** + * @brief auto driving car boundingbox with localization and map offset + * use a rectangle to represent the bounding box of the auto driving car. + * eg: + * top_left_corner.x = position.x + map_xoffset / + * + auto_driving_car->right_edge_to_center + * top_left_corner.y = position.y + map_yoffset / + * + auto_driving_car->front_edge_to_center + */ + void UpdateADCBoundingbox(double x, double y); + template void DownsampleSpeedPointsByInterval(const Points &points, size_t downsampleInterval, diff --git a/modules/dreamview/backend/simulation_world/simulation_world_updater.cc b/modules/dreamview/backend/simulation_world/simulation_world_updater.cc index 6b8dfaa0492..081d4115be3 100644 --- a/modules/dreamview/backend/simulation_world/simulation_world_updater.cc +++ b/modules/dreamview/backend/simulation_world/simulation_world_updater.cc @@ -235,8 +235,6 @@ void SimulationWorldUpdater::RegisterMessageHandlers() { auto task = std::make_shared(); auto *parking_routing_task = task->mutable_parking_routing_task(); bool succeed = ConstructParkingRoutingTask(json, parking_routing_task); - // For test routing - auto routing_request = std::make_shared(); if (succeed) { task->set_task_name("parking_routing_task"); task->set_task_type(apollo::task_manager::TaskType::PARKING_ROUTING); @@ -670,23 +668,6 @@ bool SimulationWorldUpdater::ConstructRoutingRequest( << json["parkingInfo"].dump(); return false; } - if (ContainsKey(json, "cornerPoints")) { - auto point_iter = json.find("cornerPoints"); - auto *points = - requested_parking_info->mutable_corner_point()->mutable_point(); - if (point_iter != json.end() && point_iter->is_array()) { - for (size_t i = 0; i < point_iter->size(); ++i) { - auto &point = (*point_iter)[i]; - auto *p = points->Add(); - if (!ValidateCoordinate(point)) { - AERROR << "Failed to add a corner point: invalid corner point."; - return false; - } - p->set_x(static_cast(point["x"])); - p->set_y(static_cast(point["y"])); - } - } - } } AINFO << "Constructed RoutingRequest to be sent:\n" @@ -705,20 +686,10 @@ Json SimulationWorldUpdater::GetConstructRoutingRequestJson( bool SimulationWorldUpdater::ConstructParkingRoutingTask( const Json &json, ParkingRoutingTask *parking_routing_task) { - auto *routing_request = parking_routing_task->mutable_routing_request(); // set parking Space - if (!ContainsKey(json, "laneWidth")) { - AERROR << "Failed to prepare a parking routing task: " - << "lane width not found."; - return false; - } + auto *routing_request = parking_routing_task->mutable_routing_request(); bool succeed = ConstructRoutingRequest(json, routing_request); - if (succeed) { - parking_routing_task->set_lane_width( - static_cast(json["laneWidth"])); - return true; - } - return false; + return succeed; } bool SimulationWorldUpdater::ValidateCoordinate(const nlohmann::json &json) { diff --git a/modules/dreamview/conf/hmi_modes/dev_kit_close_loop.pb.txt b/modules/dreamview/conf/hmi_modes/dev_kit_close_loop.pb.txt index 080d9d6222a..e498ed4037d 100644 --- a/modules/dreamview/conf/hmi_modes/dev_kit_close_loop.pb.txt +++ b/modules/dreamview/conf/hmi_modes/dev_kit_close_loop.pb.txt @@ -94,6 +94,16 @@ modules { } } } +modules { + key: "V2X" + value: { + start_command: "nohup /apollo/bazel-bin/modules/v2x/v2x_proxy/app/v2x --flagfile=/apollo/modules/v2x/conf/v2x.conf &" + stop_command: "pkill -f \"v2x --flagfile\"" + process_monitor_config { + command_keywords: "v2x --flagfile" + } + } +} monitored_components { key: "Recorder" value: { @@ -129,16 +139,15 @@ monitored_components { monitored_components { key: "Localization" value: { - # Special LocalizationMonitor. + process { + command_keywords: "mainboard" + command_keywords: "/apollo/modules/localization/dag/dag_streaming_rtk_localization.dag" + } + channel { + name: "/apollo/localization/pose" + } } } -# Disbale ESD-CAN for a while as in some cars we are using B-CAN. -# monitored_components { -# key: "ESD-CAN" -# value: { -# # Special EsdCanMonitor. -# } -# } monitored_components { key: "Lidar 16" value: { diff --git a/modules/dreamview/conf/hmi_modes/dev_kit_debug.pb.txt b/modules/dreamview/conf/hmi_modes/dev_kit_debug.pb.txt index 6a6b7ffa6e8..4b20ec74a2a 100644 --- a/modules/dreamview/conf/hmi_modes/dev_kit_debug.pb.txt +++ b/modules/dreamview/conf/hmi_modes/dev_kit_debug.pb.txt @@ -88,19 +88,6 @@ cyber_modules { dag_files: "/apollo/modules/transform/dag/static_transform.dag" } } - -cyber_modules { - key: "SmarterEye" - value: { - dag_files: "/apollo/modules/drivers/smartereye/dag/smartereye.dag" - } -} -cyber_modules { - key: "Third Party Perception" - value: { - dag_files: "/apollo/modules/third_party_perception/dag/third_party_perception.dag" - } -} cyber_modules { key: "TaskManager" value: { @@ -117,6 +104,16 @@ modules { } } } +modules { + key: "V2X" + value: { + start_command: "nohup /apollo/bazel-bin/modules/v2x/v2x_proxy/app/v2x --flagfile=/apollo/modules/v2x/conf/v2x.conf &" + stop_command: "pkill -f \"v2x --flagfile\"" + process_monitor_config { + command_keywords: "v2x --flagfile" + } + } +} monitored_components { key: "Recorder" value: { @@ -152,16 +149,15 @@ monitored_components { monitored_components { key: "Localization" value: { - # Special LocalizationMonitor. + process { + command_keywords: "mainboard" + command_keywords: "/apollo/modules/localization/dag/dag_streaming_rtk_localization.dag" + } + channel { + name: "/apollo/localization/pose" + } } } -# Disbale ESD-CAN for a while as in some cars we are using B-CAN. -# monitored_components { -# key: "ESD-CAN" -# value: { -# # Special EsdCanMonitor. -# } -# } monitored_components { key: "Lidar 16" value: { diff --git a/modules/dreamview/conf/vehicle_data.pb.txt b/modules/dreamview/conf/vehicle_data.pb.txt index 2683a47f9c4..9919aad2e02 100644 --- a/modules/dreamview/conf/vehicle_data.pb.txt +++ b/modules/dreamview/conf/vehicle_data.pb.txt @@ -230,3 +230,7 @@ data_files { source_path: "v2x_conf" dest_path: "/apollo/modules/v2x/conf" } +data_files { + source_path: "perception_model_conf" + dest_path: "/apollo/modules/perception/production/data/perception" +} diff --git a/modules/dreamview/cyberfile.xml b/modules/dreamview/cyberfile.xml deleted file mode 100644 index 26056bba322..00000000000 --- a/modules/dreamview/cyberfile.xml +++ /dev/null @@ -1,40 +0,0 @@ - - dreamview - local - - Dreamview or Apollo's HMI module provides a web application that helps developers visualize the output of - other relevant autonomous driving modules, e.g. the vehicle's planning trajectory, car localization, chassis status etc. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - - cyber-dev - common-dev - map-dev - transform-dev - common-msgs-dev - - 3rd-gflags-dev - 3rd-gtest-dev - 3rd-absl-dev - 3rd-boost-dev - 3rd-civetweb-dev - 3rd-opencv-dev - 3rd-glog-dev - 3rd-nlohmann-json-dev - 3rd-eigen3-dev - 3rd-protobuf-dev - - 3rd-pcl-dev - - 3rd-rules-proto-dev - - //modules/dreamview - - diff --git a/modules/dreamview/frontend/dist/138.bundle.js.map b/modules/dreamview/frontend/dist/138.bundle.js.map index c194cd51c70..8d64dd142de 100644 --- a/modules/dreamview/frontend/dist/138.bundle.js.map +++ b/modules/dreamview/frontend/dist/138.bundle.js.map @@ -1 +1 @@ -{"version":3,"file":"./138.bundle.js","mappings":"4XAAA,e,ygCAEqBA,EAAAA,WACnB,aAAc,UACZC,KAAKC,IAAM,KACXD,KAAKE,SAAW,GAChBF,KAAKG,mBAAoB,CAC1B,C,uCAED,WACE,OAAoB,OAAbH,KAAKC,KAAgBG,OAAOC,KAAKL,KAAKC,KAAKK,OAAS,CAC5D,G,qBAED,SAAQC,EAAWC,GACjBR,KAAKC,IAAM,IAAIQ,KAAKC,IAAIF,EAAgB,CAAEG,gBAAgB,IAE1DX,KAAKC,IAAIW,wBACTZ,KAAKC,IAAIY,WACP,IAAIJ,KAAKK,eAAe,CACtBC,OAAQC,qBACRC,KAAMC,iCAGVlB,KAAKC,IAAIY,WACP,IAAIJ,KAAKU,kBAAkB,CACzBJ,OAAQK,yBACRH,KAAMC,8BACNG,mBAAmB,IAGxB,G,uBAED,SAAUC,GACJtB,KAAKG,kBACPH,KAAKC,IAAIsB,UAAUD,IAEnBtB,KAAKC,IAAIuB,cAAcF,EAAO,IAC9BtB,KAAKG,mBAAoB,EAE5B,G,qBAED,SAAQsB,GACNzB,KAAKC,IAAIyB,QAAQD,EAClB,G,6BAED,SAAgBE,EAAWC,GACzB5B,KAAKC,IAAI4B,iBAAiBF,GAAW,SAACG,GACpC,IAAMC,EAAgBD,EAAMR,MAC5BM,EAAgBG,EACjB,GACF,G,yBAED,YAA0B,IAAZC,EAAY,EAAZA,IAAKC,EAAO,EAAPA,IACjB,OAAO,IAAIxB,KAAKyB,MAAMD,EAAKD,EAC5B,G,0BAED,SAAaV,EAAOa,GAAyB,IAAlBC,IAAkB,yDACvCC,EAAQ,KACRF,IACFE,EAAQ,IAAI5B,KAAK6B,MAAMH,EAAO,CAC5Bb,MAAAA,EACAiB,OAAQ,IAAI9B,KAAK+B,KAAK,IAAK,OAI/B,IAAMC,EAAS,IAAIhC,KAAKiC,OAAOpB,EAAO,CACpCe,MAAAA,EACAM,eAAgBP,EAChBQ,SAAU,IAIZ,OAFAH,EAAOI,SAASR,GAChBrC,KAAKC,IAAI6C,WAAWL,GACbA,CACR,G,4BAED,SAAeM,EAAMC,GAAoC,IAA7BC,EAA6B,uDAAnB,EAAKC,EAAc,uDAAL,EAC5CC,EAAU,CACdC,UAAU,EACVC,YAAaL,EACbM,cAAeL,EACfM,aAAcL,GAEVM,EAAW,IAAI/C,KAAKgD,SAASV,EAAMI,GAEzC,OADAnD,KAAKC,IAAI6C,WAAWU,GACbA,CACR,G,2BAED,YAEG,IADDE,EACC,EADDA,KAAMC,EACL,EADKA,IAAKX,EACV,EADUA,MAAOY,EACjB,EADiBA,QAASC,EAC1B,EAD0BA,QAASC,EACnC,EADmCA,eAE9BC,EAAY,IAAI5C,EACpBuC,EACAC,EACAX,EACA,IAAIvC,KAAK+B,KAAKoB,EAASC,GACvBC,GAEF9D,KAAKC,IAAIY,WAAWkD,GACpB/D,KAAKE,SAAS8D,KAAKD,EACpB,G,6BAED,WAAkB,WAChB/D,KAAKE,SAAS+D,SAAQ,SAACC,GACrB,EAAKjE,IAAIkE,cAAcD,EACxB,GACF,G,4BAED,WAAiB,WACflE,KAAKE,SAAS+D,SAAQ,SAACC,GACrB,EAAKjE,IAAIY,WAAWqD,EACrB,GACF,G,+BAED,SAAkBzB,GAChB,OAAOA,EAAO2B,aACf,G,4BAED,SAAeZ,EAAUa,GACvBb,EAASc,QAAQD,EAClB,G,4BAED,SAAeb,GACbxD,KAAKC,IAAIsE,cAAcf,EACxB,G,mCAED,YAAkC,I,IAAA,G,EAAA,E,4CAAA,I,gxBAAXvB,EAAW,KAAND,EAAM,KAChC,OAAO,EAAAwC,EAAAA,eAAcvC,EAAKD,EAC3B,K,EA7HkBjC,G,gBAgIfoB,EAAAA,SAAAA,I,wRAA0BV,KAAKgE,S,8ZACnC,WAAYf,EAAMC,EAAKX,EAAOT,EAAQuB,GAAyB,2CAANY,EAAM,iCAANA,EAAM,yBAC7D,+BAASA,KACJC,cAAgB3D,qBACrB,EAAK4D,cAAgBrC,EACrB,EAAKuB,eAAiBA,EACtB,EAAK3B,MAAQwB,EACb,EAAKD,KAAOA,EACZ,EAAKmB,gBAAkB7B,EAPsC,CAQ9D,C,oCAED,SAAW/C,GAAK,WACR6E,EAAaC,SAASC,cAAc,OAGpCC,EAAYF,SAASC,cAAc,OACzCC,EAAUC,MAAML,gBAAkB7E,KAAK6E,gBACvCI,EAAUC,MAAMC,OAAS,iBACzBF,EAAUC,MAAME,aAAe,MAC/BH,EAAUC,MAAMG,UAAY,2BAC5BJ,EAAUC,MAAMI,OAAS,UACzBL,EAAUC,MAAMK,aAAe,OAC/BN,EAAUC,MAAMM,UAAY,SAC5BP,EAAU9C,MAAQnC,KAAKmC,MACvB2C,EAAWW,YAAYR,GAGvB,IAAMS,EAAcX,SAASC,cAAc,OAgB3C,OAfAU,EAAYR,MAAMlC,MAAQ,gBAC1B0C,EAAYR,MAAMS,WAAa,0BAC/BD,EAAYR,MAAMU,SAAW,OAC7BF,EAAYR,MAAMW,WAAa,OAC/BH,EAAYR,MAAMY,YAAc,MAChCJ,EAAYR,MAAMa,aAAe,MACjCL,EAAYM,UAAYhG,KAAK0D,KAC7BuB,EAAUQ,YAAYC,GAEtBzF,EAAIgG,eAAeR,YAAYX,GAE/BG,EAAUpD,iBAAiB,SAAS,WAClC,EAAKiC,eAAe4B,EACrB,IAEMZ,CACR,K,EA5CG3D,E","sources":["webpack:///./components/Navigation/BaiduMapAdapter.js"],"sourcesContent":["import { WGS84ToBD09LL } from 'utils/coordinate_converter';\n\nexport default class BaiduMapAdapter {\n constructor() {\n this.map = null;\n this.controls = [];\n this.initializedCenter = false;\n }\n\n isInitialized() {\n return this.map !== null && Object.keys(this.map).length > 0;\n }\n\n loadMap(initPoint, divElementName) {\n this.map = new BMap.Map(divElementName, { enableMapClick: false });\n\n this.map.enableScrollWheelZoom();\n this.map.addControl(\n new BMap.MapTypeControl({\n anchor: BMAP_ANCHOR_TOP_LEFT,\n type: BMAP_NAVIGATION_CONTROL_SMALL,\n }),\n );\n this.map.addControl(\n new BMap.NavigationControl({\n anchor: BMAP_ANCHOR_BOTTOM_RIGHT,\n type: BMAP_NAVIGATION_CONTROL_SMALL,\n enableGeolocation: false,\n }),\n );\n }\n\n setCenter(point) {\n if (this.initializedCenter) {\n this.map.setCenter(point);\n } else {\n this.map.centerAndZoom(point, 19);\n this.initializedCenter = true;\n }\n }\n\n setZoom(zoom) {\n this.map.setZoom(zoom);\n }\n\n addEventHandler(eventName, handlerFunction) {\n this.map.addEventListener(eventName, (event) => {\n const clickedLatLng = event.point;\n handlerFunction(clickedLatLng);\n });\n }\n\n createPoint({ lat, lng }) {\n return new BMap.Point(lng, lat);\n }\n\n createMarker(point, title, draggable = true) {\n let label = null;\n if (title) {\n label = new BMap.Label(title, {\n point,\n offset: new BMap.Size(15, -15),\n });\n }\n\n const marker = new BMap.Marker(point, {\n label,\n enableDragging: draggable,\n rotation: 5,\n });\n marker.setLabel(label);\n this.map.addOverlay(marker);\n return marker;\n }\n\n createPolyline(path, color, opacity = 1.0, weight = 2.0) {\n const options = {\n geodesic: true,\n strokeColor: color,\n strokeOpacity: opacity,\n strokeWeight: weight,\n };\n const polyline = new BMap.Polyline(path, options);\n this.map.addOverlay(polyline);\n return polyline;\n }\n\n createControl({\n text, tip, color, offsetX, offsetY, onClickHandler,\n }) {\n const myControl = new NavigationControl(\n text,\n tip,\n color,\n new BMap.Size(offsetX, offsetY),\n onClickHandler,\n );\n this.map.addControl(myControl);\n this.controls.push(myControl);\n }\n\n disableControls() {\n this.controls.forEach((control) => {\n this.map.removeControl(control);\n });\n }\n\n enableControls() {\n this.controls.forEach((control) => {\n this.map.addControl(control);\n });\n }\n\n getMarkerPosition(marker) {\n return marker.getPosition();\n }\n\n updatePolyline(polyline, newPath) {\n polyline.setPath(newPath);\n }\n\n removePolyline(polyline) {\n this.map.removeOverlay(polyline);\n }\n\n applyCoordinateOffset([lng, lat]) {\n return WGS84ToBD09LL(lng, lat);\n }\n}\n\nclass NavigationControl extends BMap.Control {\n constructor(text, tip, color, offset, onClickHandler, ...args) {\n super(...args);\n this.defaultAnchor = BMAP_ANCHOR_TOP_LEFT;\n this.defaultOffset = offset;\n this.onClickHandler = onClickHandler;\n this.title = tip;\n this.text = text;\n this.backgroundColor = color;\n }\n\n initialize(map) {\n const controlDiv = document.createElement('div');\n\n // Set CSS for the control border.\n const controlUI = document.createElement('div');\n controlUI.style.backgroundColor = this.backgroundColor;\n controlUI.style.border = '2px solid #fff';\n controlUI.style.borderRadius = '3px';\n controlUI.style.boxShadow = '0 2px 6px rgba(0,0,0,.3)';\n controlUI.style.cursor = 'pointer';\n controlUI.style.marginBottom = '22px';\n controlUI.style.textAlign = 'center';\n controlUI.title = this.title;\n controlDiv.appendChild(controlUI);\n\n // // Set CSS for the control interior.\n const controlText = document.createElement('div');\n controlText.style.color = 'rgb(25,25,25)';\n controlText.style.fontFamily = 'Roboto,Arial,sans-serif';\n controlText.style.fontSize = '16px';\n controlText.style.lineHeight = '38px';\n controlText.style.paddingLeft = '5px';\n controlText.style.paddingRight = '5px';\n controlText.innerHTML = this.text;\n controlUI.appendChild(controlText);\n\n map.getContainer().appendChild(controlDiv);\n\n controlUI.addEventListener('click', () => {\n this.onClickHandler(controlText);\n });\n\n return controlDiv;\n }\n}\n"],"names":["BaiduMapAdapter","this","map","controls","initializedCenter","Object","keys","length","initPoint","divElementName","BMap","Map","enableMapClick","enableScrollWheelZoom","addControl","MapTypeControl","anchor","BMAP_ANCHOR_TOP_LEFT","type","BMAP_NAVIGATION_CONTROL_SMALL","NavigationControl","BMAP_ANCHOR_BOTTOM_RIGHT","enableGeolocation","point","setCenter","centerAndZoom","zoom","setZoom","eventName","handlerFunction","addEventListener","event","clickedLatLng","lat","lng","Point","title","draggable","label","Label","offset","Size","marker","Marker","enableDragging","rotation","setLabel","addOverlay","path","color","opacity","weight","options","geodesic","strokeColor","strokeOpacity","strokeWeight","polyline","Polyline","text","tip","offsetX","offsetY","onClickHandler","myControl","push","forEach","control","removeControl","getPosition","newPath","setPath","removeOverlay","WGS84ToBD09LL","Control","args","defaultAnchor","defaultOffset","backgroundColor","controlDiv","document","createElement","controlUI","style","border","borderRadius","boxShadow","cursor","marginBottom","textAlign","appendChild","controlText","fontFamily","fontSize","lineHeight","paddingLeft","paddingRight","innerHTML","getContainer"],"sourceRoot":""} \ No newline at end of file +{"version":3,"file":"./138.bundle.js","mappings":"4XAAA,e,ygCAEqBA,EAAAA,WACnB,aAAc,UACZC,KAAKC,IAAM,KACXD,KAAKE,SAAW,GAChBF,KAAKG,mBAAoB,E,uCAG3B,WACE,OAAoB,OAAbH,KAAKC,KAAgBG,OAAOC,KAAKL,KAAKC,KAAKK,OAAS,I,qBAG7D,SAAQC,EAAWC,GACjBR,KAAKC,IAAM,IAAIQ,KAAKC,IAAIF,EAAgB,CAAEG,gBAAgB,IAE1DX,KAAKC,IAAIW,wBACTZ,KAAKC,IAAIY,WACP,IAAIJ,KAAKK,eAAe,CACtBC,OAAQC,qBACRC,KAAMC,iCAGVlB,KAAKC,IAAIY,WACP,IAAIJ,KAAKU,kBAAkB,CACzBJ,OAAQK,yBACRH,KAAMC,8BACNG,mBAAmB,O,uBAKzB,SAAUC,GACJtB,KAAKG,kBACPH,KAAKC,IAAIsB,UAAUD,IAEnBtB,KAAKC,IAAIuB,cAAcF,EAAO,IAC9BtB,KAAKG,mBAAoB,K,qBAI7B,SAAQsB,GACNzB,KAAKC,IAAIyB,QAAQD,K,6BAGnB,SAAgBE,EAAWC,GACzB5B,KAAKC,IAAI4B,iBAAiBF,GAAW,SAACG,GACpC,IAAMC,EAAgBD,EAAMR,MAC5BM,EAAgBG,Q,yBAIpB,YAA0B,IAAZC,EAAY,EAAZA,IAAKC,EAAO,EAAPA,IACjB,OAAO,IAAIxB,KAAKyB,MAAMD,EAAKD,K,0BAG7B,SAAaV,EAAOa,GAAyB,IAAlBC,IAAkB,yDACvCC,EAAQ,KACRF,IACFE,EAAQ,IAAI5B,KAAK6B,MAAMH,EAAO,CAC5Bb,MAAAA,EACAiB,OAAQ,IAAI9B,KAAK+B,KAAK,IAAK,OAI/B,IAAMC,EAAS,IAAIhC,KAAKiC,OAAOpB,EAAO,CACpCe,MAAAA,EACAM,eAAgBP,EAChBQ,SAAU,IAIZ,OAFAH,EAAOI,SAASR,GAChBrC,KAAKC,IAAI6C,WAAWL,GACbA,I,4BAGT,SAAeM,EAAMC,GAAoC,IAA7BC,EAA6B,uDAAnB,EAAKC,EAAc,uDAAL,EAC5CC,EAAU,CACdC,UAAU,EACVC,YAAaL,EACbM,cAAeL,EACfM,aAAcL,GAEVM,EAAW,IAAI/C,KAAKgD,SAASV,EAAMI,GAEzC,OADAnD,KAAKC,IAAI6C,WAAWU,GACbA,I,2BAGT,YAEG,IADDE,EACC,EADDA,KAAMC,EACL,EADKA,IAAKX,EACV,EADUA,MAAOY,EACjB,EADiBA,QAASC,EAC1B,EAD0BA,QAASC,EACnC,EADmCA,eAE9BC,EAAY,IAAI5C,EACpBuC,EACAC,EACAX,EACA,IAAIvC,KAAK+B,KAAKoB,EAASC,GACvBC,GAEF9D,KAAKC,IAAIY,WAAWkD,GACpB/D,KAAKE,SAAS8D,KAAKD,K,6BAGrB,WAAkB,WAChB/D,KAAKE,SAAS+D,SAAQ,SAACC,GACrB,EAAKjE,IAAIkE,cAAcD,Q,4BAI3B,WAAiB,WACflE,KAAKE,SAAS+D,SAAQ,SAACC,GACrB,EAAKjE,IAAIY,WAAWqD,Q,+BAIxB,SAAkBzB,GAChB,OAAOA,EAAO2B,gB,4BAGhB,SAAeZ,EAAUa,GACvBb,EAASc,QAAQD,K,4BAGnB,SAAeb,GACbxD,KAAKC,IAAIsE,cAAcf,K,mCAGzB,YAAkC,I,IAAA,G,EAAA,E,4CAAA,I,gxBAAXvB,EAAW,KAAND,EAAM,KAChC,OAAO,EAAAwC,EAAAA,eAAcvC,EAAKD,O,EA5HTjC,G,gBAgIfoB,EAAAA,SAAAA,I,wRAA0BV,KAAKgE,S,8ZACnC,WAAYf,EAAMC,EAAKX,EAAOT,EAAQuB,GAAyB,2CAANY,EAAM,iCAANA,EAAM,yBAC7D,+BAASA,KACJC,cAAgB3D,qBACrB,EAAK4D,cAAgBrC,EACrB,EAAKuB,eAAiBA,EACtB,EAAK3B,MAAQwB,EACb,EAAKD,KAAOA,EACZ,EAAKmB,gBAAkB7B,EAPsC,E,oCAU/D,SAAW/C,GAAK,WACR6E,EAAaC,SAASC,cAAc,OAGpCC,EAAYF,SAASC,cAAc,OACzCC,EAAUC,MAAML,gBAAkB7E,KAAK6E,gBACvCI,EAAUC,MAAMC,OAAS,iBACzBF,EAAUC,MAAME,aAAe,MAC/BH,EAAUC,MAAMG,UAAY,2BAC5BJ,EAAUC,MAAMI,OAAS,UACzBL,EAAUC,MAAMK,aAAe,OAC/BN,EAAUC,MAAMM,UAAY,SAC5BP,EAAU9C,MAAQnC,KAAKmC,MACvB2C,EAAWW,YAAYR,GAGvB,IAAMS,EAAcX,SAASC,cAAc,OAgB3C,OAfAU,EAAYR,MAAMlC,MAAQ,gBAC1B0C,EAAYR,MAAMS,WAAa,0BAC/BD,EAAYR,MAAMU,SAAW,OAC7BF,EAAYR,MAAMW,WAAa,OAC/BH,EAAYR,MAAMY,YAAc,MAChCJ,EAAYR,MAAMa,aAAe,MACjCL,EAAYM,UAAYhG,KAAK0D,KAC7BuB,EAAUQ,YAAYC,GAEtBzF,EAAIgG,eAAeR,YAAYX,GAE/BG,EAAUpD,iBAAiB,SAAS,WAClC,EAAKiC,eAAe4B,MAGfZ,M,EA3CL3D","sources":["webpack:///./components/Navigation/BaiduMapAdapter.js"],"sourcesContent":["import { WGS84ToBD09LL } from 'utils/coordinate_converter';\n\nexport default class BaiduMapAdapter {\n constructor() {\n this.map = null;\n this.controls = [];\n this.initializedCenter = false;\n }\n\n isInitialized() {\n return this.map !== null && Object.keys(this.map).length > 0;\n }\n\n loadMap(initPoint, divElementName) {\n this.map = new BMap.Map(divElementName, { enableMapClick: false });\n\n this.map.enableScrollWheelZoom();\n this.map.addControl(\n new BMap.MapTypeControl({\n anchor: BMAP_ANCHOR_TOP_LEFT,\n type: BMAP_NAVIGATION_CONTROL_SMALL,\n }),\n );\n this.map.addControl(\n new BMap.NavigationControl({\n anchor: BMAP_ANCHOR_BOTTOM_RIGHT,\n type: BMAP_NAVIGATION_CONTROL_SMALL,\n enableGeolocation: false,\n }),\n );\n }\n\n setCenter(point) {\n if (this.initializedCenter) {\n this.map.setCenter(point);\n } else {\n this.map.centerAndZoom(point, 19);\n this.initializedCenter = true;\n }\n }\n\n setZoom(zoom) {\n this.map.setZoom(zoom);\n }\n\n addEventHandler(eventName, handlerFunction) {\n this.map.addEventListener(eventName, (event) => {\n const clickedLatLng = event.point;\n handlerFunction(clickedLatLng);\n });\n }\n\n createPoint({ lat, lng }) {\n return new BMap.Point(lng, lat);\n }\n\n createMarker(point, title, draggable = true) {\n let label = null;\n if (title) {\n label = new BMap.Label(title, {\n point,\n offset: new BMap.Size(15, -15),\n });\n }\n\n const marker = new BMap.Marker(point, {\n label,\n enableDragging: draggable,\n rotation: 5,\n });\n marker.setLabel(label);\n this.map.addOverlay(marker);\n return marker;\n }\n\n createPolyline(path, color, opacity = 1.0, weight = 2.0) {\n const options = {\n geodesic: true,\n strokeColor: color,\n strokeOpacity: opacity,\n strokeWeight: weight,\n };\n const polyline = new BMap.Polyline(path, options);\n this.map.addOverlay(polyline);\n return polyline;\n }\n\n createControl({\n text, tip, color, offsetX, offsetY, onClickHandler,\n }) {\n const myControl = new NavigationControl(\n text,\n tip,\n color,\n new BMap.Size(offsetX, offsetY),\n onClickHandler,\n );\n this.map.addControl(myControl);\n this.controls.push(myControl);\n }\n\n disableControls() {\n this.controls.forEach((control) => {\n this.map.removeControl(control);\n });\n }\n\n enableControls() {\n this.controls.forEach((control) => {\n this.map.addControl(control);\n });\n }\n\n getMarkerPosition(marker) {\n return marker.getPosition();\n }\n\n updatePolyline(polyline, newPath) {\n polyline.setPath(newPath);\n }\n\n removePolyline(polyline) {\n this.map.removeOverlay(polyline);\n }\n\n applyCoordinateOffset([lng, lat]) {\n return WGS84ToBD09LL(lng, lat);\n }\n}\n\nclass NavigationControl extends BMap.Control {\n constructor(text, tip, color, offset, onClickHandler, ...args) {\n super(...args);\n this.defaultAnchor = BMAP_ANCHOR_TOP_LEFT;\n this.defaultOffset = offset;\n this.onClickHandler = onClickHandler;\n this.title = tip;\n this.text = text;\n this.backgroundColor = color;\n }\n\n initialize(map) {\n const controlDiv = document.createElement('div');\n\n // Set CSS for the control border.\n const controlUI = document.createElement('div');\n controlUI.style.backgroundColor = this.backgroundColor;\n controlUI.style.border = '2px solid #fff';\n controlUI.style.borderRadius = '3px';\n controlUI.style.boxShadow = '0 2px 6px rgba(0,0,0,.3)';\n controlUI.style.cursor = 'pointer';\n controlUI.style.marginBottom = '22px';\n controlUI.style.textAlign = 'center';\n controlUI.title = this.title;\n controlDiv.appendChild(controlUI);\n\n // // Set CSS for the control interior.\n const controlText = document.createElement('div');\n controlText.style.color = 'rgb(25,25,25)';\n controlText.style.fontFamily = 'Roboto,Arial,sans-serif';\n controlText.style.fontSize = '16px';\n controlText.style.lineHeight = '38px';\n controlText.style.paddingLeft = '5px';\n controlText.style.paddingRight = '5px';\n controlText.innerHTML = this.text;\n controlUI.appendChild(controlText);\n\n map.getContainer().appendChild(controlDiv);\n\n controlUI.addEventListener('click', () => {\n this.onClickHandler(controlText);\n });\n\n return controlDiv;\n }\n}\n"],"names":["BaiduMapAdapter","this","map","controls","initializedCenter","Object","keys","length","initPoint","divElementName","BMap","Map","enableMapClick","enableScrollWheelZoom","addControl","MapTypeControl","anchor","BMAP_ANCHOR_TOP_LEFT","type","BMAP_NAVIGATION_CONTROL_SMALL","NavigationControl","BMAP_ANCHOR_BOTTOM_RIGHT","enableGeolocation","point","setCenter","centerAndZoom","zoom","setZoom","eventName","handlerFunction","addEventListener","event","clickedLatLng","lat","lng","Point","title","draggable","label","Label","offset","Size","marker","Marker","enableDragging","rotation","setLabel","addOverlay","path","color","opacity","weight","options","geodesic","strokeColor","strokeOpacity","strokeWeight","polyline","Polyline","text","tip","offsetX","offsetY","onClickHandler","myControl","push","forEach","control","removeControl","getPosition","newPath","setPath","removeOverlay","WGS84ToBD09LL","Control","args","defaultAnchor","defaultOffset","backgroundColor","controlDiv","document","createElement","controlUI","style","border","borderRadius","boxShadow","cursor","marginBottom","textAlign","appendChild","controlText","fontFamily","fontSize","lineHeight","paddingLeft","paddingRight","innerHTML","getContainer"],"sourceRoot":""} \ No newline at end of file diff --git a/modules/dreamview/frontend/dist/734.bundle.js.map b/modules/dreamview/frontend/dist/734.bundle.js.map index 17253d3dd0e..25a37b1aec3 100644 --- a/modules/dreamview/frontend/dist/734.bundle.js.map +++ b/modules/dreamview/frontend/dist/734.bundle.js.map @@ -1 +1 @@ -{"version":3,"file":"./734.bundle.js","mappings":"4XAAA,I,EAAA,G,EAAA,W,2BAEA,W,mzBAEqBA,EAAAA,SAAAA,I,iyBACnB,WACE,OACQ,+BAAKC,QAAQ,aACT,oCACI,gCAAMC,EAAE,mBAAmBC,GAAG,MAC9B,gCAAMD,EAAE,uBAAuBC,GAAG,MAClC,gCAAMD,EAAE,aAAaC,GAAG,OAE5B,+BAAKC,UAAU,KAAKC,QAAQ,KAAKC,KAAK,YACtC,+BAAKF,UAAU,KAAKG,YAAY,IAAIC,OAAO,UAAUC,YAAY,MACjE,+BAAKL,UAAU,KAAKG,YAAY,IAAIC,OAAO,UAAUC,YAAY,MAG9E,G,+BAED,WACE,OACQ,+BAAKR,QAAQ,aACT,oCACI,gCAAMC,EAAE,mBAAmBC,GAAG,MAC9B,gCAAMD,EAAE,uBAAuBC,GAAG,MAClC,gCAAMD,EAAE,aAAaC,GAAG,OAE5B,+BAAKC,UAAU,KAAKC,QAAQ,KAAKC,KAAK,YACtC,+BAAKF,UAAU,KAAKG,YAAY,IAAIC,OAAO,UAAUC,YAAY,MACjE,+BAAKL,UAAU,KAAKG,YAAY,IAAIC,OAAO,UAAUC,YAAY,MAG9E,G,oBAED,WACE,MAA0BC,KAAKC,MAAvBC,EAAR,EAAQA,KAAMC,EAAd,EAAcA,QAEVC,EAAO,KACX,OAAQF,GACN,KAAKG,EAAAA,SAASC,KACZF,EAAOJ,KAAKO,oBACZ,MACF,KAAKF,EAAAA,SAASG,QACZJ,EAAOJ,KAAKS,oBACZ,MACF,QACEC,QAAQC,MAAM,6BAA8BT,GAIhD,OACQ,+BAAKU,UAAU,wBAAwBT,QAASA,GAC3CC,EAGd,M,sEApDkBd,CAA4BuB,EAAAA,QAAMC,e,kVCJvD,kBAEA,cACA,cACA,WACA,cAEA,c,2wBAEqBC,EAAAA,SAAAA,I,6rBACnB,WAAYd,GAAO,MAKjB,G,4FALiB,UACjB,cAAMA,IAEDe,oBAAsB,EAAKA,oBAAoBC,KAAzB,OAEtBC,EAAAA,QAAcC,aAAc,CAC/B,IAAIC,EAAS,WACXV,QAAQW,IAAI,yBACb,EACiC,aAA9BC,WAAWC,WAAWC,IAExBC,OAAOC,QAAU,EAAKV,oBACiB,cAA9BM,WAAWC,WAAWC,MAE/BJ,EAAS,EAAKJ,sBAGhB,EAAAW,EAAAA,SAAgB,CACdC,IAAKN,WAAWC,WAAWM,UAC3BT,OAAAA,EACAU,QAAS,WACPpB,QAAQW,IAAI,yBACb,GAEJ,CAxBgB,QAyBlB,C,8CAED,WACMH,EAAAA,QAAcC,cAChBnB,KAAKgB,qBAER,G,gCAED,WACE,MAAqChB,KAAKC,MAAlC8B,EAAR,EAAQA,mBAAoBC,EAA5B,EAA4BA,KAExBD,GAAsBC,IAAS3B,EAAAA,SAASC,KAC1CY,EAAAA,QAAce,iBAEdf,EAAAA,QAAcgB,iBAEjB,G,iCAED,WACE,SAAO,YAAyBZ,WAAWC,WAAWC,IAAtD,YAAoEW,MAClE,SAACC,GACC,IACMC,EAAa,IAAIC,EADCF,EAAgB,SAExClB,EAAAA,QAAcC,cAAe,EAC7BD,EAAAA,QAAcqB,WAAWC,EAAAA,QAAIH,GAC7BnB,EAAAA,QAAcgB,iBACf,GAEJ,G,kCAED,WACEhB,EAAAA,QAAcuB,OACf,G,oBAED,WACE,MAEIzC,KAAKC,MADPyC,EADF,EACEA,MAAOC,EADT,EACSA,OAAQX,EADjB,EACiBA,KAAMY,EADvB,EACuBA,SAGvB,MAAK,CAAC,YAAa,YAAYC,SAASvB,WAAWC,WAAWC,KAMtD,+BAAKsB,YAAY,aAAalC,UAAU,kBAAkBmC,MAAO,CAAEL,MAAAA,EAAOC,OAAAA,IACtE,+BAAKlD,GAAG,eACR,wBAAC,UAAD,CAAqBS,KAAM8B,EAAM7B,QAASyC,MAPpDlC,QAAQC,MAAR,kBAAyBW,WAAWC,WAAWC,IAA/C,uBACO,KASV,M,sEA5EkBT,CAAmBF,EAAAA,QAAMmC,W,mGCT/B,YAAmD,IAAxBpB,EAAwB,EAAxBA,IAAKR,EAAmB,EAAnBA,OAAQU,EAAW,EAAXA,QAC/CmB,EAASC,SAASC,cAAc,UACtCF,EAAOG,IAAMxB,EACbqB,EAAO/C,KAAO,kBACd+C,EAAOI,OAAQ,EACfJ,EAAOK,OAASlC,EAChB6B,EAAOM,QAAUzB,EACjBoB,SAASM,KAAKC,YAAYR,EAC3B,C,kBCRD,IAAIzB,EAAM,CACT,oBAAqB,CACpB,MACA,KAED,qBAAsB,CACrB,MACA,MAGF,SAASkC,EAAoBC,GAC5B,IAAIC,EAAoBC,EAAErC,EAAKmC,GAC9B,OAAOG,QAAQC,UAAU5B,MAAK,KAC7B,IAAI6B,EAAI,IAAIC,MAAM,uBAAyBN,EAAM,KAEjD,MADAK,EAAEE,KAAO,mBACHF,CAAC,IAIT,IAAIG,EAAM3C,EAAImC,GAAMlE,EAAK0E,EAAI,GAC7B,OAAOP,EAAoBI,EAAEG,EAAI,IAAIhC,MAAK,IAClCyB,EAAoBnE,IAE7B,CACAiE,EAAoBU,KAAO,IAAOC,OAAOD,KAAK5C,GAC9CkC,EAAoBjE,GAAK,MACzB6E,EAAOC,QAAUb,C","sources":["webpack:///./components/Navigation/WindowResizeControl.js","webpack:///./components/Navigation/index.js","webpack:///./utils/script_loader.js","webpack:///./components/Navigation/ lazy ^\\.\\/.*Adapter$ namespace object"],"sourcesContent":["import React from 'react';\n\nimport { MAP_SIZE } from 'store/dimension';\n\nexport default class WindowResizeControl extends React.PureComponent {\n getMinimizingIcon() {\n return (\n \n \n \n \n \n \n \n \n \n \n );\n }\n\n getMaximizingIcon() {\n return (\n \n \n \n \n \n \n \n \n \n \n );\n }\n\n render() {\n const { type, onClick } = this.props;\n\n let icon = null;\n switch (type) {\n case MAP_SIZE.FULL:\n icon = this.getMinimizingIcon();\n break;\n case MAP_SIZE.DEFAULT:\n icon = this.getMaximizingIcon();\n break;\n default:\n console.error('Unknown window size found:', type);\n break;\n }\n\n return (\n
\n {icon}\n
\n );\n }\n}\n","import React from 'react';\n\nimport MAP_NAVIGATOR from 'components/Navigation/MapNavigator';\nimport WS from 'store/websocket';\nimport { MAP_SIZE } from 'store/dimension';\nimport loadScriptAsync from 'utils/script_loader';\n\nimport WindowResizeControl from 'components/Navigation/WindowResizeControl';\n\nexport default class Navigation extends React.Component {\n constructor(props) {\n super(props);\n\n this.scriptOnLoadHandler = this.scriptOnLoadHandler.bind(this);\n\n if (!MAP_NAVIGATOR.mapAPILoaded) {\n let onLoad = () => {\n console.log('Map API script loaded.');\n };\n if (PARAMETERS.navigation.map === 'BaiduMap') {\n // For Baidu Map, the callback function is set in the window Object level\n window.initMap = this.scriptOnLoadHandler;\n } else if (PARAMETERS.navigation.map === 'GoogleMap') {\n // For Google Map, the callback function is set from the ') - html = doc.getvalue() - return html - - -def utm2latlon(x, y, pzone=10): - """ - convert the utm x y to lat and lon - """ - projector2 = pyproj.Proj(proj='utm', zone=pzone, ellps='WGS84') - lon, lat = projector2(x, y, inverse=True) - return lat, lon - - -def run(gmap_key, map_file, utm_zone): - """ - read and process map file - """ - map_pb = map_pb2.Map() - proto_utils.get_pb_from_file(map_file, map_pb) - - left_boundaries = [] - right_boundaries = [] - center_lat = None - center_lon = None - for lane in map_pb.lane: - for curve in lane.left_boundary.curve.segment: - if curve.HasField('line_segment'): - left_boundary = [] - for p in curve.line_segment.point: - point = {} - lat, lng = utm2latlon(p.x, p.y, utm_zone) - if center_lat is None: - center_lat = lat - if center_lon is None: - center_lon = lng - point['lat'] = lat - point['lng'] = lng - left_boundary.append(point) - left_boundaries.append(left_boundary) - for curve in lane.right_boundary.curve.segment: - if curve.HasField('line_segment'): - right_boundary = [] - for p in curve.line_segment.point: - point = {} - lat, lng = utm2latlon(p.x, p.y, utm_zone) - point['lat'] = lat - point['lng'] = lng - right_boundary.append(point) - right_boundaries.append(right_boundary) - - html = generate(gmap_key, left_boundaries, right_boundaries, center_lat, - center_lon) - - with open('gmap.html', 'w') as file: - file.write(html) - - -if __name__ == "__main__": - parser = argparse.ArgumentParser( - description="Mapshow is a tool to display hdmap info on a map.", - prog="mapshow.py") - - parser.add_argument( - "-m", "--map", action="store", type=str, required=True, - help="Specify the HDMap file in txt or binary format") - parser.add_argument( - "-k", "--key", action="store", type=str, required=True, - help="Specify your google map api key") - parser.add_argument( - "-z", "--zone", action="store", type=int, required=True, - help="Specify utm zone id. e.g, -z 10") - - args = parser.parse_args() - - run(args.key, args.map, args.zone) diff --git a/modules/tools/mapviewers/hdmapviewer.py b/modules/tools/mapviewers/hdmapviewer.py deleted file mode 100644 index bd36549b425..00000000000 --- a/modules/tools/mapviewers/hdmapviewer.py +++ /dev/null @@ -1,68 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import argparse - -from bokeh.plotting import figure, output_file, show -from modules.common_msgs.map_msgs import map_pb2 -import modules.tools.common.proto_utils as proto_utils - - -def draw(map_pb, plot): - for lane in map_pb.lane: - for curve in lane.left_boundary.curve.segment: - if curve.HasField('line_segment'): - x = [] - y = [] - for p in curve.line_segment.point: - x.append(p.x) - y.append(p.y) - plot.line(x, y, line_width=2) - for curve in lane.right_boundary.curve.segment: - if curve.HasField('line_segment'): - x = [] - y = [] - for p in curve.line_segment.point: - x.append(p.x) - y.append(p.y) - plot.line(x, y, line_width=2) - - -def load_map_data(map_file): - map_pb = map_pb2.Map() - proto_utils.get_pb_from_file(map_file, map_pb) - return map_pb - - -if __name__ == "__main__": - parser = argparse.ArgumentParser( - description="HDMapViewer is a tool to display hdmap.", - prog="hdmapviewer.py") - - parser.add_argument( - "-m", "--map", action="store", type=str, required=True, - help="Specify the HDMap file in txt or binary format") - - args = parser.parse_args() - map_pb = load_map_data(args.map) - - output_file("hdmap.html") - plot = figure(sizing_mode='scale_both', match_aspect=True) - - draw(map_pb, plot) - show(plot) diff --git a/modules/tools/mobileye_viewer/BUILD b/modules/tools/mobileye_viewer/BUILD deleted file mode 100644 index 8289400e467..00000000000 --- a/modules/tools/mobileye_viewer/BUILD +++ /dev/null @@ -1,53 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_library") - -package(default_visibility = ["//visibility:public"]) - -py_library( - name = "chassis_data", - srcs = ["chassis_data.py"], -) - -py_library( - name = "localization_data", - srcs = ["localization_data.py"], -) - -py_library( - name = "mobileye_data", - srcs = ["mobileye_data.py"], -) - -py_library( - name = "planning_data", - srcs = ["planning_data.py"], -) - -py_library( - name = "routing_data", - srcs = ["routing_data.py"], -) - -py_library( - name = "subplot_routing", - srcs = ["subplot_routing.py"], -) - -py_library( - name = "subplot_s_speed", - srcs = ["subplot_s_speed.py"], -) - -py_library( - name = "subplot_s_theta", - srcs = ["subplot_s_theta.py"], -) - -py_library( - name = "subplot_s_time", - srcs = ["subplot_s_time.py"], -) - -py_library( - name = "view_subplot", - srcs = ["view_subplot.py"], -) diff --git a/modules/tools/mobileye_viewer/chassis_data.py b/modules/tools/mobileye_viewer/chassis_data.py deleted file mode 100644 index 2e612de8f05..00000000000 --- a/modules/tools/mobileye_viewer/chassis_data.py +++ /dev/null @@ -1,37 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import threading - - -class ChassisData: - def __init__(self, chassis_pb=None): - self.chassis_pb = chassis_pb - - def update(self, chassis_pb): - self.chassis_pb = chassis_pb - - def is_auto(self): - if self.chassis_pb is None: - return False - if self.chassis_pb.driving_mode is None: - return False - if self.chassis_pb.driving_mode == \ - self.chassis_pb.COMPLETE_AUTO_DRIVE: - return True - return False diff --git a/modules/tools/mobileye_viewer/localization_data.py b/modules/tools/mobileye_viewer/localization_data.py deleted file mode 100644 index 4c5712a1c27..00000000000 --- a/modules/tools/mobileye_viewer/localization_data.py +++ /dev/null @@ -1,27 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import threading - - -class LocalizationData: - def __init__(self, localization_pb=None): - self.localization_pb = localization_pb - - def update(self, localization_pb): - self.localization_pb = localization_pb diff --git a/modules/tools/mobileye_viewer/location_monitor.html b/modules/tools/mobileye_viewer/location_monitor.html deleted file mode 100644 index 14f36240fd1..00000000000 --- a/modules/tools/mobileye_viewer/location_monitor.html +++ /dev/null @@ -1,246 +0,0 @@ - - - - - Google Maps - pygmaps - - - - - -
- - \ No newline at end of file diff --git a/modules/tools/mobileye_viewer/location_server_key b/modules/tools/mobileye_viewer/location_server_key deleted file mode 100644 index 424dd51f902..00000000000 --- a/modules/tools/mobileye_viewer/location_server_key +++ /dev/null @@ -1 +0,0 @@ -put key (only) in the first line, e.g., AIzaSyArRypN9OdShkutQzOcbXC4cwrIHU1Xi3 \ No newline at end of file diff --git a/modules/tools/mobileye_viewer/mobileye_data.py b/modules/tools/mobileye_viewer/mobileye_data.py deleted file mode 100644 index ea2f4e5ebc2..00000000000 --- a/modules/tools/mobileye_viewer/mobileye_data.py +++ /dev/null @@ -1,128 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import threading - - -class MobileyeData: - def __init__(self, mobileye_pb=None): - self.mobileye_pb = mobileye_pb - self.lane_data_lock = threading.Lock() - self.next_lane_data_lock = threading.Lock() - self.obstacle_data_lock = threading.Lock() - self.left_lane_x = [] - self.left_lane_y = [] - self.right_lane_x = [] - self.right_lane_y = [] - self.obstacle_x = [] - self.obstacle_y = [] - self.ref_lane_x = [] - self.ref_lane_y = [] - - self.next_lanes_x = [] - self.next_lanes_y = [] - - def update(self, mobileye_pb): - self.mobileye_pb = mobileye_pb - - def compute_next_lanes(self): - if self.mobileye_pb is None: - return - - self.next_lane_data_lock.acquire() - self.next_lanes_x = [] - self.next_lanes_y = [] - if len(self.mobileye_pb.next_76c) != len(self.mobileye_pb.next_76d): - print("next lanes output is incomplete!") - self.next_lane_data_lock.release() - return - for i in range(len(self.mobileye_pb.next_76c)): - lane_x = [] - lane_y = [] - c0 = self.mobileye_pb.next_76c[i].position - c1 = self.mobileye_pb.next_76d[i].heading_angle - c2 = self.mobileye_pb.next_76c[i].curvature - c3 = self.mobileye_pb.next_76c[i].curvature_derivative - rangex = self.mobileye_pb.next_76d[i].view_range - for y in range(int(rangex)): - lane_y.append(y) - x = c3*(y*y*y) + c2*(y*y) + c1*y + c0 - lane_x.append(x) - # print rangex - self.next_lanes_x.append(lane_x) - self.next_lanes_y.append(lane_y) - self.next_lane_data_lock.release() - - def compute_lanes(self): - if self.mobileye_pb is None: - return - self.left_lane_x = [] - self.left_lane_y = [] - self.right_lane_x = [] - self.right_lane_y = [] - self.ref_lane_x = [] - self.ref_lane_y = [] - - rc0 = self.mobileye_pb.lka_768.position - rc1 = self.mobileye_pb.lka_769.heading_angle - rc2 = self.mobileye_pb.lka_768.curvature - rc3 = self.mobileye_pb.lka_768.curvature_derivative - rrangex = self.mobileye_pb.lka_769.view_range + 1 - self.lane_data_lock.acquire() - for y in range(int(rrangex)): - self.right_lane_y.append(y) - x = rc3*(y*y*y) + rc2*(y*y) + rc1*y + rc0 - self.right_lane_x.append(x) - self.lane_data_lock.release() - - lc0 = self.mobileye_pb.lka_766.position - lc1 = self.mobileye_pb.lka_767.heading_angle - lc2 = self.mobileye_pb.lka_766.curvature - lc3 = self.mobileye_pb.lka_766.curvature_derivative - lrangex = self.mobileye_pb.lka_767.view_range + 1 - self.lane_data_lock.acquire() - for y in range(int(lrangex)): - self.left_lane_y.append(y) - x = lc3*(y * y * y) + lc2 * (y * y) + lc1 * y + lc0 - self.left_lane_x.append(x) - self.lane_data_lock.release() - - c0 = (rc0 + lc0) // 2 - c1 = (rc1 + lc1) // 2 - c2 = (rc2 + lc2) // 2 - c3 = (rc3 + lc3) // 2 - rangex = (lrangex + rrangex) // 2 - self.lane_data_lock.acquire() - for y in range(int(rangex)): - self.ref_lane_y.append(y) - x = c3 * (y * y * y) + c2 * (y * y) + c1 * y + c0 - self.ref_lane_x.append(x) - self.lane_data_lock.release() - - def compute_obstacles(self): - if self.mobileye_pb is None: - return - self.obstacle_x = [] - self.obstacle_y = [] - self.obstacle_data_lock.acquire() - for i in range(len(self.mobileye_pb.details_739)): - x = self.mobileye_pb.details_739[i].obstacle_pos_x - y = self.mobileye_pb.details_739[i].obstacle_pos_y - self.obstacle_x.append(x) - self.obstacle_y.append(y * -1) - self.obstacle_data_lock.release() diff --git a/modules/tools/mobileye_viewer/planning_data.py b/modules/tools/mobileye_viewer/planning_data.py deleted file mode 100644 index 27c5fe478d3..00000000000 --- a/modules/tools/mobileye_viewer/planning_data.py +++ /dev/null @@ -1,69 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import threading - - -class PlanningData: - def __init__(self, planning_pb=None): - self.path_lock = threading.Lock() - self.path_param_lock = threading.Lock() - - self.planning_pb = planning_pb - self.path_x = [] - self.path_y = [] - - self.relative_time = [] - self.speed = [] - self.s = [] - self.theta = [] - - def update(self, planning_pb): - self.planning_pb = planning_pb - - def compute_path(self): - if self.planning_pb is None: - return - path_x = [] - path_y = [] - for point in self.planning_pb.trajectory_point: - path_x.append(-1 * point.path_point.y) - path_y.append(point.path_point.x) - self.path_lock.acquire() - self.path_x = path_x - self.path_y = path_y - self.path_lock.release() - - def compute_path_param(self): - if self.planning_pb is None: - return - relative_time = [] - speed = [] - s = [] - theta = [] - for point in self.planning_pb.trajectory_point: - relative_time.append(point.relative_time) - speed.append(point.v) - s.append(point.path_point.s) - theta.append(point.path_point.theta) - self.path_param_lock.acquire() - self.relative_time = relative_time - self.speed = speed - self.s = s - self.theta = theta - self.path_param_lock.release() diff --git a/modules/tools/mobileye_viewer/routing_data.py b/modules/tools/mobileye_viewer/routing_data.py deleted file mode 100644 index 6653936bda8..00000000000 --- a/modules/tools/mobileye_viewer/routing_data.py +++ /dev/null @@ -1,75 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import threading -import json - - -class RoutingData: - def __init__(self, routing_str=None): - self.routing_str = routing_str - self.routing_debug_str = None - self.routing_data_lock = threading.Lock() - self.routing_x = [] - self.routing_y = [] - self.segment_x = [] - self.segment_y = [] - - def update_navigation(self, navigation_info_pb): - routing_x = [] - routing_y = [] - for navi_path in navigation_info_pb.navigation_path: - for path_point in navi_path.path.path_point: - routing_x.append(path_point.x) - routing_y.append(path_point.y) - self.routing_data_lock.acquire() - self.routing_x = routing_x - self.routing_y = routing_y - self.routing_data_lock.release() - - def update(self, routing_str): - self.routing_str = routing_str - routing_json = json.loads(routing_str.data) - routing_x = [] - routing_y = [] - for step in routing_json: - points = step['polyline']['points'] - for point in points: - routing_x.append(point[0]) - routing_y.append(point[1]) - - self.routing_data_lock.acquire() - self.routing_x = routing_x - self.routing_y = routing_y - self.routing_data_lock.release() - - def update_debug(self, routing_debug_str): - self.routing_debug_str = routing_debug_str - segment_json = json.loads(routing_debug_str.data) - if segment_json is None: - return - segment_x = [] - segment_y = [] - for point in segment_json: - segment_x.append(point[0]) - segment_y.append(point[1]) - - self.routing_data_lock.acquire() - self.segment_x = segment_x - self.segment_y = segment_y - self.routing_data_lock.release() diff --git a/modules/tools/mobileye_viewer/subplot_routing.py b/modules/tools/mobileye_viewer/subplot_routing.py deleted file mode 100644 index 78325a370b6..00000000000 --- a/modules/tools/mobileye_viewer/subplot_routing.py +++ /dev/null @@ -1,39 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -import math - - -class SubplotRouting: - def __init__(self, ax): - self.ax = ax - self.routing_dot, = ax.plot([0], [0], 'ro', lw=3, alpha=0.4) - self.routing_line, = ax.plot([0], [0], 'b-', lw=1, alpha=1) - self.segment_line, = ax.plot([0], [0], 'bo', lw=1, alpha=1) - - def show(self, routing_data): - routing_data.routing_data_lock.acquire() - self.routing_dot.set_xdata(routing_data.routing_x) - self.routing_dot.set_ydata(routing_data.routing_y) - self.routing_line.set_xdata(routing_data.routing_x) - self.routing_line.set_ydata(routing_data.routing_y) - self.segment_line.set_xdata(routing_data.segment_x) - self.segment_line.set_ydata(routing_data.segment_y) - - routing_data.routing_data_lock.release() - self.ax.autoscale_view() - self.ax.relim() diff --git a/modules/tools/mobileye_viewer/subplot_s_speed.py b/modules/tools/mobileye_viewer/subplot_s_speed.py deleted file mode 100644 index f96c7332169..00000000000 --- a/modules/tools/mobileye_viewer/subplot_s_speed.py +++ /dev/null @@ -1,33 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -import math - - -class SubplotSSpeed: - def __init__(self, ax): - self.s_speed_line, = ax.plot([0], [0], 'r-', lw=3, alpha=0.4) - ax.set_xlim([-2, 100]) - ax.set_ylim([-1, 40]) - ax.set_xlabel("s (m)") - ax.set_ylabel("speed (m/s)") - - def show(self, planning_data): - planning_data.path_param_lock.acquire() - self.s_speed_line.set_xdata(planning_data.s) - self.s_speed_line.set_ydata(planning_data.speed) - planning_data.path_param_lock.release() diff --git a/modules/tools/mobileye_viewer/subplot_s_theta.py b/modules/tools/mobileye_viewer/subplot_s_theta.py deleted file mode 100644 index eada1714de0..00000000000 --- a/modules/tools/mobileye_viewer/subplot_s_theta.py +++ /dev/null @@ -1,33 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -import math - - -class SubplotSTheta: - def __init__(self, ax): - self.s_speed_line, = ax.plot([0], [0], 'r-', lw=3, alpha=0.4) - ax.set_xlim([-2, 100]) - ax.set_ylim([-0.5, 0.5]) - ax.set_xlabel("s (m)") - ax.set_ylabel("theta (r)") - - def show(self, planning_data): - planning_data.path_param_lock.acquire() - self.s_speed_line.set_xdata(planning_data.s) - self.s_speed_line.set_ydata(planning_data.theta) - planning_data.path_param_lock.release() diff --git a/modules/tools/mobileye_viewer/subplot_s_time.py b/modules/tools/mobileye_viewer/subplot_s_time.py deleted file mode 100644 index 8fc84562742..00000000000 --- a/modules/tools/mobileye_viewer/subplot_s_time.py +++ /dev/null @@ -1,33 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -import math - - -class SubplotSTime: - def __init__(self, ax): - self.s_speed_line, = ax.plot([0], [0], 'r-', lw=3, alpha=0.4) - ax.set_xlim([-2, 100]) - ax.set_ylim([-0.5, 10]) - ax.set_xlabel("s (m)") - ax.set_ylabel("time (sec)") - - def show(self, planning_data): - planning_data.path_param_lock.acquire() - self.s_speed_line.set_xdata(planning_data.s) - self.s_speed_line.set_ydata(planning_data.relative_time) - planning_data.path_param_lock.release() diff --git a/modules/tools/mobileye_viewer/view_subplot.py b/modules/tools/mobileye_viewer/view_subplot.py deleted file mode 100644 index eca37c0a7e6..00000000000 --- a/modules/tools/mobileye_viewer/view_subplot.py +++ /dev/null @@ -1,141 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -import math - - -class ViewSubplot: - def __init__(self, ax): - # self.ax = ax - self.right_lane, = ax.plot( - [-10, 10, -10, 10], [-10, 150, 150, -10], - 'bo', lw=3, alpha=0.4) - self.left_lane, = ax.plot( - [0], [0], 'go', lw=3, alpha=0.5) - self.obstacles, = ax.plot( - [0], [0], 'r.', ms=20, alpha=0.5) - self.ref_lane, = ax.plot( - [0], [0], 'k--', lw=3, alpha=0.8) - self.vehicle = ax.plot( - [-1.055, 1.055, 1.055, -1.055, -1.055], [0, 0, -4.933, -4.933, 0], - 'r-', lw=1) - self.routing, = ax.plot( - [0], [0], 'r--', lw=3, alpha=0.8) - - self.speed_line, = ax.plot([0], [0], 'r-', lw=3, alpha=0.4) - self.acc_line, = ax.plot([0], [0], 'y-', lw=3, alpha=1) - - ax.set_xlim([-10, 10]) - ax.set_ylim([-10, 100]) - ax.relim() - ax.set_xlabel("lat(m)") - self.next_lanes = [] - for i in range(8): - lane, = ax.plot([0], [0], 'b-', lw=3, alpha=0.4) - self.next_lanes.append(lane) - - self.left_lane.set_visible(False) - self.right_lane.set_visible(False) - self.ref_lane.set_visible(False) - - def show(self, mobileye_data, localization_data, planning_data, - chassis_data, routing_data): - self.left_lane.set_visible(True) - self.right_lane.set_visible(True) - self.ref_lane.set_visible(True) - - mobileye_data.lane_data_lock.acquire() - self.right_lane.set_xdata(mobileye_data.right_lane_x) - self.right_lane.set_ydata(mobileye_data.right_lane_y) - self.left_lane.set_xdata(mobileye_data.left_lane_x) - self.left_lane.set_ydata(mobileye_data.left_lane_y) - mobileye_data.lane_data_lock.release() - - planning_data.path_lock.acquire() - self.ref_lane.set_xdata(planning_data.path_x) - self.ref_lane.set_ydata(planning_data.path_y) - planning_data.path_lock.release() - - if chassis_data.is_auto(): - self.ref_lane.set_color('r') - else: - self.ref_lane.set_color('k') - - mobileye_data.obstacle_data_lock.acquire() - self.obstacles.set_ydata(mobileye_data.obstacle_x) - self.obstacles.set_xdata(mobileye_data.obstacle_y) - mobileye_data.obstacle_data_lock.release() - - mobileye_data.next_lane_data_lock.acquire() - for i in range(len(mobileye_data.next_lanes_x)): - if i >= len(self.next_lanes): - mobileye_data.next_lane_data_lock.release() - break - self.next_lanes[i].set_xdata(mobileye_data.next_lanes_x[i]) - self.next_lanes[i].set_ydata(mobileye_data.next_lanes_y[i]) - mobileye_data.next_lane_data_lock.release() - - if localization_data.localization_pb is None: - return - - vx = localization_data.localization_pb.pose.position.x - vy = localization_data.localization_pb.pose.position.y - - routing_data.routing_data_lock.acquire() - path_x = [x - vx for x in routing_data.routing_x] - path_y = [y - vy for y in routing_data.routing_y] - routing_data.routing_data_lock.release() - - heading = localization_data.localization_pb.pose.heading - npath_x = [] - npath_y = [] - - for i in range(len(path_x)): - x = path_x[i] - y = path_y[i] - # newx = x * math.cos(heading) - y * math.sin(heading) - # newy = y * math.cos(heading) + x * math.sin(heading) - newx = x * math.cos(- heading + 1.570796) - y * math.sin( - -heading + 1.570796) - newy = y * math.cos(- heading + 1.570796) + x * math.sin( - -heading + 1.570796) - npath_x.append(newx) - npath_y.append(newy) - - self.routing.set_xdata(npath_x) - self.routing.set_ydata(npath_y) - - speed_x = localization_data.localization_pb.pose.linear_velocity.x - speed_y = localization_data.localization_pb.pose.linear_velocity.y - acc_x = localization_data.localization_pb.pose.linear_acceleration.x - acc_y = localization_data.localization_pb.pose.linear_acceleration.y - heading = localization_data.localization_pb.pose.heading - - new_speed_x = math.cos(-heading + math.pi / 2) * speed_x - math.sin( - -heading + math.pi / 2) * speed_y - new_speed_y = math.sin(-heading + math.pi / 2) * speed_x + math.cos( - -heading + math.pi / 2) * speed_y - - new_acc_x = math.cos(-heading + math.pi / 2) * acc_x - math.sin( - -heading + math.pi / 2) * acc_y - new_acc_y = math.sin(-heading + math.pi / 2) * acc_x + math.cos( - -heading + math.pi / 2) * acc_y - - # self.speed_line.set_xdata([0, new_speed_x]) - # self.speed_line.set_ydata([0, new_speed_y]) - # self.acc_line.set_xdata([0, new_acc_x]) - # self.acc_line.set_ydata([0, new_acc_y]) diff --git a/modules/tools/mock_routing/BUILD b/modules/tools/mock_routing/BUILD deleted file mode 100644 index 8b54557beaf..00000000000 --- a/modules/tools/mock_routing/BUILD +++ /dev/null @@ -1,22 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -py_binary( - name = "mock_routing_request", - srcs = ["mock_routing_request.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:cyber_time", - "//modules/common_msgs/routing_msgs:routing_py_pb2", - ], -) - -install( - name = "install", - py_dest = "tools/mock_routing", - targets = [ - ":mock_routing_request", - ] -) \ No newline at end of file diff --git a/modules/tools/mock_routing/mock_routing_request.py b/modules/tools/mock_routing/mock_routing_request.py deleted file mode 100644 index 1e27cdecd16..00000000000 --- a/modules/tools/mock_routing/mock_routing_request.py +++ /dev/null @@ -1,68 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -Insert routing request -Usage: - mock_routing_request.py -""" -import argparse -import os -import sys -import time - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import cyber_time -from modules.common_msgs.routing_msgs import routing_pb2 - - -def main(): - """ - Main rosnode - """ - cyber.init() - node = cyber.Node("mock_routing_requester") - sequence_num = 0 - - routing_request = routing_pb2.RoutingRequest() - - routing_request.header.timestamp_sec = cyber_time.Time.now().to_sec() - routing_request.header.module_name = 'routing_request' - routing_request.header.sequence_num = sequence_num - sequence_num = sequence_num + 1 - - waypoint = routing_request.waypoint.add() - waypoint.pose.x = 587696.82286 - waypoint.pose.y = 4141446.66696 - waypoint.id = '1-1' - waypoint.s = 1 - - waypoint = routing_request.waypoint.add() - waypoint.pose.x = 586948.740120 - waypoint.pose.y = 4141171.118641 - waypoint.id = '1-1' - waypoint.s = 80 - - writer = node.create_writer('/apollo/routing_request', - routing_pb2.RoutingRequest) - time.sleep(2.0) - print("routing_request", routing_request) - writer.write(routing_request) - - -if __name__ == '__main__': - main() diff --git a/modules/tools/navigation/BUILD b/modules/tools/navigation/BUILD deleted file mode 100644 index 88b89d5aacc..00000000000 --- a/modules/tools/navigation/BUILD +++ /dev/null @@ -1,18 +0,0 @@ -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -filegroup( - name = "runtime_files", - srcs = [ - "navigation_server_key", - ], -) - -install( - name = "install", - deps = [ - "//modules/tools/navigation/config:install", - "//modules/tools/navigation/driving_behavior:install" - ] -) \ No newline at end of file diff --git a/modules/tools/navigation/config/BUILD b/modules/tools/navigation/config/BUILD deleted file mode 100644 index a67c44ea987..00000000000 --- a/modules/tools/navigation/config/BUILD +++ /dev/null @@ -1,33 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -filegroup( - name = "readme", - srcs = [ - "README.md", - "default.ini", - ], -) - -py_binary( - name = "navi_config", - srcs = ["navi_config.py"], - data = ["default.ini"], - deps = [ - "//modules/dreamview/proto:hmi_config_py_pb2", - "//modules/planning/proto:planning_config_py_pb2", - "//modules/tools/common:proto_utils", - ], -) - -install( - name = "install", - data = [":readme"], - data_dest = "tools/navigation/config", - py_dest = "tools/navigation/config", - targets = [ - "navi_config", - ] -) \ No newline at end of file diff --git a/modules/tools/navigation/config/README.md b/modules/tools/navigation/config/README.md deleted file mode 100644 index 98f07ec6836..00000000000 --- a/modules/tools/navigation/config/README.md +++ /dev/null @@ -1,37 +0,0 @@ -# Navi Config - -Navi Config is a tool to set parameters and flags in various modules for navigation mode. - -### usage - -``` -python navi_config.py default.ini -``` - -*default.ini* file is the default navigation mode configuration, with following content: - -``` -[PerceptionConf] -# three perception solutions: MOBILEYE, CAMERA, and VELODYNE64 -perception = CAMERA - - -[LocalizationConf] -utm_zone = 10 - - -[PlanningConf] -# three planners are available: EM, LATTICE, NAVI -planner_type = EM - -# highest speed for planning algorithms, unit is meter per second -speed_limit = 5 -``` - -In **PerceptionConf** section, the *perception* parameter is to specify the perception solution. Currently there are three supported in Apollo Navigation Mode: mobileye based, camera based and lidar based. - -In the **LocalizationConf** section, utm_zone need to be specified based on location of the road test. - -In the **PlanningConf** section, three planner are supported: EM, Lattice, and Navi. Select one for the planner_type parameter. speed_limt, which is the planner upper speed limit, is also configurable in this seciton, which unit is meter per second. - -Developers could create differet ini files for different test scenarios/purposes or modified the default.ini based on needs. \ No newline at end of file diff --git a/modules/tools/navigation/config/default.ini b/modules/tools/navigation/config/default.ini deleted file mode 100644 index 40e6bb651e3..00000000000 --- a/modules/tools/navigation/config/default.ini +++ /dev/null @@ -1,15 +0,0 @@ -[PerceptionConf] -# three perception solutions: MOBILEYE, CAMERA, and VELODYNE64 -perception = CAMERA - - -[LocalizationConf] -utm_zone = 10 - - -[PlanningConf] -# three planners are available: EM, LATTICE, NAVI -planner_type = EM - -# highest speed for planning algorithms, unit is meter per second -speed_limit = 5 diff --git a/modules/tools/navigation/config/navi_config.py b/modules/tools/navigation/config/navi_config.py deleted file mode 100644 index dbcba2d70af..00000000000 --- a/modules/tools/navigation/config/navi_config.py +++ /dev/null @@ -1,135 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### -""" -config navigation mode -""" -import sys -import configparser -from modules.dreamview.proto import hmi_config_pb2 -from modules.common_msgs.planning_msgs import planning_config_pb2 -from modules.tools.common import proto_utils - -DEFAULT_NAVI_CONFIG_FILE = "/apollo/modules/tools/navigation/config/default.ini" -HMI_CONF_FILE = "/apollo/modules/dreamview/conf/hmi.conf" -PLANNING_CONF_FILE = "/apollo/modules/planning/conf/planning_config_navi.pb.txt" -GLOBAL_FLAG_FILE = "/apollo/modules/common/data/global_flagfile.txt" -LOCALIZATION_FLAG_FILE = "/apollo/modules/localization/conf/localization.conf" -PLANNING_FLAG_FILE1 = "/apollo/modules/planning/conf/planning.conf" -PLANNING_FLAG_FILE2 = "/apollo/modules/planning/conf/planning_navi.conf" - - -def set_hmi_conf(config): - """change hmi conf file based on navi config file""" - hmi_conf = hmi_config_pb2.HMIConfig() - proto_utils.get_pb_from_file(HMI_CONF_FILE, hmi_conf) - - perception = config.get('PerceptionConf', 'perception') - navi_mode = hmi_conf.modes["Navigation"] - - if 'navigation_camera' in navi_mode.live_modules: - navi_mode.live_modules.remove('navigation_camera') - if 'navigation_perception' in navi_mode.live_modules: - navi_mode.live_modules.remove('navigation_perception') - - if 'mobileye' in navi_mode.live_modules: - navi_mode.live_modules.remove('mobileye') - if 'third_party_perception' in navi_mode.live_modules: - navi_mode.live_modules.remove('third_party_perception') - - if 'velodyne' in navi_mode.live_modules: - navi_mode.live_modules.remove('velodyne') - if 'perception' in navi_mode.live_modules: - navi_mode.live_modules.remove('perception') - - if perception == "CAMERA": - if 'navigation_camera' not in navi_mode.live_modules: - navi_mode.live_modules.insert(0, 'navigation_camera') - if 'navigation_perception' not in navi_mode.live_modules: - navi_mode.live_modules.insert(0, 'navigation_perception') - - if perception == "MOBILEYE": - if 'mobileye' not in navi_mode.live_modules: - navi_mode.live_modules.insert(0, 'mobileye') - if 'third_party_perception' not in navi_mode.live_modules: - navi_mode.live_modules.insert(0, 'third_party_perception') - - if perception == "VELODYNE64": - if 'velodyne' not in navi_mode.live_modules: - navi_mode.live_modules.insert(0, 'velodyne') - if 'perception' not in navi_mode.live_modules: - navi_mode.live_modules.insert(0, 'perception') - - hmi_conf.modes["Navigation"].CopyFrom(navi_mode) - proto_utils.write_pb_to_text_file(hmi_conf, HMI_CONF_FILE) - - -def set_planning_conf(config): - """change planning config based on navi config""" - planning_conf = planning_config_pb2.PlanningConfig() - proto_utils.get_pb_from_file(PLANNING_CONF_FILE, planning_conf) - planner_type = config.get('PlanningConf', 'planner_type') - if planner_type == "EM": - planning_conf.planner_type = planning_config_pb2.PlanningConfig.EM - if planner_type == "LATTICE": - planning_conf.planner_type = planning_config_pb2.PlanningConfig.LATTICE - if planner_type == "NAVI": - planning_conf.planner_type = planning_config_pb2.PlanningConfig.NAVI - proto_utils.write_pb_to_text_file(planning_conf, PLANNING_CONF_FILE) - - -def set_global_flag(config): - """update global flag file""" - utm_zone = config.get('LocalizationConf', 'utm_zone') - with open(GLOBAL_FLAG_FILE, 'a') as f: - f.write('\n') - f.write('--use_navigation_mode=true\n\n') - f.write('--local_utm_zone_id=' + utm_zone + '\n\n') - - -def set_localization_flag(config): - """update localization flag file""" - utm_zone = config.get('LocalizationConf', 'utm_zone') - with open(LOCALIZATION_FLAG_FILE, 'a') as f: - f.write('\n') - f.write('--local_utm_zone_id=' + utm_zone + '\n\n') - - -def set_planning_flag(config): - """update planning flag files""" - speed_limit = config.get('PlanningConf', 'speed_limit') - with open(PLANNING_FLAG_FILE1, 'a') as f: - f.write('\n') - f.write('--planning_upper_speed_limit=' + speed_limit + '\n\n') - with open(PLANNING_FLAG_FILE2, 'a') as f: - f.write('\n') - f.write('--planning_upper_speed_limit=' + speed_limit + '\n\n') - - -if __name__ == "__main__": - if len(sys.argv) < 2: - print("\nusage: python navi_config.py config.ini\n\n") - sys.exit(0) - config_file = sys.argv[1] - config = configparser.ConfigParser() - config.read(config_file) - - set_hmi_conf(config) - set_planning_conf(config) - set_global_flag(config) - set_localization_flag(config) - set_planning_flag(config) diff --git a/modules/tools/navigation/driving_behavior/BUILD b/modules/tools/navigation/driving_behavior/BUILD deleted file mode 100644 index 126a0afedc3..00000000000 --- a/modules/tools/navigation/driving_behavior/BUILD +++ /dev/null @@ -1,41 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -py_binary( - name = "path_extract", - srcs = ["path_extract.py"], - deps = [ - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - ], -) - -py_binary( - name = "path_plot", - srcs = ["path_plot.py"], -) - -py_binary( - name = "path_process", - srcs = ["path_process.py"], -) - -py_binary( - name = "plot_gps_path", - srcs = ["plot_gps_path.py"], -) - - -install( - name = "install", - data_dest = "tools/navigation/driving_behavior", - py_dest = "tools/navigation/driving_behavior", - targets = [ - "path_plot", - "path_process", - "plot_gps_path", - "path_extract", - ] -) \ No newline at end of file diff --git a/modules/tools/navigation/driving_behavior/path_extract.py b/modules/tools/navigation/driving_behavior/path_extract.py deleted file mode 100644 index 9d0738da8ff..00000000000 --- a/modules/tools/navigation/driving_behavior/path_extract.py +++ /dev/null @@ -1,48 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -extract localization message from bag files -Usage: - python path_extract.py file1 file2 ... -""" -import sys -import datetime -from cyber.python.cyber_py3.record import RecordReader -from modules.common_msgs.localization_msgs import localization_pb2 - -kLocalizationTopic = '/apollo/localization/pose' - -if __name__ == '__main__': - bag_files = sys.argv[1:] - - bag_file = bag_files[0] - now = datetime.datetime.now().strftime("%Y-%m-%d_%H.%M.%S") - f = open("path_" + bag_file.split('/')[-1] + ".txt", 'w') - - for bag_file in bag_files: - print("begin to extract path from file :", bag_file) - reader = RecordReader(bag_file) - localization = localization_pb2.LocalizationEstimate() - for msg in reader.read_messages(): - if msg.topic == kLocalizationTopic: - localization.ParseFromString(msg.message) - x = localization.pose.position.x - y = localization.pose.position.y - f.write(str(x) + "," + str(y) + "\n") - print("Finished extracting path from file :", bag_file) - f.close() diff --git a/modules/tools/navigation/driving_behavior/path_plot.py b/modules/tools/navigation/driving_behavior/path_plot.py deleted file mode 100644 index 3f373358e12..00000000000 --- a/modules/tools/navigation/driving_behavior/path_plot.py +++ /dev/null @@ -1,43 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import sys -import matplotlib.pyplot as plt - -fig = plt.figure() -ax = plt.subplot2grid((1, 1), (0, 0)) -styles = ["b-", "r-", "y-"] -i = 0 -for fn in sys.argv[1:]: - f = open(fn, 'r') - xs = [] - ys = [] - for line in f: - line = line.replace("\n", '') - data = line.split(',') - x = float(data[0]) - y = float(data[1]) - xs.append(x) - ys.append(y) - f.close() - si = i % len(styles) - ax.plot(xs, ys, styles[si], lw=3, alpha=0.8) - i += 1 - -ax.axis('equal') -plt.show() diff --git a/modules/tools/navigation/driving_behavior/path_process.py b/modules/tools/navigation/driving_behavior/path_process.py deleted file mode 100644 index e76f97cb308..00000000000 --- a/modules/tools/navigation/driving_behavior/path_process.py +++ /dev/null @@ -1,57 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import sys -from shapely.geometry import LineString, Point -import matplotlib.pyplot as plt - -if __name__ == "__main__": - fpath = sys.argv[1] - f = open(fpath, 'r') - points_x = [] - points_y = [] - points = [] - - for line in f: - line = line.replace("\n", '') - if len(line.strip()) == 0: - continue - data = line.split(',') - x = float(data[0]) - y = float(data[1]) - points_x.append(x) - points_y.append(y) - points.append((x, y)) - f.close() - line_string = LineString(points) - new_px = [] - new_py = [] - f = open("processed_" + fpath.split("/")[-1], 'w') - for i in range(int(line_string.length)): - p = line_string.interpolate(i) - new_px.append(p.x) - new_py.append(p.y) - f.write(str(p.x) + "," + str(p.y) + "\n") - f.close() - print(len(points_x)) - print(len(new_px)) - plt.figure() - plt.plot(points_x, points_y, '-r', lw=1, label='raw') - plt.plot(new_px, new_py, '-g', label='processed') - plt.legend(loc='best') - plt.show() diff --git a/modules/tools/navigation/driving_behavior/plot_gps_path.py b/modules/tools/navigation/driving_behavior/plot_gps_path.py deleted file mode 100644 index a0b5201c821..00000000000 --- a/modules/tools/navigation/driving_behavior/plot_gps_path.py +++ /dev/null @@ -1,47 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import sys -import pyproj -import matplotlib.pyplot as plt - -projector = pyproj.Proj(proj='utm', zone=10, ellps='WGS84') -fig = plt.figure() -ax = plt.subplot2grid((1, 1), (0, 0)) -styles = ['r-', 'b-'] - -i = 0 -for fn in sys.argv[1:]: - X = [] - Y = [] - f = open(fn, 'r') - for line in f: - line = line.replace('\n', '') - vals = line.split(",") - if len(vals) < 3: - continue - print(float(vals[-2]), float(vals[-1])) - x, y = projector(float(vals[-1]), float(vals[-2])) - print(x, y) - X.append(x) - Y.append(y) - f.close() - ax.plot(X, Y, styles[i % len(styles)], lw=3, alpha=0.8) - i += 1 -ax.axis('equal') -plt.show() diff --git a/modules/tools/navigation/navigation_server_key b/modules/tools/navigation/navigation_server_key deleted file mode 100644 index 424dd51f902..00000000000 --- a/modules/tools/navigation/navigation_server_key +++ /dev/null @@ -1 +0,0 @@ -put key (only) in the first line, e.g., AIzaSyArRypN9OdShkutQzOcbXC4cwrIHU1Xi3 \ No newline at end of file diff --git a/modules/tools/navigation/planning/BUILD b/modules/tools/navigation/planning/BUILD deleted file mode 100644 index 758a1a7c249..00000000000 --- a/modules/tools/navigation/planning/BUILD +++ /dev/null @@ -1,54 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_library") - -package(default_visibility = ["//visibility:public"]) - -py_library( - name = "ad_vehicle", - srcs = ["ad_vehicle.py"], -) - -py_library( - name = "heading_decider", - srcs = ["heading_decider.py"], -) - -py_library( - name = "lanemarker_corrector", - srcs = ["lanemarker_corrector.py"], -) - -py_library( - name = "local_path", - srcs = ["local_path.py"], -) - -py_library( - name = "provider_chassis", - srcs = ["provider_chassis.py"], -) - -py_library( - name = "provider_localization", - srcs = ["provider_localization.py"], -) - -py_library( - name = "reference_path", - srcs = ["reference_path.py"], -) - -py_library( - name = "speed_decider", - srcs = ["speed_decider.py"], -) - -py_library( - name = "trajectory_generator", - srcs = ["trajectory_generator.py"], - deps = [ - "//cyber/python/cyber_py3:cyber_time", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/basic_msgs:drive_state_py_pb2", - "//modules/common_msgs/planning_msgs:planning_py_pb2", - ], -) diff --git a/modules/tools/navigation/planning/ad_vehicle.py b/modules/tools/navigation/planning/ad_vehicle.py deleted file mode 100644 index fd9fab7ebfd..00000000000 --- a/modules/tools/navigation/planning/ad_vehicle.py +++ /dev/null @@ -1,46 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - - -class ADVehicle: - def __init__(self): - self._chassis_pb = None - self._localization_pb = None - self.front_edge_to_center = 3.89 - self.back_edge_to_center = 1.043 - self.left_edge_to_center = 1.055 - self.right_edge_to_center = 1.055 - self.speed_mps = None - self.x = None - self.y = None - self.heading = None - - def update_chassis(self, chassis_pb): - self._chassis_pb = chassis_pb - self.speed_mps = self._chassis_pb.speed_mps - - def update_localization(self, localization_pb): - self._localization_pb = localization_pb - self.x = self._localization_pb.pose.position.x - self.y = self._localization_pb.pose.position.y - self.heading = self._localization_pb.pose.heading - - def is_ready(self): - if self._chassis_pb is None or self._localization_pb is None: - return False - return True diff --git a/modules/tools/navigation/planning/heading_decider.py b/modules/tools/navigation/planning/heading_decider.py deleted file mode 100644 index 8121d83666c..00000000000 --- a/modules/tools/navigation/planning/heading_decider.py +++ /dev/null @@ -1,42 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -import math -import numpy.polynomial.polynomial as poly - - -class HeadingDecider: - def __init__(self): - self.mobileye_pb = None - - def get_path(self, x, y, path_length): - ind = int(math.floor((abs(x[0]) * 100.0) / 1) + 1) - newx = [0] - newy = [0] - w = [1000] - if len(y) - ind > 0: - for i in range(len(y) - ind): - newx.append(x[i + ind]) - newy.append(y[i + ind]) - w.append(w[-1] - 10) - else: - newx.append(x[-1]) - newy.append(y[-1]) - w.append(w[-1] - 10) - coefs = poly.polyfit(newy, newx, 4, w=w) # x = f(y) - nx = poly.polyval(y, coefs) - return nx, y diff --git a/modules/tools/navigation/planning/lanemarker_corrector.py b/modules/tools/navigation/planning/lanemarker_corrector.py deleted file mode 100644 index 8e4f725593e..00000000000 --- a/modules/tools/navigation/planning/lanemarker_corrector.py +++ /dev/null @@ -1,28 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import math - - -class LaneMarkerCorrector: - def __init__(self, left_marker, right_marker): - self.left_marker = left_marker - self.right_marker = right_marker - - def correct(self, position, heading, routing_segment): - return self.left_marker, self.right_marker diff --git a/modules/tools/navigation/planning/local_path.py b/modules/tools/navigation/planning/local_path.py deleted file mode 100644 index 9fb0bbc1f74..00000000000 --- a/modules/tools/navigation/planning/local_path.py +++ /dev/null @@ -1,55 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - - -class LocalPath: - def __init__(self, points): - self.points = points - - def init_y(self): - if len(self.points) > 0: - return self.points[0][1] - return None - - def get_xy(self): - x = [] - y = [] - for p in self.points: - x.append(p[0]) - y.append(p[1]) - return x, y - - def range(self): - return len(self.points) - 1 - - def shift(self, dist): - for i in range(len(self.points)): - self.points[i][1] += dist - - def cut(self, dist): - pass - - def resample(self): - pass - - def merge(self, local_path, weight): - for i in range(len(self.points)): - y = self.points[i][1] - if i < len(local_path.points): - y2 = local_path.points[i][1] * weight - self.points[i][1] = (y + y2) / (1 + weight) diff --git a/modules/tools/navigation/planning/provider_chassis.py b/modules/tools/navigation/planning/provider_chassis.py deleted file mode 100644 index 5a8a73b2bcd..00000000000 --- a/modules/tools/navigation/planning/provider_chassis.py +++ /dev/null @@ -1,30 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - - -class ChassisProvider: - def __init__(self): - self.chassis_pb = None - - def update(self, chassis_pb): - self.chassis_pb = chassis_pb - - def get_speed_mps(self): - if self.chassis_pb is None: - return None - return self.chassis_pb.speed_mps diff --git a/modules/tools/navigation/planning/provider_localization.py b/modules/tools/navigation/planning/provider_localization.py deleted file mode 100644 index e9864e23b2f..00000000000 --- a/modules/tools/navigation/planning/provider_localization.py +++ /dev/null @@ -1,31 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - - -class LocalizationProvider: - def __init__(self): - self.localization_pb = None - self.x = 0 - self.y = 0 - self.heading = 0 - - def update(self, localization_pb): - self.localization_pb = localization_pb - self.x = self.localization_pb.pose.position.x - self.y = self.localization_pb.pose.position.y - self.heading = self.localization_pb.pose.heading diff --git a/modules/tools/navigation/planning/reference_path.py b/modules/tools/navigation/planning/reference_path.py deleted file mode 100644 index 128902e8edf..00000000000 --- a/modules/tools/navigation/planning/reference_path.py +++ /dev/null @@ -1,131 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -import math -from numpy.polynomial.polynomial import polyval - - -class ReferencePath: - def __init__(self): - self.MINIMUM_PATH_LENGTH = 5 - self.MAX_LAT_CHANGE = 0.1 - self.init_y_last = None - - def get_path_length(self, speed_mps): - path_length = self.MINIMUM_PATH_LENGTH - current_speed = speed_mps - if current_speed is not None: - if path_length < current_speed * 2: - path_length = math.ceil(current_speed * 2) - return path_length - - def get_ref_path_init_y(self, init_y_perception): - if self.init_y_last is None: - return 0 - if abs(init_y_perception - self.init_y_last) < self.MAX_LAT_CHANGE: - return init_y_perception - else: - if init_y_perception > self.init_y_last: - return self.init_y_last + self.MAX_LAT_CHANGE - else: - return self.init_y_last - self.MAX_LAT_CHANGE - - def get_ref_path_by_lm(self, perception, chassis): - path_length = self.get_path_length(chassis.get_speed_mps()) - init_y_perception = (perception.right_lm_coef[0] + - perception.left_lm_coef[0]) / -2.0 - init_y = self.get_ref_path_init_y(init_y_perception) - self.init_y_last = init_y - path_x, path_y = self._get_perception_ref_path( - perception, path_length, init_y) - return path_x, path_y, path_length - - def _get_perception_ref_path(self, perception, path_length, init_y): - path_coef = [0, 0, 0, 0] - - path_coef[0] = -1 * init_y - quality = perception.right_lm_quality + perception.left_lm_quality - if quality > 0: - for i in range(1, 4): - path_coef[i] = (perception.right_lm_coef[i] * - perception.right_lm_quality + - perception.left_lm_coef[i] * - perception.left_lm_quality) / quality - path_x = [] - path_y = [] - for x in range(int(path_length)): - y = -1 * polyval(x, path_coef) - path_x.append(x) - path_y.append(y) - return path_x, path_y - - def get_ref_path_by_lmr(self, perception, routing, adv): - - path_length = self.get_path_length(adv.speed_mps) - - rpath_x, rpath_y = routing.get_local_segment_spline(adv.x, - adv.y, - adv.heading) - init_y_perception = (perception.right_lm_coef[0] + - perception.left_lm_coef[0]) / -2.0 - quality = perception.right_lm_quality + perception.left_lm_quality - quality = quality / 2.0 - - if len(rpath_x) >= path_length and routing.human and rpath_y[0] <= 3: - init_y_routing = rpath_y[0] - init_y = self.get_ref_path_init_y(init_y_routing) - if quality > 0.1: - quality = 0.1 - self.init_y_last = init_y - else: - init_y = self.get_ref_path_init_y(init_y_perception) - self.init_y_last = init_y - - lmpath_x, lmpath_y = self._get_perception_ref_path( - perception, path_length, init_y) - - if len(rpath_x) < path_length: - return lmpath_x, lmpath_y, path_length - - routing_shift = rpath_y[0] - init_y - path_x = [] - path_y = [] - for i in range(int(path_length)): - # TODO(yifei): more accurate shift is needed. - y = (lmpath_y[i] * quality + rpath_y[i] - routing_shift) / ( - 1 + quality) - path_x.append(i) - path_y.append(y) - - return path_x, path_y, path_length - - def shift_point(self, p, p2, distance): - delta_y = p2.y - p.y - delta_x = p2.x - p.x - angle = 0 - if distance >= 0: - angle = math.atan2(delta_y, delta_x) + math.pi / 2.0 - else: - angle = math.atan2(delta_y, delta_x) - math.pi / 2.0 - p1n = [] - p1n.append(p.x + (math.cos(angle) * distance)) - p1n.append(p.y + (math.sin(angle) * distance)) - - p2n = [] - p2n.append(p2.x + (math.cos(angle) * distance)) - p2n.append(p2.y + (math.sin(angle) * distance)) - return p1n, p2n diff --git a/modules/tools/navigation/planning/speed_decider.py b/modules/tools/navigation/planning/speed_decider.py deleted file mode 100644 index 1396437bb5c..00000000000 --- a/modules/tools/navigation/planning/speed_decider.py +++ /dev/null @@ -1,51 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - - -class SpeedDecider: - def __init__(self, max_cruise_speed, enable_follow): - self.CRUISE_SPEED = max_cruise_speed # m/s - self.enable_follow = enable_follow - - def get_target_speed_and_path_length(self, mobileye_provider, - chassis_provider, path_length): - obstacle_closest_lon = 999 - obstacle_speed = None - obstacles = mobileye_provider.obstacles - for obs in obstacles: - if obs.lane == 1: - if (obs.x - obs.length / 2.0) < obstacle_closest_lon: - obstacle_closest_lon = obs.x - obs.length / 2.0 - obstacle_speed = obs.rel_speed + \ - chassis_provider.get_speed_mps() - - new_path_length = path_length - if obstacle_closest_lon < new_path_length: - new_path_length = obstacle_closest_lon - if obstacle_speed is None or obstacle_speed > self.CRUISE_SPEED: - return self.CRUISE_SPEED, new_path_length - else: - return obstacle_speed, new_path_length - - def get(self, mobileye_provider, chassis_provider, path_length): - if self.enable_follow: - return self.get_target_speed_and_path_length(mobileye_provider, - chassis_provider, - path_length) - else: - return self.CRUISE_SPEED, path_length diff --git a/modules/tools/navigation/planning/trajectory_generator.py b/modules/tools/navigation/planning/trajectory_generator.py deleted file mode 100644 index 880f7ab43d9..00000000000 --- a/modules/tools/navigation/planning/trajectory_generator.py +++ /dev/null @@ -1,72 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -import math -from numpy.polynomial.polynomial import polyval -from modules.common_msgs.planning_msgs import planning_pb2 -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.basic_msgs import drive_state_pb2 -from cyber.python.cyber_py3 import cyber_time - - -def euclidean_distance(point1, point2): - sum = (point1[0] - point2[0]) * (point1[0] - point2[0]) - sum += (point1[1] - point2[1]) * (point1[1] - point2[1]) - return math.sqrt(sum) - - -def get_theta(point, point_base): - # print point - return math.atan2(1, 0) - math.atan2(point[0] - point_base[0], - point[1] - point_base[1]) - - -class TrajectoryGenerator: - def __init__(self): - self.mobileye_pb = None - - def generate(self, path, final_path_length, speed, - start_timestamp): - path_x, path_y = path.get_xy() - adc_trajectory = planning_pb2.ADCTrajectory() - adc_trajectory.header.timestamp_sec = cyber_time.Time.now().to_sec() - adc_trajectory.header.module_name = "planning" - adc_trajectory.gear = chassis_pb2.Chassis.GEAR_DRIVE - adc_trajectory.latency_stats.total_time_ms = \ - (cyber_time.Time.now().to_sec() - start_timestamp) * 1000 - s = 0 - relative_time = 0 - adc_trajectory.engage_advice.advice \ - = drive_state_pb2.EngageAdvice.READY_TO_ENGAGE - - for x in range(int(final_path_length - 1)): - y = path_y[x] - - traj_point = adc_trajectory.trajectory_point.add() - traj_point.path_point.x = x - traj_point.path_point.y = y - if x > 0: - dist = euclidean_distance((x, y), (x - 1, path_y[x - 1])) - s += dist - relative_time += dist / speed - - traj_point.path_point.theta = get_theta( - (x + 1, path_y[x + 1]), (0, path_y[0])) - traj_point.path_point.s = s - traj_point.v = speed - traj_point.relative_time = relative_time - return adc_trajectory diff --git a/modules/tools/navigator/BUILD b/modules/tools/navigator/BUILD deleted file mode 100644 index ae80ff1fa60..00000000000 --- a/modules/tools/navigator/BUILD +++ /dev/null @@ -1,22 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary") - -package(default_visibility = ["//visibility:public"]) - -py_binary( - name = "viewer_raw", - srcs = ["viewer_raw.py"], -) - -py_binary( - name = "viewer_smooth", - srcs = ["viewer_smooth.py"], -) - -py_binary( - name = "record_extractor", - srcs = ["record_extractor.py"], - deps = [ - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - ], -) \ No newline at end of file diff --git a/modules/tools/navigator/README.md b/modules/tools/navigator/README.md deleted file mode 100644 index f5227178ffc..00000000000 --- a/modules/tools/navigator/README.md +++ /dev/null @@ -1,59 +0,0 @@ -# Steps for - -- Generating navigation data from bag and -- Manually sending the data to /apollo/navigation topic - -### Step 1: In dev docker, extract path data from bags - -``` -dev_docker:/apollo$cd /modules/tools/navigator -dev_docker:/apollo/modules/tools/navigator$python extractor.py path-to-bags/*.bag -``` - -A path file will be generated in - -``` -dev_docker:/apollo/modules/tools/navigator$ -``` - -With format of - -``` -path_[first_bag_name].bag.txt -``` - - - -### Step2: (Optional) Verify the extracted path is correct - -dev_docker:/apollo/modules/tools/navigator$python viewer_raw.py path_[bag_name].bag.txt - -### Step3: Smooth the path - -``` -dev_docker:/apollo/modules/tools/navigator$./smooth.sh /apollo/modules/tools/navigator/path_[first_bag_name].bag.txt 200 -``` - -200 is the parameter for smooth length. If the smooth is failed, try to change this parameter to make the smooth pass. The preferred number is between 150 and 200. - -A smoothed data file, path_[first_bag_name].bag.txt.smoothed, is generated under folder - -``` -dev_docker:/apollo/modules/tools/navigator$ -``` - -### Step4: (Optional) Verify the smoothed data - -``` -dev_docker:/apollo/modules/tools/navigator$ python viewer_smooth.py path[first_bag_name].bag.txt path[first_bag_name].bag.txt.smoothed -``` - - - -### Step5: Send /apollo/navigation topic - -Run follow command to send /apollo/navigation data - -``` -dev_docker:/apollo/modules/tools/navigator$python navigator.py path_[first_bag_name].bag.txt.smoothed -``` \ No newline at end of file diff --git a/modules/tools/navigator/dbmap/BUILD b/modules/tools/navigator/dbmap/BUILD deleted file mode 100644 index b19cef78326..00000000000 --- a/modules/tools/navigator/dbmap/BUILD +++ /dev/null @@ -1,19 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") - -package(default_visibility = ["//visibility:public"]) - -py_library( - name = "generator", - srcs = ["generator.py"], - deps = [ - "//modules/common_msgs/planning_msgs:navigation_py_pb2", - ], -) - -py_binary( - name = "viewer", - srcs = ["viewer.py"], - deps = [ - "//modules/common_msgs/planning_msgs:navigation_py_pb2", - ], -) diff --git a/modules/tools/navigator/dbmap/README.md b/modules/tools/navigator/dbmap/README.md deleted file mode 100644 index 36bf5894cb1..00000000000 --- a/modules/tools/navigator/dbmap/README.md +++ /dev/null @@ -1,5 +0,0 @@ -# Driving Behavior Map (DBMap) - -DBMap is learned and generated based on human driving behaviors. - - diff --git a/modules/tools/navigator/dbmap/generator.py b/modules/tools/navigator/dbmap/generator.py deleted file mode 100644 index cf01210c4e4..00000000000 --- a/modules/tools/navigator/dbmap/generator.py +++ /dev/null @@ -1,59 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -from datetime import datetime -import json -import sys - -from modules.common_msgs.planning_msgs import navigation_pb2 - - -if __name__ == '__main__': - if len(sys.argv) < 2: - print("usage: python generator.py " - "navi_line1.smoothed navi_line2.smoothed ...") - sys.exit(0) - navi_files = sys.argv[1:] - # generate navigation info - navigation_info = navigation_pb2.NavigationInfo() - priority = 0 - for fdata in navi_files: - print("processing " + fdata) - navigation_path = navigation_info.navigation_path.add() - navigation_path.path_priority = priority - priority += 1 - navigation_path.path.name = "navigation" - - with open(fdata, 'r') as f: - cnt = 0 - for line in f: - cnt += 1 - if cnt < 3: - continue - json_point = json.loads(line) - point = navigation_path.path.path_point.add() - point.x = json_point['x'] - point.y = json_point['y'] - point.s = json_point['s'] - point.theta = json_point['theta'] - point.kappa = json_point['kappa'] - point.dkappa = json_point['dkappa'] - - datetime_str = datetime.now().strftime("%Y%m%d_%H%M%S") - with open(datetime_str + ".dbmap", 'w') as f: - f.write(str(navigation_info)) diff --git a/modules/tools/navigator/dbmap/libs/BUILD b/modules/tools/navigator/dbmap/libs/BUILD deleted file mode 100644 index adafcb2ed53..00000000000 --- a/modules/tools/navigator/dbmap/libs/BUILD +++ /dev/null @@ -1,8 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_library") - -package(default_visibility = ["//visibility:public"]) - -py_library( - name = "point", - srcs = ["point.py"], -) diff --git a/modules/tools/navigator/dbmap/libs/point.py b/modules/tools/navigator/dbmap/libs/point.py deleted file mode 100644 index 0c2b0916275..00000000000 --- a/modules/tools/navigator/dbmap/libs/point.py +++ /dev/null @@ -1,69 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import pyproj -import math - - -class PointUtils: - """point utils""" - - @staticmethod - def utm2latlon(x, y, zone): - """utm to latlon""" - proj = pyproj.Proj(proj='utm', zone=zone, ellps='WGS84') - lon, lat = proj(x, y, inverse=True) - return lat, lon - - @staticmethod - def latlon2utm(lat, lon): - """latlon to utm""" - zone = PointUtils.latlon2utmzone(lat, lon) - projector2 = pyproj.Proj(proj='utm', zone=zone, ellps='WGS84') - x, y = projector2(lon, lat) - return x, y, zone - - @staticmethod - def latlon2utmzone(lat, lon): - """latlon to utm zone""" - zone_num = math.floor((lon + 180) / 6) + 1 - if 56.0 <= lat < 64.0 and 3.0 <= lon < 12.0: - zone_num = 32 - if 72.0 <= lat < 84.0: - if 0.0 <= lon < 9.0: - zone_num = 31 - elif 9.0 <= lon < 21.0: - zone_num = 33 - elif 21.0 <= lon < 33.0: - zone_num = 35 - elif 33.0 <= lon < 42.0: - zone_num = 37 - return zone_num - - @staticmethod - def latlon2latlondict(lat, lon): - """latlon to latlon dictionary""" - return {'lat': lat, 'lng': lon} - - @staticmethod - def utm2grididx(x, y, resolution_mm): - """utm to grid index""" - index_str = str(int(round(x / resolution_mm)) * resolution_mm) - index_str += "," - index_str += str(int(round(y / resolution_mm)) * resolution_mm) - return index_str diff --git a/modules/tools/navigator/dbmap/proto/BUILD b/modules/tools/navigator/dbmap/proto/BUILD deleted file mode 100644 index 4d111a0cb3e..00000000000 --- a/modules/tools/navigator/dbmap/proto/BUILD +++ /dev/null @@ -1,25 +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") - -package(default_visibility = ["//visibility:public"]) - -cc_proto_library( - name = "dbmap_cc_proto", - deps = [ - ":dbmap_proto", - ], -) - -proto_library( - name = "dbmap_proto", - srcs = ["dbmap.proto"], -) - -py_proto_library( - name = "dbmap_py_pb2", - deps = [ - ":dbmap_proto", - ], -) diff --git a/modules/tools/navigator/dbmap/proto/dbmap.proto b/modules/tools/navigator/dbmap/proto/dbmap.proto deleted file mode 100644 index 43040e977cd..00000000000 --- a/modules/tools/navigator/dbmap/proto/dbmap.proto +++ /dev/null @@ -1,41 +0,0 @@ -syntax = "proto2"; - -package apollo.dbmap; - -message DBPoint { - optional double x = 1; - optional double y = 2; - optional double z = 3; - optional double s = 4; - optional double heading = 5; -} - -message DBLine { - repeated DBPoint point = 1; -} - -message DBNeighbourSegment { - optional double start_s = 1; - optional double end_s = 2; - optional string path_id = 3; - optional double path_start_s = 4; - optional double path_end_s = 5; -} - -message DBNeighbourPath { - repeated DBNeighbourSegment segment = 1; -} - -message DBPath { - optional string id = 1; - repeated DBLine path = 2; - repeated DBLine left_bounday = 3; - repeated DBLine right_bounday = 4; - repeated DBNeighbourPath left_path = 5; - repeated DBNeighbourPath right_path = 6; - repeated DBNeighbourPath duplicate_path = 7; -} - -message DBMap { - repeated DBPath paths = 1; -} diff --git a/modules/tools/navigator/dbmap/setup.sh b/modules/tools/navigator/dbmap/setup.sh deleted file mode 100755 index c93e3d99bb1..00000000000 --- a/modules/tools/navigator/dbmap/setup.sh +++ /dev/null @@ -1,3 +0,0 @@ -SRC_DIR=./proto -DST_DIR=./proto -protoc -I=$SRC_DIR --python_out=$DST_DIR $SRC_DIR/*.proto diff --git a/modules/tools/navigator/dbmap/viewer.py b/modules/tools/navigator/dbmap/viewer.py deleted file mode 100644 index e0f6b7914a5..00000000000 --- a/modules/tools/navigator/dbmap/viewer.py +++ /dev/null @@ -1,141 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import json -import sys - -from yattag import Doc -import pyproj - -from modules.common_msgs.planning_msgs import navigation_pb2 -import modules.tool.common.proto_utils as proto_utils - - -class DBMapViewer: - def __init__(self, utm_zone): - """ - init function - """ - self.utm_zone = utm_zone - self.projector = pyproj.Proj( - proj='utm', zone=self.utm_zone, ellps='WGS84') - - self.navigation_lines = [] - self.center_lat = None - self.center_lon = None - self.html = "" - - def utm2latlon(self, x, y): - """ - convert the utm x y to lat and lon - """ - lon, lat = self.projector(x, y, inverse=True) - return lat, lon - - def add(self, dbmap): - for navigation_path in dbmap.navigation_path: - navigation_line = [] - for p in navigation_path.path.path_point: - point = {} - lat, lng = self.utm2latlon(p.x, p.y) - if self.center_lat is None: - self.center_lat = lat - if self.center_lon is None: - self.center_lon = lng - point['lat'] = lat - point['lng'] = lng - navigation_line.append(point) - self.navigation_lines.append(navigation_line) - - def generate(self): - """ - function to generate html code. - """ - doc, tag, text, line = Doc().ttl() - doc.asis('') - api_url = 'http://maps.google.com/maps/api/js?sensor=' \ - 'false&callback=initMap' - with tag('html'): - with tag('head'): - with tag('title'): - text('Gmap Viewer') - doc.asis('') - doc.asis('') - with tag('style'): - doc.asis('#map { height: 100%; }') - doc.asis( - 'html, body { height: 100%; margin: 0; padding: 0; }') - with tag('body'): - with tag('div', id='map'): - pass - with tag('script'): - doc.asis('\nvar map;\n') - doc.asis("\nvar colors = ['#e6194b', '#3cb44b', '#ffe119', " - "'#0082c8', '#f58231', '#911eb4', '#46f0f0', " - "'#f032e6', '#d2f53c', '#fabebe', '#008080', " - "'#e6beff', '#aa6e28', '#fffac8', '#800000', " - "'#aaffc3', '#808000', '#ffd8b1', '#000080', " - "'#808080', '#000000']\n") - doc.asis('function initMap() {\n') - doc.asis("map = new google.maps.Map(" - "document.getElementById('map'), {\n") - doc.asis('center: {lat: ' + str(self.center_lat) + - ', lng: ' + str(self.center_lon) + '},\n') - doc.asis('zoom: 16\n') - doc.asis('});\n') - doc.asis('var navi_lines = ' + - json.dumps(self.navigation_lines) + ';\n') - doc.asis(""" - for (var i = 0; i < navi_lines.length; i++) { - var boundary = new google.maps.Polyline({ - path: navi_lines[i], - geodesic: true, - strokeColor: colors[i % colors.length], - strokeOpacity: 1.0, - strokeWeight: 3 - }); - boundary.setMap(map); - } - """) - doc.asis('}\n') - doc.asis('') - self.html = doc.getvalue() - return self.html - - -if __name__ == "__main__": - import google.protobuf.text_format as text_format - - if len(sys.argv) < 2: - print("usage: python map_viewer.py dbmap_file [utm_zone=10]") - sys.exit(0) - - map_file = sys.argv[1] - utm_zone = 10 - if len(sys.argv) >= 3: - utm_zone = int(sys.argv[2]) - - dbmap = navigation_pb2.NavigationInfo() - proto_utils.get_pb_from_file(map_file, dbmap) - with open(map_file, 'r') as file_in: - text_format.Merge(file_in.read(), dbmap) - viewer = DBMapViewer(utm_zone) - viewer.add(dbmap) - html = viewer.generate() - with open('dbmap.html', 'w') as f: - f.write(html) diff --git a/modules/tools/navigator/record_extractor.py b/modules/tools/navigator/record_extractor.py deleted file mode 100644 index 765cf68ea0f..00000000000 --- a/modules/tools/navigator/record_extractor.py +++ /dev/null @@ -1,41 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import sys -from datetime import datetime -from cyber.python.cyber_py3.record import RecordReader -from modules.common_msgs.localization_msgs import localization_pb2 - -if __name__ == '__main__': - if len(sys.argv) < 2: - print("usage: python record_extractor.py record_file1 record_file2 ...") - - frecords = sys.argv[1:] - now = datetime.now().strftime("%Y-%m-%d_%H.%M.%S") - - with open("path_" + frecords[0].split('/')[-1] + ".txt", 'w') as f: - for frecord in frecords: - print("processing " + frecord) - reader = RecordReader(frecord) - for msg in reader.read_messages(): - if msg.topic == "/apollo/localization/pose": - localization = localization_pb2.LocalizationEstimate() - localization.ParseFromString(msg.message) - x = localization.pose.position.x - y = localization.pose.position.y - f.write(str(x) + "," + str(y) + "\n") diff --git a/modules/tools/navigator/smooth.sh b/modules/tools/navigator/smooth.sh deleted file mode 100644 index acebbba8b7f..00000000000 --- a/modules/tools/navigator/smooth.sh +++ /dev/null @@ -1,26 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -# Get the absolute path. -dir=$(cd "$(dirname "$1" )" && pwd) -filename=$(basename $1) -pathname="${dir}/${filename}" -#echo ${pathname} -cd /apollo -./bazel-bin/modules/planning/reference_line/spiral_smoother_util --input_file ${pathname} --smooth_length $2 - diff --git a/modules/tools/navigator/viewer_raw.py b/modules/tools/navigator/viewer_raw.py deleted file mode 100644 index 3f373358e12..00000000000 --- a/modules/tools/navigator/viewer_raw.py +++ /dev/null @@ -1,43 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import sys -import matplotlib.pyplot as plt - -fig = plt.figure() -ax = plt.subplot2grid((1, 1), (0, 0)) -styles = ["b-", "r-", "y-"] -i = 0 -for fn in sys.argv[1:]: - f = open(fn, 'r') - xs = [] - ys = [] - for line in f: - line = line.replace("\n", '') - data = line.split(',') - x = float(data[0]) - y = float(data[1]) - xs.append(x) - ys.append(y) - f.close() - si = i % len(styles) - ax.plot(xs, ys, styles[si], lw=3, alpha=0.8) - i += 1 - -ax.axis('equal') -plt.show() diff --git a/modules/tools/navigator/viewer_smooth.py b/modules/tools/navigator/viewer_smooth.py deleted file mode 100644 index 38ddca44bd1..00000000000 --- a/modules/tools/navigator/viewer_smooth.py +++ /dev/null @@ -1,110 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import sys -import json -import matplotlib.pyplot as plt - -import numpy -from scipy.signal import butter, lfilter, freqz - - -def get_s_xy_kappa(fn, ax, ax2): - f = open(fn, 'r') - xs = [] - ys = [] - ks = [] - theta = [] - s = [] - cnt = 0 - for line in f: - cnt += 1 - if cnt < 3: - continue - line = line.replace("\n", '') - data = json.loads(line) - ks.append(data['kappa']) - s.append(data['s']) - xs.append(data['x']) - ys.append(data['y']) - theta.append(data['theta']) - f.close() - return s, xs, ys, theta, ks - - -def plot_raw_path(fn, ax): - f = open(fn, 'r') - xs = [] - ys = [] - for line in f: - line = line.replace("\n", '') - data = line.split(',') - x = float(data[0]) - y = float(data[1]) - xs.append(x) - ys.append(y) - f.close() - ax.plot(xs, ys, "r-", lw=3, alpha=0.8) - - -if __name__ == "__main__": - fig = plt.figure() - ax = plt.subplot2grid((2, 2), (0, 0)) - ax2 = plt.subplot2grid((2, 2), (0, 1)) - ax3 = plt.subplot2grid((2, 2), (1, 0)) - ax4 = plt.subplot2grid((2, 2), (1, 1)) - - styles = ["bo", "ro", "yo"] - i = 0 - - fn = sys.argv[1] - plot_raw_path(fn, ax) - - fn = sys.argv[2] - s, xs, ys, theta, ks = get_s_xy_kappa(fn, ax, ax2) - ax.plot(xs, ys, "b-", lw=8, alpha=0.5) - ax.set_title("x-y") - - ax2.plot(s, ks, 'k-') - ax2.set_title("s-kappa") - ax2.axhline(y=0.0, color='b', linestyle='-') - - ax3.plot(s, theta, 'k-') - ax3.set_title("s-theta") - - ax4.plot(s, s, 'k-') - ax4.set_title("s-s") - - if len(sys.argv) >= 4: - fn = sys.argv[3] - s, xs, ys, theta, ks = get_s_xy_kappa(fn, ax, ax2) - ax.plot(xs, ys, "r-", lw=8, alpha=0.5) - ax.set_title("x-y") - - ax2.plot(s, ks, 'r-') - ax2.set_title("s-kappa") - ax2.axhline(y=0.0, color='b', linestyle='-') - - ax3.plot(s, theta, 'r-') - ax3.set_title("s-theta") - - ax4.plot(s, s, 'r-') - ax4.set_title("s-s") - - ax.axis('equal') - plt.show() diff --git a/modules/tools/open_space_visualization/BUILD b/modules/tools/open_space_visualization/BUILD deleted file mode 100644 index 976c45158aa..00000000000 --- a/modules/tools/open_space_visualization/BUILD +++ /dev/null @@ -1,63 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -py_library( - name = "distance_approach_python_interface", - srcs = ["distance_approach_python_interface.py"], - data = [ - "//modules/planning/open_space/tools:distance_approach_problem_wrapper_lib.so", - ], -) - -py_binary( - name = "distance_approach_visualizer", - srcs = ["distance_approach_visualizer.py"], - deps = [ - ":distance_approach_python_interface", - ], -) - -py_library( - name = "hybrid_a_star_python_interface", - srcs = ["hybrid_a_star_python_interface.py"], - data = [ - "//modules/planning/open_space/tools:hybrid_a_star_wrapper_lib.so", - ], -) - -py_binary( - name = "hybrid_a_star_visualizer", - srcs = ["hybrid_a_star_visualizer.py"], - deps = [ - ":hybrid_a_star_python_interface", - ], -) - -py_library( - name = "open_space_roi_interface", - srcs = ["open_space_roi_interface.py"], - data = [ - "//modules/planning/open_space/tools:open_space_roi_wrapper_lib.so", - ], -) - -py_binary( - name = "open_space_roi_visualizer", - srcs = ["open_space_roi_visualizer.py"], - deps = [ - ":open_space_roi_interface", - ], -) - -install( - name = "install", - py_dest = "tools/open_space_visualization", - targets = [ - ":open_space_roi_interface", - ":hybrid_a_star_python_interface", - ":distance_approach_python_interface", - ":distance_approach_visualizer", - ] -) \ No newline at end of file diff --git a/modules/tools/open_space_visualization/auto_param_tuning.py b/modules/tools/open_space_visualization/auto_param_tuning.py deleted file mode 100755 index 51d9b0a92bf..00000000000 --- a/modules/tools/open_space_visualization/auto_param_tuning.py +++ /dev/null @@ -1,169 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import argparse -import random - -from google.protobuf.internal import decoder -from google.protobuf.internal import encoder - -from modules.common_msgs.planning_msgs import planner_open_space_config_pb2 -import modules.tools.common.proto_utils as proto_utils -import distance_approach_visualizer -import hybrid_a_star_visualizer - - -random.seed(99999) -rand_num = 1000 -original_file_path = "/apollo/modules/planning/conf/planner_open_space_config.pb.txt" -optimal_file_path = "/apollo/modules/planning/conf/optimal_planner_open_space_config_-8_4.pb.txt" -# tunning_object = "coarse_trajectory" -tunning_object = "smooth_trajectory" - - -def load_open_space_protobuf(filename): - open_space_params = planner_open_space_config_pb2.PlannerOpenSpaceConfig() - proto_utils.get_pb_from_text_file(filename, open_space_params) - return open_space_params - - -def GetParamsForTunning(tunning_object): - param_names_and_range = [] - if tunning_object == "coarse_trajectory": - param_names_and_range.append( - ("warm_start_config.traj_forward_penalty", 2.0)) - param_names_and_range.append( - ("warm_start_config.traj_back_penalty", 2.0)) - param_names_and_range.append( - ("warm_start_config.traj_gear_switch_penalty", 2.0)) - param_names_and_range.append( - ("warm_start_config.traj_steer_penalty", 3.0)) - param_names_and_range.append( - ("warm_start_config.traj_steer_change_penalty", 2.0)) - elif tunning_object == "smooth_trajectory": - param_names_and_range.append( - ("distance_approach_config.weight_steer", 2.0)) - param_names_and_range.append( - ("distance_approach_config.weight_a", 2.0)) - param_names_and_range.append( - ("distance_approach_config.weight_steer_rate", 2.0)) - param_names_and_range.append( - ("distance_approach_config.weight_a_rate", 2.0)) - param_names_and_range.append( - ("distance_approach_config.weight_x", 2.0)) - param_names_and_range.append( - ("distance_approach_config.weight_y", 2.0)) - param_names_and_range.append( - ("distance_approach_config.weight_phi", 2.0)) - param_names_and_range.append( - ("distance_approach_config.weight_v", 2.0)) - param_names_and_range.append( - ("distance_approach_config.weight_steer_stitching", 2.0)) - param_names_and_range.append( - ("distance_approach_config.weight_a_stitching", 2.0)) - param_names_and_range.append( - ("distance_approach_config.weight_first_order_time", 2.0)) - param_names_and_range.append( - ("distance_approach_config.weight_second_order_time", 2.0)) - return param_names_and_range - - -def RandSampling(param_names_and_range, origin_open_space_params): - params_lists = [] - for iter in range(0, rand_num): - rand_params = planner_open_space_config_pb2.PlannerOpenSpaceConfig() - rand_params.CopyFrom(origin_open_space_params) - for param in param_names_and_range: - exec("rand_params." + - str(param[0]) + "=random.uniform(max(rand_params." + - str(param[0]) - + " - " + str(param[1]) + ",0.0)" - + " ,rand_params." + str(param[0]) + " + " + str(param[1]) + ")") - params_lists.append(rand_params) - return params_lists - - -def TestingParams(params_lists, tunning_object): - key_to_evaluations = {} - for iter in range(0, len(params_lists)): - evaluation = ParamEvaluation(params_lists[iter], tunning_object) - key_to_evaluations[iter] = evaluation - return key_to_evaluations - - -def ParamEvaluation(params, tunning_object): - proto_utils.write_pb_to_text_file(params, original_file_path) - if tunning_object == "coarse_trajectory": - visualize_flag = False - success, x_out, y_out, phi_out, v_out, a_out, steer_out, planning_time = hybrid_a_star_visualizer.HybridAStarPlan( - visualize_flag) - if not success: - return float('inf') - else: - return planning_time - elif tunning_object == "smooth_trajectory": - visualize_flag = False - success, opt_x_out, opt_y_out, opt_phi_out, opt_v_out, opt_a_out, opt_steer_out, opt_time_out, planning_time = distance_approach_visualizer.SmoothTrajectory( - visualize_flag) - if not success: - return float('inf') - else: - return planning_time - - -def GetOptimalParams(params_lists, key_to_evaluations): - tmp = [] - for key, value in key_to_evaluations.items(): - tmptuple = (value, key) - tmp.append(tmptuple) - - tmp = sorted(tmp) - optimal_params = params_lists[tmp[0][1]] - optimal_evaluation = tmp[0][0] - return optimal_params, optimal_evaluation - - -if __name__ == '__main__': - parser = argparse.ArgumentParser() - parser.add_argument( - "--InputConfig", help="original conf address to be tuned", type=str, default=original_file_path) - parser.add_argument("--OutputConfig", help="tuned conf address", - type=str, default=optimal_file_path) - parser.add_argument("--TunningObject", - help="algorithm to be tuned", type=str, default=tunning_object) - args = parser.parse_args() - original_file_path = args.InputConfig - optimal_file_path = args.OutputConfig - tunning_object = args.TunningObject - param_names_and_range = GetParamsForTunning(tunning_object) - origin_open_space_params = load_open_space_protobuf(original_file_path) - params_lists = RandSampling( - param_names_and_range, origin_open_space_params) - key_to_evaluations = TestingParams(params_lists, tunning_object) - optimal_params, optimal_evaluation = GetOptimalParams( - params_lists, key_to_evaluations) - origin_evaluation = ParamEvaluation( - origin_open_space_params, tunning_object) - print("optimal_evaluation is " + str(optimal_evaluation)) - print("origin_evaluation is " + str(origin_evaluation)) - improvement_percentage = ( - origin_evaluation - optimal_evaluation) / origin_evaluation - print("improvement_percentage is " + str(improvement_percentage)) - proto_utils.write_pb_to_text_file(optimal_params, optimal_file_path) - proto_utils.write_pb_to_text_file( - origin_open_space_params, original_file_path) diff --git a/modules/tools/open_space_visualization/distance_approach_python_interface.py b/modules/tools/open_space_visualization/distance_approach_python_interface.py deleted file mode 100755 index fb7c7ca78ac..00000000000 --- a/modules/tools/open_space_visualization/distance_approach_python_interface.py +++ /dev/null @@ -1,74 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math - -from ctypes import c_bool -from ctypes import c_double -from ctypes import c_ushort -from ctypes import c_void_p -from ctypes import cdll, POINTER - - -lib = cdll.LoadLibrary( - '/apollo/bazel-bin/modules/planning/open_space/tools/distance_approach_problem_wrapper_lib.so') - -lib.CreateHybridAPtr.argtypes = [] -lib.CreateHybridAPtr.restype = c_void_p -lib.DistanceCreateResultPtr.argtypes = [] -lib.DistanceCreateResultPtr.restype = c_void_p -lib.DistanceCreateObstaclesPtr.argtypes = [] -lib.DistanceCreateObstaclesPtr.restype = c_void_p -lib.AddObstacle.argtypes = [c_void_p, POINTER(c_double)] -lib.DistancePlan.restype = c_bool -lib.DistancePlan.argtypes = [c_void_p, c_void_p, c_void_p, c_double, c_double, c_double, c_double, - c_double, c_double, POINTER(c_double)] -lib.DistanceGetResult.argtypes = [c_void_p, c_void_p, POINTER(c_double), POINTER(c_double), POINTER(c_double), - POINTER(c_double), POINTER(c_double), POINTER( - c_double), POINTER(c_double), - POINTER(c_double), POINTER(c_double), POINTER( - c_double), POINTER(c_double), - POINTER(c_double), POINTER(c_double), POINTER( - c_double), POINTER(c_double), - POINTER(c_ushort), POINTER(c_double), POINTER(c_double), POINTER(c_double)] - - -class DistancePlanner(object): - def __init__(self): - self.warm_start_planner = lib.CreateHybridAPtr() - self.obstacles = lib.DistanceCreateObstaclesPtr() - self.result = lib.DistanceCreateResultPtr() - - def AddObstacle(self, ROI_distance_approach_parking_boundary): - lib.AddObstacle(self.obstacles, POINTER( - c_double)(ROI_distance_approach_parking_boundary)) - - def DistancePlan(self, sx, sy, sphi, ex, ey, ephi, XYbounds): - return lib.DistancePlan(self.warm_start_planner, self.obstacles, self.result, c_double(sx), - c_double(sy), c_double(sphi), c_double(ex), c_double(ey), c_double(ephi), POINTER(c_double)(XYbounds)) - - def DistanceGetResult(self, x, y, phi, v, a, steer, opt_x, opt_y, opt_phi, opt_v, opt_a, opt_steer, opt_time, - opt_dual_l, opt_dual_n, output_size, hybrid_time, dual_time, ipopt_time): - lib.DistanceGetResult(self.result, self.obstacles, POINTER(c_double)(x), POINTER(c_double)(y), - POINTER(c_double)(phi), POINTER(c_double)(v), POINTER(c_double)(a), POINTER( - c_double)(steer), POINTER(c_double)(opt_x), POINTER(c_double)(opt_y), - POINTER(c_double)(opt_phi), POINTER(c_double)(opt_v), POINTER(c_double)(opt_a), - POINTER(c_double)(opt_steer), POINTER(c_double)( - opt_time), POINTER(c_double)(opt_dual_l), - POINTER(c_double)(opt_dual_n), POINTER(c_ushort)(output_size), - POINTER(c_double)(hybrid_time), POINTER(c_double)(dual_time), POINTER(c_double)(ipopt_time)) diff --git a/modules/tools/open_space_visualization/distance_approach_visualizer.py b/modules/tools/open_space_visualization/distance_approach_visualizer.py deleted file mode 100755 index 947c5cd4a0d..00000000000 --- a/modules/tools/open_space_visualization/distance_approach_visualizer.py +++ /dev/null @@ -1,316 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math -import time - -from matplotlib import animation -import matplotlib.patches as patches -import matplotlib.pyplot as plt -import numpy as np - -from distance_approach_python_interface import * - - -result_file = "/tmp/open_space_osqp_ipopt.csv" - - -# def SmoothTrajectory(visualize_flag): -def SmoothTrajectory(visualize_flag, sx, sy): - # initialze object - OpenSpacePlanner = DistancePlanner() - - # parameter(except max, min and car size is defined in proto) - num_output_buffer = 10000 - # sx = -8 - # sy = 1.5 - # sphi = 0.5 - sphi = 0.0 - - scenario = "backward" - # scenario = "parallel" - - if scenario == "backward": - # obstacles for distance approach(vertices coords in clock wise order) - ROI_distance_approach_parking_boundary = ( - c_double * 20)(*[-13.6407054776, - 0.0140634663703, - 0.0, - 0.0, - 0.0515703622475, - -5.15258191624, - 0.0515703622475, - -5.15258191624, - 2.8237895441, - -5.15306980547, - 2.8237895441, - -5.15306980547, - 2.7184833539, - -0.0398078878812, - 16.3592013995, - -0.011889513383, - 16.3591910364, - 5.60414234644, - -13.6406951857, - 5.61797800844, - ]) - OpenSpacePlanner.AddObstacle( - ROI_distance_approach_parking_boundary) - # parking lot position - ex = 1.359 - ey = -3.86443643718 - ephi = 1.581 - XYbounds = [-13.6406951857, 16.3591910364, -5.15258191624, 5.61797800844] - - x = (c_double * num_output_buffer)() - y = (c_double * num_output_buffer)() - phi = (c_double * num_output_buffer)() - v = (c_double * num_output_buffer)() - a = (c_double * num_output_buffer)() - steer = (c_double * num_output_buffer)() - opt_x = (c_double * num_output_buffer)() - opt_y = (c_double * num_output_buffer)() - opt_phi = (c_double * num_output_buffer)() - opt_v = (c_double * num_output_buffer)() - opt_a = (c_double * num_output_buffer)() - opt_steer = (c_double * num_output_buffer)() - opt_time = (c_double * num_output_buffer)() - opt_dual_l = (c_double * num_output_buffer)() - opt_dual_n = (c_double * num_output_buffer)() - size = (c_ushort * 1)() - XYbounds_ctype = (c_double * 4)(*XYbounds) - hybrid_time = (c_double * 1)(0.0) - dual_time = (c_double * 1)(0.0) - ipopt_time = (c_double * 1)(0.0) - - success = True - start = time.time() - print("planning start") - if not OpenSpacePlanner.DistancePlan(sx, sy, sphi, ex, ey, ephi, XYbounds_ctype): - print("planning fail") - success = False - # exit() - planning_time = time.time() - start - print("planning time is " + str(planning_time)) - - x_out = [] - y_out = [] - phi_out = [] - v_out = [] - a_out = [] - steer_out = [] - opt_x_out = [] - opt_y_out = [] - opt_phi_out = [] - opt_v_out = [] - opt_a_out = [] - opt_steer_out = [] - opt_time_out = [] - opt_dual_l_out = [] - opt_dual_n_out = [] - - if visualize_flag and success: - # load result - OpenSpacePlanner.DistanceGetResult(x, y, phi, v, a, steer, opt_x, - opt_y, opt_phi, opt_v, opt_a, opt_steer, opt_time, - opt_dual_l, opt_dual_n, size, - hybrid_time, dual_time, ipopt_time) - for i in range(0, size[0]): - x_out.append(float(x[i])) - y_out.append(float(y[i])) - phi_out.append(float(phi[i])) - v_out.append(float(v[i])) - a_out.append(float(a[i])) - steer_out.append(float(steer[i])) - opt_x_out.append(float(opt_x[i])) - opt_y_out.append(float(opt_y[i])) - opt_phi_out.append(float(opt_phi[i])) - opt_v_out.append(float(opt_v[i])) - opt_a_out.append(float(opt_a[i])) - opt_steer_out.append(float(opt_steer[i])) - opt_time_out.append(float(opt_time[i])) - - for i in range(0, size[0] * 6): - opt_dual_l_out.append(float(opt_dual_l[i])) - for i in range(0, size[0] * 16): - opt_dual_n_out.append(float(opt_dual_n[i])) - # trajectories plot - fig1 = plt.figure(1) - ax = fig1.add_subplot(111) - for i in range(0, size[0]): - # warm start - downx = 1.055 * math.cos(phi_out[i] - math.pi / 2) - downy = 1.055 * math.sin(phi_out[i] - math.pi / 2) - leftx = 1.043 * math.cos(phi_out[i] - math.pi) - lefty = 1.043 * math.sin(phi_out[i] - math.pi) - x_shift_leftbottom = x_out[i] + downx + leftx - y_shift_leftbottom = y_out[i] + downy + lefty - warm_start_car = patches.Rectangle((x_shift_leftbottom, y_shift_leftbottom), 3.89 + 1.043, 1.055 * 2, - angle=phi_out[i] * 180 / math.pi, linewidth=1, edgecolor='r', facecolor='none') - warm_start_arrow = patches.Arrow( - x_out[i], y_out[i], 0.25 * math.cos(phi_out[i]), 0.25 * math.sin(phi_out[i]), 0.2, edgecolor='r',) - # ax.add_patch(warm_start_car) - ax.add_patch(warm_start_arrow) - # distance approach - downx = 1.055 * math.cos(opt_phi_out[i] - math.pi / 2) - downy = 1.055 * math.sin(opt_phi_out[i] - math.pi / 2) - leftx = 1.043 * math.cos(opt_phi_out[i] - math.pi) - lefty = 1.043 * math.sin(opt_phi_out[i] - math.pi) - x_shift_leftbottom = opt_x_out[i] + downx + leftx - y_shift_leftbottom = opt_y_out[i] + downy + lefty - smoothing_car = patches.Rectangle((x_shift_leftbottom, y_shift_leftbottom), 3.89 + 1.043, 1.055 * 2, - angle=opt_phi_out[i] * 180 / math.pi, linewidth=1, edgecolor='y', facecolor='none') - smoothing_arrow = patches.Arrow( - opt_x_out[i], opt_y_out[i], 0.25 * math.cos(opt_phi_out[i]), 0.25 * math.sin(opt_phi_out[i]), 0.2, edgecolor='y',) - ax.add_patch(smoothing_car) - ax.add_patch(smoothing_arrow) - - ax.plot(sx, sy, "s") - ax.plot(ex, ey, "s") - if scenario == "backward": - left_boundary_x = [-13.6407054776, 0.0, 0.0515703622475] - left_boundary_y = [0.0140634663703, 0.0, -5.15258191624] - down_boundary_x = [0.0515703622475, 2.8237895441] - down_boundary_y = [-5.15258191624, -5.15306980547] - right_boundary_x = [2.8237895441, 2.7184833539, 16.3592013995] - right_boundary_y = [-5.15306980547, -0.0398078878812, -0.011889513383] - up_boundary_x = [16.3591910364, -13.6406951857] - up_boundary_y = [5.60414234644, 5.61797800844] - ax.plot(left_boundary_x, left_boundary_y, "k") - ax.plot(down_boundary_x, down_boundary_y, "k") - ax.plot(right_boundary_x, right_boundary_y, "k") - ax.plot(up_boundary_x, up_boundary_y, "k") - - plt.axis('equal') - - # input plot - fig2 = plt.figure(2) - v_graph = fig2.add_subplot(411) - v_graph.title.set_text('v') - v_graph.plot(np.linspace(0, size[0], size[0]), v_out) - v_graph.plot(np.linspace(0, size[0], size[0]), opt_v_out) - a_graph = fig2.add_subplot(412) - a_graph.title.set_text('a') - a_graph.plot(np.linspace(0, size[0], size[0]), a_out) - a_graph.plot(np.linspace(0, size[0], size[0]), opt_a_out) - steer_graph = fig2.add_subplot(413) - steer_graph.title.set_text('steering') - steer_graph.plot(np.linspace(0, size[0], size[0]), steer_out) - steer_graph.plot(np.linspace(0, size[0], size[0]), opt_steer_out) - steer_graph = fig2.add_subplot(414) - steer_graph.title.set_text('t') - steer_graph.plot(np.linspace(0, size[0], size[0]), opt_time_out) - # dual variables - fig3 = plt.figure(3) - dual_l_graph = fig3.add_subplot(211) - dual_l_graph.title.set_text('dual_l') - dual_l_graph.plot(np.linspace(0, size[0] * 6, size[0] * 6), opt_dual_l_out) - dual_n_graph = fig3.add_subplot(212) - dual_n_graph.title.set_text('dual_n') - dual_n_graph.plot(np.linspace(0, size[0] * 16, size[0] * 16), opt_dual_n_out) - plt.show() - return True - - if not visualize_flag: - if success: - # load result - OpenSpacePlanner.DistanceGetResult(x, y, phi, v, a, steer, opt_x, - opt_y, opt_phi, opt_v, opt_a, opt_steer, opt_time, - opt_dual_l, opt_dual_n, size, - hybrid_time, dual_time, ipopt_time) - for i in range(0, size[0]): - x_out.append(float(x[i])) - y_out.append(float(y[i])) - phi_out.append(float(phi[i])) - v_out.append(float(v[i])) - a_out.append(float(a[i])) - steer_out.append(float(steer[i])) - opt_x_out.append(float(opt_x[i])) - opt_y_out.append(float(opt_y[i])) - opt_phi_out.append(float(opt_phi[i])) - opt_v_out.append(float(opt_v[i])) - opt_a_out.append(float(opt_a[i])) - opt_steer_out.append(float(opt_steer[i])) - opt_time_out.append(float(opt_time[i])) - # check end_pose distacne - end_pose_dist = math.sqrt((opt_x_out[-1] - ex)**2 + (opt_y_out[-1] - ey)**2) - end_pose_heading = abs(opt_phi_out[-1] - ephi) - reach_end_pose = (end_pose_dist <= 0.1 and end_pose_heading <= 0.17) - else: - end_pose_dist = 100.0 - end_pose_heading = 100.0 - reach_end_pose = 0 - return [success, end_pose_dist, end_pose_heading, reach_end_pose, opt_x_out, opt_y_out, opt_phi_out, opt_v_out, opt_a_out, opt_steer_out, opt_time_out, - hybrid_time, dual_time, ipopt_time, planning_time] - return False - - -if __name__ == '__main__': - # visualize_flag = True - # SmoothTrajectory(visualize_flag) - - visualize_flag = False - planning_time_stats = [] - hybrid_time_stats = [] - dual_time_stats = [] - ipopt_time_stats = [] - end_pose_dist_stats = [] - end_pose_heading_stats = [] - - test_count = 0 - success_count = 0 - for sx in np.arange(-10, 10, 1.0): - for sy in np.arange(2, 4, 0.5): - print("sx is " + str(sx) + " and sy is " + str(sy)) - test_count += 1 - result = SmoothTrajectory(visualize_flag, sx, sy) - # if result[0] and result[3]: # success cases only - if result[0]: - success_count += 1 - planning_time_stats.append(result[-1]) - ipopt_time_stats.append(result[-2][0]) - dual_time_stats.append(result[-3][0]) - hybrid_time_stats.append(result[-4][0]) - end_pose_dist_stats.append(result[1]) - end_pose_heading_stats.append(result[2]) - - print("success rate is " + str(float(success_count) / float(test_count))) - print("min is " + str(min(planning_time_stats))) - print("max is " + str(max(planning_time_stats))) - print("average is " + str(sum(planning_time_stats) / len(planning_time_stats))) - print("max end_pose_dist difference is: " + str(max(end_pose_dist_stats))) - print("min end_pose_dist difference is: " + str(min(end_pose_dist_stats))) - print("average end_pose_dist difference is: " + - str(sum(end_pose_dist_stats) / len(end_pose_dist_stats))) - print("max end_pose_heading difference is: " + str(max(end_pose_heading_stats))) - print("min end_pose_heading difference is: " + str(min(end_pose_heading_stats))) - print("average end_pose_heading difference is: " + - str(sum(end_pose_heading_stats) / len(end_pose_heading_stats))) - - module_timing = np.asarray([hybrid_time_stats, dual_time_stats, ipopt_time_stats]) - np.savetxt(result_file, module_timing, delimiter=",") - - print("average hybrid time(s): %4.4f, with max: %4.4f, min: %4.4f" % ( - sum(hybrid_time_stats) / len(hybrid_time_stats) / 1000.0, max(hybrid_time_stats) / 1000.0, - min(hybrid_time_stats) / 1000.0)) - print("average dual time(s): %4.4f, with max: %4.4f, min: %4.4f" % ( - sum(dual_time_stats) / len(dual_time_stats) / 1000.0, max(dual_time_stats) / 1000.0, - min(dual_time_stats) / 1000.0)) - print("average ipopt time(s): %4.4f, with max: %4.4f, min: %4.4f" % ( - sum(ipopt_time_stats) / len(ipopt_time_stats) / 1000.0, max(ipopt_time_stats) / 1000.0, - min(ipopt_time_stats) / 1000.0)) diff --git a/modules/tools/open_space_visualization/hybrid_a_star_python_interface.py b/modules/tools/open_space_visualization/hybrid_a_star_python_interface.py deleted file mode 100755 index 9f206644f5c..00000000000 --- a/modules/tools/open_space_visualization/hybrid_a_star_python_interface.py +++ /dev/null @@ -1,64 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math -import ctypes -from ctypes import POINTER -from ctypes import c_bool -from ctypes import c_double -from ctypes import c_int -from ctypes import c_ushort -from ctypes import c_void_p - - -lib = ctypes.cdll.LoadLibrary( - '/apollo/bazel-bin/modules/planning/open_space/tools/hybrid_a_star_wrapper_lib.so') - -lib.CreatePlannerPtr.argtypes = [] -lib.CreatePlannerPtr.restype = c_void_p -lib.CreateResultPtr.argtypes = [] -lib.CreateResultPtr.restype = c_void_p -lib.CreateObstaclesPtr.argtypes = [] -lib.CreateObstaclesPtr.restype = c_void_p -lib.AddVirtualObstacle.argtypes = [c_void_p, POINTER(c_double), POINTER(c_double), c_int] -lib.Plan.restype = c_bool -lib.Plan.argtypes = [c_void_p, c_void_p, c_void_p, c_double, c_double, c_double, c_double, - c_double, c_double, POINTER(c_double)] -lib.GetResult.argtypes = [c_void_p, POINTER(c_double), POINTER(c_double), POINTER(c_double), - POINTER(c_double), POINTER(c_double), POINTER(c_double), POINTER(c_ushort)] - - -class HybridAStarPlanner(object): - def __init__(self): - self.planner = lib.CreatePlannerPtr() - self.obstacles = lib.CreateObstaclesPtr() - self.result = lib.CreateResultPtr() - - def AddVirtualObstacle(self, obstacle_x, obstacle_y, vertice_num): - lib.AddVirtualObstacle(self.obstacles, POINTER(c_double)(obstacle_x), - POINTER(c_double)(obstacle_y), (c_int)(vertice_num)) - - def Plan(self, sx, sy, sphi, ex, ey, ephi, XYbounds): - return lib.Plan(self.planner, self.obstacles, self.result, c_double(sx), - c_double(sy), c_double(sphi), c_double(ex), c_double(ey), - c_double(ephi), POINTER(c_double)(XYbounds)) - - def GetResult(self, x, y, phi, v, a, steer, output_size): - lib.GetResult(self.result, POINTER(c_double)(x), POINTER(c_double)(y), - POINTER(c_double)(phi), POINTER(c_double)(v), POINTER(c_double)(a), - POINTER(c_double)(steer), POINTER(c_ushort)(output_size)) diff --git a/modules/tools/open_space_visualization/hybrid_a_star_visualizer.py b/modules/tools/open_space_visualization/hybrid_a_star_visualizer.py deleted file mode 100755 index 0adff5d2635..00000000000 --- a/modules/tools/open_space_visualization/hybrid_a_star_visualizer.py +++ /dev/null @@ -1,168 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math -import time - -from matplotlib import animation -import matplotlib.patches as patches -import matplotlib.pyplot as plt -import numpy as np - -from hybrid_a_star_python_interface import * - - -def HybridAStarPlan(visualize_flag): - # initialze object - HybridAStar = HybridAStarPlanner() - - # parameter(except max, min and car size is defined in proto) - num_output_buffer = 100000 - sx = -8 - sy = 4 - sphi = 0.0 - - scenario = "backward" - # scenario = "parallel" - - if scenario == "backward": - # for parking space 11543 in sunnyvale_with_two_offices - left_boundary_x = ( - c_double * 3)(*[-13.6407054776, 0.0, 0.0515703622475]) - left_boundary_y = ( - c_double * 3)(*[0.0140634663703, 0.0, -5.15258191624]) - down_boundary_x = (c_double * 2)(*[0.0515703622475, 2.8237895441]) - down_boundary_y = (c_double * 2)(*[-5.15258191624, -5.15306980547]) - right_boundary_x = ( - c_double * 3)(*[2.8237895441, 2.7184833539, 16.3592013995]) - right_boundary_y = ( - c_double * 3)(*[-5.15306980547, -0.0398078878812, -0.011889513383]) - up_boundary_x = (c_double * 2)(*[16.3591910364, -13.6406951857]) - up_boundary_y = (c_double * 2)(*[5.60414234644, 5.61797800844]) - # obstacles(x, y, size) - HybridAStar.AddVirtualObstacle(left_boundary_x, left_boundary_y, 3) - HybridAStar.AddVirtualObstacle( - down_boundary_x, down_boundary_y, 2) - HybridAStar.AddVirtualObstacle( - right_boundary_x, right_boundary_y, 3) - HybridAStar.AddVirtualObstacle( - up_boundary_x, up_boundary_y, 2) - ex = 1.359 - ey = -3.86443643718 - ephi = 1.581 - XYbounds = [-13.6406951857, 16.3591910364, - - 5.15258191624, 5.61797800844] - - x = (c_double * num_output_buffer)() - y = (c_double * num_output_buffer)() - phi = (c_double * num_output_buffer)() - v = (c_double * num_output_buffer)() - a = (c_double * num_output_buffer)() - steer = (c_double * num_output_buffer)() - size = (c_ushort * 1)() - XYbounds_ctype = (c_double * 4)(*XYbounds) - - start = time.time() - print("planning start") - success = True - if not HybridAStar.Plan(sx, sy, sphi, ex, ey, ephi, XYbounds_ctype): - print("planning fail") - success = False - end = time.time() - planning_time = end - start - print("planning time is " + str(planning_time)) - - # load result - x_out = [] - y_out = [] - phi_out = [] - v_out = [] - a_out = [] - steer_out = [] - - if visualize_flag and success: - HybridAStar.GetResult(x, y, phi, v, a, steer, size) - for i in range(0, size[0]): - x_out.append(float(x[i])) - y_out.append(float(y[i])) - phi_out.append(float(phi[i])) - v_out.append(float(v[i])) - a_out.append(float(a[i])) - steer_out.append(float(steer[i])) - - # plot - fig1 = plt.figure(1) - ax = fig1.add_subplot(111) - for i in range(0, size[0]): - downx = 1.055 * math.cos(phi_out[i] - math.pi / 2) - downy = 1.055 * math.sin(phi_out[i] - math.pi / 2) - leftx = 1.043 * math.cos(phi_out[i] - math.pi) - lefty = 1.043 * math.sin(phi_out[i] - math.pi) - x_shift_leftbottom = x_out[i] + downx + leftx - y_shift_leftbottom = y_out[i] + downy + lefty - car = patches.Rectangle((x_shift_leftbottom, y_shift_leftbottom), 3.89 + 1.043, 1.055*2, - angle=phi_out[i] * 180 / math.pi, linewidth=1, edgecolor='r', facecolor='none') - arrow = patches.Arrow( - x_out[i], y_out[i], 0.25*math.cos(phi_out[i]), 0.25*math.sin(phi_out[i]), 0.2) - ax.add_patch(car) - ax.add_patch(arrow) - ax.plot(sx, sy, "s") - ax.plot(ex, ey, "s") - if scenario == "backward": - left_boundary_x = [-13.6407054776, 0.0, 0.0515703622475] - left_boundary_y = [0.0140634663703, 0.0, -5.15258191624] - down_boundary_x = [0.0515703622475, 2.8237895441] - down_boundary_y = [-5.15258191624, -5.15306980547] - right_boundary_x = [2.8237895441, 2.7184833539, 16.3592013995] - right_boundary_y = [-5.15306980547, -0.0398078878812, -0.011889513383] - up_boundary_x = [16.3591910364, -13.6406951857] - up_boundary_y = [5.60414234644, 5.61797800844] - ax.plot(left_boundary_x, left_boundary_y, "k") - ax.plot(down_boundary_x, down_boundary_y, "k") - ax.plot(right_boundary_x, right_boundary_y, "k") - ax.plot(up_boundary_x, up_boundary_y, "k") - - plt.axis('equal') - - fig2 = plt.figure(2) - v_graph = fig2.add_subplot(311) - v_graph.title.set_text('v') - v_graph.plot(np.linspace(0, size[0], size[0]), v_out) - a_graph = fig2.add_subplot(312) - a_graph.title.set_text('a') - a_graph.plot(np.linspace(0, size[0], size[0]), a_out) - steer_graph = fig2.add_subplot(313) - steer_graph.title.set_text('steering') - steer_graph.plot(np.linspace(0, size[0], size[0]), steer_out) - plt.show() - if not visualize_flag: - if success: - HybridAStar.GetResult(x, y, phi, v, a, steer, size) - for i in range(0, size[0]): - x_out.append(float(x[i])) - y_out.append(float(y[i])) - phi_out.append(float(phi[i])) - v_out.append(float(v[i])) - a_out.append(float(a[i])) - steer_out.append(float(steer[i])) - return success, x_out, y_out, phi_out, v_out, a_out, steer_out, planning_time - - -if __name__ == '__main__': - visualize_flag = True - HybridAStarPlan(visualize_flag) diff --git a/modules/tools/open_space_visualization/open_space_roi_interface.py b/modules/tools/open_space_visualization/open_space_roi_interface.py deleted file mode 100755 index ad42970d4ea..00000000000 --- a/modules/tools/open_space_visualization/open_space_roi_interface.py +++ /dev/null @@ -1,42 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import ctypes -import math -from ctypes import cdll, c_ushort, c_int, c_char_p, c_double, POINTER - -lib = cdll.LoadLibrary( - '/apollo/bazel-bin/modules/planning/open_space/tools/open_space_roi_wrapper_lib.so') - - -class open_space_roi(object): - def __init__(self): - self.open_space_roi_test = lib.CreateROITestPtr() - - def ROITest(self, lane_id, parking_id, - unrotated_roi_boundary_x, unrotated_roi_boundary_y, roi_boundary_x, roi_boundary_y, - parking_spot_x, parking_spot_y, end_pose, - xy_boundary, origin_pose): - return lib.ROITest(self.open_space_roi_test, (c_char_p)(lane_id), (c_char_p)(parking_id), - POINTER(c_double)(unrotated_roi_boundary_x), POINTER( - c_double)(unrotated_roi_boundary_y), - POINTER(c_double)(roi_boundary_x), POINTER( - c_double)(roi_boundary_y), POINTER(c_double)( - parking_spot_x), POINTER(c_double)( - parking_spot_y), POINTER(c_double)(end_pose), - POINTER(c_double)(xy_boundary), POINTER(c_double)(origin_pose)) diff --git a/modules/tools/open_space_visualization/open_space_roi_visualizer.py b/modules/tools/open_space_visualization/open_space_roi_visualizer.py deleted file mode 100755 index 70e99c7d827..00000000000 --- a/modules/tools/open_space_visualization/open_space_roi_visualizer.py +++ /dev/null @@ -1,87 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - - -# @file to run it, change the modules/common/configs/config_gflags.cc to use sunnyvale_with_two_offices - - -from open_space_roi_interface import * -import matplotlib.pyplot as plt - -# initialize object -open_space_roi = open_space_roi() - - -lane_id = "11564dup1_1_-1" -parking_id = "11543" -num_output_buffer = 50 -unrotated_roi_boundary_x = (c_double * num_output_buffer)() -roi_boundary_x = (c_double * num_output_buffer)() -parking_spot_x = (c_double * num_output_buffer)() -unrotated_roi_boundary_y = (c_double * num_output_buffer)() -roi_boundary_y = (c_double * num_output_buffer)() -parking_spot_y = (c_double * num_output_buffer)() -end_pose = (c_double * num_output_buffer)() -xy_boundary = (c_double * num_output_buffer)() -origin_pose = (c_double * num_output_buffer)() - -if not open_space_roi.ROITest(lane_id, parking_id, - unrotated_roi_boundary_x, unrotated_roi_boundary_y, roi_boundary_x, roi_boundary_y, - parking_spot_x, parking_spot_y, end_pose, - xy_boundary, origin_pose): - print("open_space_roi fail") -result_unrotated_roi_boundary_x = [] -result_unrotated_roi_boundary_y = [] -result_roi_boundary_x = [] -result_roi_boundary_y = [] -result_parking_spot_x = [] -result_parking_spot_y = [] -result_end_pose = [] -result_xy_boundary = [] -result_origin_pose = [] - -print("vertices of obstacles") -for i in range(0, 10): - result_unrotated_roi_boundary_x.append(float(unrotated_roi_boundary_x[i])) - result_unrotated_roi_boundary_y.append(float(unrotated_roi_boundary_y[i])) - result_roi_boundary_x.append(float(roi_boundary_x[i])) - result_roi_boundary_y.append(float(roi_boundary_y[i])) - print(str(float(roi_boundary_x[i]))) - print(str(float(roi_boundary_y[i]))) -print("parking spot") -for i in range(0, 4): - result_parking_spot_x.append(float(parking_spot_x[i])) - result_parking_spot_y.append(float(parking_spot_y[i])) -print("end_pose in x,y,phi,v") -for i in range(0, 4): - print(str(float(end_pose[i]))) -print("xy_boundary in xmin xmax ymin ymax") -for i in range(0, 4): - print(str(float(xy_boundary[i]))) -print("origin_pose") -for i in range(0, 2): - print(str(float(origin_pose[i]))) - -fig = plt.figure() -ax1 = fig.add_subplot(211) -ax1.scatter(result_unrotated_roi_boundary_x, result_unrotated_roi_boundary_y) -ax1.scatter(result_parking_spot_x, result_parking_spot_y) -ax2 = fig.add_subplot(212) -ax2.scatter(result_roi_boundary_x, result_roi_boundary_y) -plt.gca().set_aspect('equal', adjustable='box') -plt.show() diff --git a/modules/tools/ota/config.ini b/modules/tools/ota/config.ini deleted file mode 100644 index b67effe019c..00000000000 --- a/modules/tools/ota/config.ini +++ /dev/null @@ -1,3 +0,0 @@ -[Host] -ip: 180.76.145.202 -port: 5000 diff --git a/modules/tools/ota/create_sec_package.py b/modules/tools/ota/create_sec_package.py deleted file mode 100755 index 975aee3b407..00000000000 --- a/modules/tools/ota/create_sec_package.py +++ /dev/null @@ -1,42 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import secure_upgrade_export as sec_api -import os -import sys -sys.path.append('/home/caros/secure_upgrade/python') - -root_config_path = "/home/caros/secure_upgrade/config/secure_config.json" -ret = sec_api.init_secure_upgrade(root_config_path) -if ret is True: - print('Security environment init successfully!') -else: - print('Security environment init failed!') - exit(1) - -homedir = os.environ['HOME'] -release_tgz = homedir + '/.cache/apollo_release.tar.gz' -sec_release_tgz = homedir + '/.cache/sec_apollo_release.tar.gz' -package_token = homedir + '/.cache/package_token' - -ret = sec_api.sec_upgrade_get_package( - release_tgz, sec_release_tgz, package_token) -if ret is True: - print('Security package generated successfully!') -else: - print('Security package generated failed!') diff --git a/modules/tools/ota/ota.cert b/modules/tools/ota/ota.cert deleted file mode 100644 index bf6a82f6581..00000000000 --- a/modules/tools/ota/ota.cert +++ /dev/null @@ -1,33 +0,0 @@ ------BEGIN CERTIFICATE----- -MIIFozCCA4ugAwIBAgIJAMvsOaOMZCjpMA0GCSqGSIb3DQEBCwUAMGgxCzAJBgNV -BAYTAkNOMRAwDgYDVQQIDAdCZWlqaW5nMRAwDgYDVQQHDAdCZWlqaW5nMQ4wDAYD -VQQKDAVCYWlkdTEMMAoGA1UECwwDSURHMRcwFQYDVQQDDA4xODAuNzYuMTQ1LjIw -MjAeFw0xNzEyMjYyMzU2NDBaFw0yNzEyMjQyMzU2NDBaMGgxCzAJBgNVBAYTAkNO -MRAwDgYDVQQIDAdCZWlqaW5nMRAwDgYDVQQHDAdCZWlqaW5nMQ4wDAYDVQQKDAVC -YWlkdTEMMAoGA1UECwwDSURHMRcwFQYDVQQDDA4xODAuNzYuMTQ1LjIwMjCCAiIw -DQYJKoZIhvcNAQEBBQADggIPADCCAgoCggIBALOEBanzSF/+Deg1DmjRLxnfsAKr -D/mR717RLCc92LsLujfKjHIhfy/NBOxGlrWhc7ScAp5mcSnFeByEXhyLUnd7pXuy -6DLvdrmDJExiciaRkz0zmoPO7H1LjzdPbcnkLz7zPrFG3zCBhLaZIHZukvS73vcK -OGxhX+9MXTlwl9nsC8lGx6ZNLSj5f8KVOpdy2P7Jeus5rdUBEthpjIpXMOgfDiaz -LcGrw5oBD38NwA6n5PGbgCOSkGM/GDmgBUeHxLirBsJncJPcgznLRgqrpiHizNsY -hijAH7qxn/JsF08w2YzVad5CSE8FLBElnGBrj6O0VmlWwoleKqhRCJXeqt+M+J2x -ccUyBA7dHmGhW3ELIwmIIA2fYrRm/s0SnZi9iDuwnHCHSe362kDXdl6l3WkjH34w -z1LsYlXV1rVyzu20sc98Irq+JvpP8rbY/PGg38UqyvcSJUdbrThEOcWbVuEqHbFO -iBdW8+WgBLDnp+4Q/uTFWSDl+vw3M0U3gTGhAPMYDDkjQyeGTAsXxQFplenpppAi -ycaap2+IAeJ0nQI94bhz8WBiEDfMqqUecWhnvwgDGjTRYdF+vNn7ZtsbkvdwckEe -ra8pDs/5uDMU8fCW48bkdo0QOYSTc3zufkN+mJiCQ+4kTuK+URGVCaZL9+GvTkhO -kQP8X8VtnqImEYWFAgMBAAGjUDBOMB0GA1UdDgQWBBSB4MbBrVai2n0XnQHLwIcg -xKKmbDAfBgNVHSMEGDAWgBSB4MbBrVai2n0XnQHLwIcgxKKmbDAMBgNVHRMEBTAD -AQH/MA0GCSqGSIb3DQEBCwUAA4ICAQAvZ/BU6ZdIDc12hFnOc4YXQld2uCApbznX -TuGqVedL/vcx5lwzGnbpJJQEg8BePLZSZznpP4h4UAhruTEzbYkaXibEgVD4k9wv -e/XEYaDQ07VKaRMEeuq8IKb5w9MXMENquN/YIvAmlRtVYgCuBUal9AZJulbXhD6E -HYuvPAMuuBUVINBcSPhby3UzY/yMP7VKDV3+QagRGZuelAjM9zzUY2BtHUPPkxgP -HAc+5clb2yi0wpHo1thHcm9DhN1cp9raYwHNiVIKKXV+RBlCKYX/huL3MyJPC5Pk -AdPrKe/yPMBPoISrEFeJta142/l2ywz1XVkUjeVBZzXDx01SJw5ta7iYKqcjfha2 -e2dGOJTg1U6cJftlkUB1bM4QnRf5QQIJ7Q06lOkcAGYuLBHlVJmkeSMEOOdXyaXY -ylV/wbQIzfL4t8DRkw+ZjUEvTcrJqXe6RgahpqD4SYTJoasYEVmmNfWVQVNTN9Wj -nbtyx3YFlecfYz+aJfAvNxpL0EZdGlUm0heIYn09dXknUQAfUQ/pkVLVkXWsy7WM -ddHiNjZjITt2N/3QQWaJJ16hPHcbFXqsSyfnLEjDTXp/Xy7DjWHJYlYEB1sScWlp -sB9arnO1iIRp5vLFjs3f6QDNPt6rygLses5/oZMzjUteFHoIKFoGBItjVdQkYGn6 -UyVKS7Me6A== ------END CERTIFICATE----- diff --git a/modules/tools/ota/query_client.py b/modules/tools/ota/query_client.py deleted file mode 100644 index 0977859a8c1..00000000000 --- a/modules/tools/ota/query_client.py +++ /dev/null @@ -1,109 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import os -import requests -import sys - -from configparser import ConfigParser -import secure_upgrade_export as sec_api -import urllib3 - -from modules.data.proto.static_info_pb2 import VehicleInfo -import modules.tools.common.proto_utils as proto_utils - - -sys.path.append('/home/caros/secure_upgrade/python') - -root_config_path = '/home/caros/secure_upgrade/config/secure_config.json' -ret = sec_api.init_secure_upgrade(root_config_path) -if ret is False: - print('Failed to initialize security environment!') - sys.exit(1) - - -def query(): - vehicle_info = VehicleInfo() - VEHICLE_INFO_FILE = os.path.join( - os.path.dirname(__file__), 'vehicle_info.pb.txt') - try: - proto_utils.get_pb_from_text_file(VEHICLE_INFO_FILE, vehicle_info) - except IOError: - print('vehicle_info.pb.txt cannot be open file.') - sys.exit(1) - - # Setup server url - config = ConfigParser() - CONFIG_FILE = os.path.join(os.path.dirname(__file__), 'config.ini') - config.read(CONFIG_FILE) - ip = config.get('Host', 'ip') - port = config.get('Host', 'port') - url = 'https://' + ip + ':' + port + '/query' - - # Generate device token - ret = sec_api.sec_upgrade_get_device_token() - if ret[0] is False: - print('Failed to get device token.') - sys.exit(1) - dev_token = ret[1] - - # setup car info - brand = VehicleInfo.Brand.Name(vehicle_info.brand) - model = VehicleInfo.Model.Name(vehicle_info.model) - vin = vehicle_info.vehicle_config.vehicle_id.vin - META_FILE = '/apollo/meta.ini' - config.read(META_FILE) - car_info = { - "car_type": brand + "." + model, - "tag": config.get('Release', 'tag'), - "vin": vin, - "token": dev_token - } - - urllib3.disable_warnings() - CERT_FILE = os.path.join(os.path.dirname(__file__), 'ota.cert') - r = requests.post(url, json=car_info, verify=CERT_FILE) - if r.status_code == 200: - auth_token = r.json().get("auth_token") - if auth_token == "": - print('Cannot get authorize token!') - sys.exit(1) - else: - token_file_name = os.environ['HOME'] + \ - '/.cache/apollo_update/auth_token' - apollo_update = os.path.dirname(token_file_name) - if not os.path.exists(apollo_update): - os.makedirs(apollo_update) - with open(token_file_name, 'w') as token_file: - token_file.write(auth_token) - tag = r.json().get("tag") - print(tag) - sys.exit(0) - elif r.status_code == 204: - print('Release is up to date.') - sys.exit(0) - elif r.status_code == 400: - print('Invalid car type.') - else: - print('Cannot connect to server.') - - sys.exit(1) - - -if __name__ == '__main__': - query() diff --git a/modules/tools/ota/update_client.py b/modules/tools/ota/update_client.py deleted file mode 100644 index 95b776807af..00000000000 --- a/modules/tools/ota/update_client.py +++ /dev/null @@ -1,70 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import requests -import os -import sys -import urllib3 -from configparser import ConfigParser -from modules.data.proto.static_info_pb2 import VehicleInfo -import modules.tools.common.proto_utils as proto_utils - - -def update(): - # setup server url - config = ConfigParser() - CONFIG_FILE = os.path.join(os.path.dirname(__file__), 'config.ini') - config.read(CONFIG_FILE) - ip = config.get('Host', 'ip') - port = config.get('Host', 'port') - url = 'https://' + ip + ':' + port + '/update' - - # setup car info - vehicle_info = VehicleInfo() - VEHICLE_INFO_FILE = os.path.join( - os.path.dirname(__file__), 'vehicle_info.pb.txt') - try: - proto_utils.get_pb_from_text_file(VEHICLE_INFO_FILE, vehicle_info) - except IOError: - print("vehicle_info.pb.txt cannot be open file.") - exit() - - brand = VehicleInfo.Brand.Name(vehicle_info.brand) - model = VehicleInfo.Model.Name(vehicle_info.model) - vin = vehicle_info.vehicle_config.vehicle_id.vin - car_info = { - "car_type": brand + "." + model, - "tag": sys.argv[1], - "vin": vin, - } - - urllib3.disable_warnings() - CERT_FILE = os.path.join(os.path.dirname(__file__), 'ota.cert') - r = requests.post(url, json=car_info, verify=CERT_FILE) - if r.status_code == 200: - print("Update successfully.") - sys.exit(0) - elif r.status_code == 400: - print("Invalid Request.") - else: - print("Cannot connect to server.") - sys.exit(1) - - -if __name__ == "__main__": - update() diff --git a/modules/tools/ota/verify_client.py b/modules/tools/ota/verify_client.py deleted file mode 100644 index fdb97cd55a2..00000000000 --- a/modules/tools/ota/verify_client.py +++ /dev/null @@ -1,61 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -"""OTA verify client""" - -import os -import requests -import sys - -from configparser import ConfigParser -import secure_upgrade_export as sec_api - -from modules.data.proto.static_info_pb2 import VehicleInfo -import modules.tools.common.proto_utils as proto_utils - - -sys.path.append('/home/caros/secure_upgrade/python') - -root_config_path = "/home/caros/secure_upgrade/config/secure_config.json" -ret = sec_api.init_secure_upgrade(root_config_path) -if ret is True: - print('Security environment init successfully!') -else: - print('Security environment init failed!') - sys.exit(1) - - -def verify(): - # Generate orig update package - token_file_name = os.environ['HOME'] + '/.cache/apollo_update/auth_token' - with open(token_file_name, 'r') as token_file: - auth_token = token_file.read() - sec_package = os.environ['HOME'] + '/.cache/sec_apollo_release.tar.gz' - orig_package = os.environ['HOME'] + '/.cache/apollo_release.tar.gz' - ret = sec_api.sec_upgrade_verify_package(auth_token, sec_package, - orig_package) - if ret is True: - print('Verify package successfully!') - sys.exit(0) - else: - print('Verify package failed!!!') - sys.exit(1) - - -if __name__ == "__main__": - verify() diff --git a/modules/tools/perception/BUILD b/modules/tools/perception/BUILD deleted file mode 100644 index 5c806df6de3..00000000000 --- a/modules/tools/perception/BUILD +++ /dev/null @@ -1,61 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -filegroup( - name = "garage_config", - srcs = glob(["*.json"]) + ["garage_perception.bash"], -) - -py_binary( - name = "empty_prediction", - srcs = ["empty_prediction.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:cyber_time", - "//modules/common_msgs/prediction_msgs:prediction_obstacle_py_pb2", - ], -) - -py_binary( - name = "extend_prediction", - srcs = ["extend_prediction.py"], - deps = [ - "//modules/common_msgs/prediction_msgs:prediction_obstacle_py_pb2", - "//modules/tools/common:proto_utils", - ], -) - -py_binary( - name = "print_perception", - srcs = ["print_perception.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//modules/common_msgs/perception_msgs:perception_obstacle_py_pb2", - ], -) - -py_binary( - name = "replay_perception", - srcs = ["replay_perception.py"], - data = [":garage_config"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:cyber_time", - "//modules/common_msgs/basic_msgs:geometry_py_pb2", - "//modules/common_msgs/perception_msgs:perception_obstacle_py_pb2", - ], -) - -install( - name = "install", - data_dest = "tools/perception", - py_dest = "tools/perception", - targets = [ - ":empty_prediction", - ":extend_prediction", - ":print_perception", - ":replay_perception" - ] -) \ No newline at end of file diff --git a/modules/tools/perception/empty_prediction.py b/modules/tools/perception/empty_prediction.py deleted file mode 100644 index 1c20936b656..00000000000 --- a/modules/tools/perception/empty_prediction.py +++ /dev/null @@ -1,61 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -""" -this module creates a node and fake prediction data based -on json configurations -""" -import argparse -import math -import time - -import numpy -import simplejson -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import cyber_time - -from modules.common_msgs.prediction_msgs.prediction_obstacle_pb2 import PredictionObstacles - - -def prediction_publisher(prediction_channel, rate): - """publisher""" - cyber.init() - node = cyber.Node("prediction") - writer = node.create_writer(prediction_channel, PredictionObstacles) - sleep_time = 1.0 / rate - seq_num = 1 - while not cyber.is_shutdown(): - prediction = PredictionObstacles() - prediction.header.sequence_num = seq_num - prediction.header.timestamp_sec = cyber_time.Time.now().to_sec() - prediction.header.module_name = "prediction" - print(str(prediction)) - writer.write(prediction) - seq_num += 1 - time.sleep(sleep_time) - - -if __name__ == '__main__': - parser = argparse.ArgumentParser(description="create empty prediction message", - prog="replay_prediction.py") - parser.add_argument("-c", "--channel", action="store", type=str, default="/apollo/prediction", - help="set the prediction channel") - parser.add_argument("-r", "--rate", action="store", type=int, default=10, - help="set the prediction channel publish time duration") - args = parser.parse_args() - prediction_publisher(args.channel, args.rate) diff --git a/modules/tools/perception/extend_prediction.py b/modules/tools/perception/extend_prediction.py deleted file mode 100644 index f879c8d66e8..00000000000 --- a/modules/tools/perception/extend_prediction.py +++ /dev/null @@ -1,90 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -""" -print received prediction message -""" -import argparse -import math -import sys - -import numpy - -import modules.tools.common.proto_utils as proto_utils -from modules.common_msgs.prediction_msgs.prediction_obstacle_pb2 import PredictionObstacles - - -def distance(p1, p2): - """distance between two trajectory points""" - return math.sqrt((p1.y - p2.y)**2 + (p1.x - p2.x)**2) - - -def get_trajectory_length(trajectory): - """get_trajectory_length""" - total = 0.0 - for i in range(1, len(trajectory.trajectory_point)): - total += distance(trajectory.trajectory_point[i - 1].path_point, - trajectory.trajectory_point[i].path_point) - return total - - -def extend_prediction(prediction, min_length, min_time): - """extend prediction""" - for obstacle in prediction.prediction_obstacle: - i = 0 - for trajectory in obstacle.trajectory: - points = trajectory.trajectory_point - point_num = len(points) - trajectory_length = get_trajectory_length(trajectory) - sys.stderr.write("obstacle_id :%s trajectory_id: %s length: %s\n" % ( - obstacle.perception_obstacle.id, i, trajectory_length)) - i += 1 - if trajectory_length < min_length: - second_last = points[point_num - 2] - last_point = points[point_num - 1] - x_diff = last_point.path_point.x - second_last.path_point.x - y_diff = last_point.path_point.y - second_last.path_point.y - t_diff = last_point.path_point.theta - second_last.path_point.theta - delta_diff = math.sqrt(x_diff ** 2 + y_diff ** 2) - cur_len = trajectory_length - while cur_len < min_length and abs(cur_len) > 0.000001: - last_point.path_point.x += x_diff - last_point.path_point.y += y_diff - last_point.path_point.theta += t_diff - p = points.add() - p.CopyFrom(last_point) - last_point = p - cur_len += delta_diff - return prediction - - -if __name__ == '__main__': - parser = argparse.ArgumentParser( - description="extend prediction trajectory") - parser.add_argument("prediction", action="store", - type=str, help="set the prediction file") - parser.add_argument("-p", "--period", action="store", type=float, default=10.0, - help="set the prediction period") - parser.add_argument("-d", "--distance", action="store", type=float, default=70.0, - help="set the prediction distance") - args = parser.parse_args() - prediction_data = proto_utils.get_pb_from_file( - args.prediction, PredictionObstacles()) - extended_prediction = extend_prediction( - prediction_data, args.distance, args.period) - print(extended_prediction) diff --git a/modules/tools/perception/garage_cross_vehicle_2.json b/modules/tools/perception/garage_cross_vehicle_2.json deleted file mode 100644 index 17beee750d8..00000000000 --- a/modules/tools/perception/garage_cross_vehicle_2.json +++ /dev/null @@ -1,14 +0,0 @@ -{ - "id": 2, - "position": [-1868.59, -2990.91, 0.0], - "theta": 1.1659045405098132, - "length": 4, - "width": 2, - "height": 1, - "speed": 8.0, - "tracking_time": 1.0, - "type": "VEHICLE", - "trace": [[-1868.59, -2990.91, 0.0], - [-1845.16, -2994.59, 0.0], - [-1850.16, -3000.0, 0.0]] -} diff --git a/modules/tools/perception/garage_offroad_static_1.json b/modules/tools/perception/garage_offroad_static_1.json deleted file mode 100644 index 4b6cb0deedd..00000000000 --- a/modules/tools/perception/garage_offroad_static_1.json +++ /dev/null @@ -1,11 +0,0 @@ -{ - "id": 1, - "position": [-1855.5, -2961.51, 0], - "theta": 1.1659045405098132, - "length": 4, - "width": 2, - "height": 1, - "speed": 0.0, - "tracking_time": 1.0, - "type": "UNKNOWN_UNMOVABLE" -} diff --git a/modules/tools/perception/garage_onroad_static_4.json b/modules/tools/perception/garage_onroad_static_4.json deleted file mode 100644 index aa3d68ed37b..00000000000 --- a/modules/tools/perception/garage_onroad_static_4.json +++ /dev/null @@ -1,11 +0,0 @@ -{ - "id": 1, - "position": [586347.42124613957, 4140710.9270518012, 0.0], - "theta": 1.1659045405098132, - "length": 4, - "width": 2, - "height": 1, - "speed": 0.0, - "tracking_time": 1.0, - "type": "UNKNOWN_UNMOVABLE" -} diff --git a/modules/tools/perception/garage_onroad_vehicle_3.json b/modules/tools/perception/garage_onroad_vehicle_3.json deleted file mode 100644 index 7a648151e99..00000000000 --- a/modules/tools/perception/garage_onroad_vehicle_3.json +++ /dev/null @@ -1,113 +0,0 @@ -{ - "id": 3, - "position": [586376.36731545243, 4140677.2173802247, 0.0], - "theta": 1.1659045405098132, - "length": 4, - "width": 2, - "height": 1, - "speed": 8.0, - "tracking_time": 1.0, - "type": "VEHICLE", - "trace": [ - [586392.84003, 4140673.01232, 0.0], - [586391.48345350777, 4140673.3586190776, 0.0], - [586389.93308037391, 4140673.7543894518, 0.0], - [586388.38270724006, 4140674.1501598256, 0.0], - [586386.83233410609, 4140674.5459302, 0.0], - [586385.28196097224, 4140674.941700574, 0.0], - [586383.92538448, 4140675.2879996509, 0.0], - [586382.37501134619, 4140675.6837700251, 0.0], - [586380.82463821233, 4140676.0795403994, 0.0], - [586379.27426507848, 4140676.4753107731, 0.0], - [586377.72389194451, 4140676.8710811473, 0.0], - [586376.36731545243, 4140677.2173802247, 0.0], - [586374.81694231846, 4140677.6131505985, 0.0], - [586373.26656918461, 4140678.0089209727, 0.0], - [586371.71619605075, 4140678.4046913465, 0.0], - [586370.1658229169, 4140678.8004617207, 0.0], - [586368.8092464247, 4140679.1467607981, 0.0], - [586367.25887329085, 4140679.5425311718, 0.0], - [586365.708500157, 4140679.938301546, 0.0], - [586364.158127023, 4140680.3340719203, 0.0], - [586362.60775388917, 4140680.729842294, 0.0], - [586361.05738075532, 4140681.1256126682, 0.0], - [586359.70080426312, 4140681.4719117456, 0.0], - [586358.15043112927, 4140681.8676821194, 0.0], - [586356.60005799541, 4140682.2634524936, 0.0], - [586355.04968486144, 4140682.6592228673, 0.0], - [586353.49931172759, 4140683.0549932416, 0.0], - [586352.14273523539, 4140683.4012923189, 0.0], - [586350.59236210154, 4140683.7970626927, 0.0], - [586349.04198896769, 4140684.1928330669, 0.0], - [586347.569402928, 4140684.6569425897, 0.0], - [586346.34040037962, 4140685.3234600914, 0.0], - [586345.30744645279, 4140686.0166505864, 0.0], - [586344.29222947382, 4140686.9242762327, 0.0], - [586343.56665382232, 4140688.0126865744, 0.0], - [586342.949612425, 4140689.1510837893, 0.0], - [586342.55869757663, 4140690.3676857753, 0.0], - [586342.55462259543, 4140691.4767941991, 0.0], - [586342.6637494904, 4140692.8428249569, 0.0], - [586342.99203702353, 4140694.4008130711, 0.0], - [586343.35804034967, 4140695.9494921896, 0.0], - [586343.75255533273, 4140697.4911341346, 0.0], - [586344.16637783637, 4140699.0280107288, 0.0], - [586344.537075054, 4140700.3706546258, 0.0], - [586344.962295973, 4140701.904718264, 0.0], - [586345.38318794768, 4140703.4398507774, 0.0], - [586345.80090989673, 4140704.9757669368, 0.0], - [586346.21787014115, 4140706.5118733062, 0.0], - [586346.58354364219, 4140707.8557630088, 0.0], - [586347.00225746073, 4140709.3914409908, 0.0], - [586347.42124613957, 4140710.9270518012, 0.0], - [586347.83999702206, 4140712.4627208482, 0.0], - [586348.25850161957, 4140713.9984501684, 0.0], - [586348.62461901968, 4140715.3422314571, 0.0], - [586349.04308792681, 4140716.8779694913, 0.0], - [586349.4616301487, 4140718.4136895789, 0.0], - [586349.88020279026, 4140719.9494022224, 0.0], - [586350.2987647875, 4140721.4851174741, 0.0], - [586350.66498962464, 4140722.8288724585, 0.0], - [586351.08352311642, 4140724.3645946868, 0.0], - [586351.502057768, 4140725.9003166305, 0.0], - [586351.92059813277, 4140727.4360371758, 0.0], - [586352.33914143045, 4140728.9717570036, 0.0], - [586352.75768457341, 4140730.507476869, 0.0], - [586353.12390853534, 4140731.8512320668, 0.0], - [586353.54244935873, 4140733.3869525003, 0.0], - [586353.96099008131, 4140734.9226729581, 0.0], - [586354.37953121448, 4140736.4583933158, 0.0], - [586354.798072612, 4140737.9941136083, 0.0], - [586355.16429637477, 4140739.3378688549, 0.0], - [586355.582837717, 4140740.8735891613, 0.0], - [586356.00137897744, 4140742.4093094873, 0.0], - [586356.41992021643, 4140743.9450298189, 0.0], - [586356.8384614815, 4140745.4807501445, 0.0], - [586357.20468510769, 4140746.8245054241, 0.0], - [586357.62322640244, 4140748.3602257422, 0.0], - [586358.04176769149, 4140749.8959460612, 0.0], - [586358.46030897368, 4140751.4316663826, 0.0], - [586358.8788502533, 4140752.9673867039, 0.0], - [586359.245073874, 4140754.3111419855, 0.0], - [586359.66361515666, 4140755.8468623064, 0.0], - [586360.08215644024, 4140757.3825826268, 0.0], - [586360.50069772359, 4140758.9183029477, 0.0], - [586360.91923900647, 4140760.4540232685, 0.0], - [586361.337780289, 4140761.9897435894, 0.0], - [586361.70400391135, 4140763.33349887, 0.0], - [586362.122545194, 4140764.8692191909, 0.0], - [586362.54108647688, 4140766.4049395118, 0.0], - [586362.95962775976, 4140767.9406598327, 0.0], - [586363.37816904252, 4140769.4763801536, 0.0], - [586363.74439266487, 4140770.8201354346, 0.0], - [586364.16293394763, 4140772.3558557555, 0.0], - [586364.5814752304, 4140773.8915760764, 0.0], - [586365.00001651316, 4140775.4272963973, 0.0], - [586365.418557796, 4140776.9630167182, 0.0], - [586365.78478141839, 4140778.3067719988, 0.0], - [586366.20332270127, 4140779.8424923196, 0.0], - [586366.621863984, 4140781.3782126405, 0.0], - [586367.0404052668, 4140782.9139329614, 0.0], - [586367.45894654957, 4140784.4496532823, 0.0] - ] -} diff --git a/modules/tools/perception/garage_perception.bash b/modules/tools/perception/garage_perception.bash deleted file mode 100755 index a2bca096e32..00000000000 --- a/modules/tools/perception/garage_perception.bash +++ /dev/null @@ -1,23 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# 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. -############################################################################### - -cd "$(dirname "${BASH_SOURCE[0]}")" - -source "/apollo/scripts/apollo_base.sh" - -/apollo/bazel-bin/modules/tools/perception/replay_perception garage_*.json diff --git a/modules/tools/perception/print_perception.py b/modules/tools/perception/print_perception.py deleted file mode 100644 index a863398b4f9..00000000000 --- a/modules/tools/perception/print_perception.py +++ /dev/null @@ -1,49 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -""" -print received perception message -""" -import argparse -from cyber.python.cyber_py3 import cyber - -from modules.common_msgs.perception_msgs.perception_obstacle_pb2 import PerceptionObstacles - - -def receiver(data): - """receiver""" - print(data) - - -def perception_receiver(perception_channel): - """publisher""" - cyber.init() - node = cyber.Node("perception") - node.create_reader(perception_channel, PerceptionObstacles, receiver) - node.spin() - - -if __name__ == '__main__': - parser = argparse.ArgumentParser(description="create fake perception obstacles", - prog="print_perception.py") - parser.add_argument("-c", "--channel", action="store", type=str, - default="/apollo/perception/obstacles", - help="set the perception channel") - - args = parser.parse_args() - perception_receiver(args.channel) diff --git a/modules/tools/perception/replay_perception.py b/modules/tools/perception/replay_perception.py deleted file mode 100644 index 61070ed5932..00000000000 --- a/modules/tools/perception/replay_perception.py +++ /dev/null @@ -1,298 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -""" -This module creates a node and fake perception data based -on json configurations -""" - -import argparse -import math -import time - -import simplejson - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import cyber_time -from modules.common_msgs.basic_msgs.geometry_pb2 import Point3D -from modules.common_msgs.perception_msgs.perception_obstacle_pb2 import PerceptionObstacle -from modules.common_msgs.perception_msgs.perception_obstacle_pb2 import PerceptionObstacles - - -_s_seq_num = 0 -_s_delta_t = 0.1 -_s_epsilon = 1e-8 - - -def get_seq_num(): - """ - Return the sequence number - """ - global _s_seq_num - _s_seq_num += 1 - return _s_seq_num - - -def get_velocity(theta, speed): - """ - Get velocity from theta and speed - """ - point = Point3D() - point.x = math.cos(theta) * speed - point.y = math.sin(theta) * speed - point.z = 0.0 - return point - - -def generate_polygon(point, heading, length, width): - """ - Generate polygon - """ - points = [] - half_l = length / 2.0 - half_w = width / 2.0 - sin_h = math.sin(heading) - cos_h = math.cos(heading) - vectors = [(half_l * cos_h - half_w * sin_h, - half_l * sin_h + half_w * cos_h), - (-half_l * cos_h - half_w * sin_h, - - half_l * sin_h + half_w * cos_h), - (-half_l * cos_h + half_w * sin_h, - - half_l * sin_h - half_w * cos_h), - (half_l * cos_h + half_w * sin_h, - half_l * sin_h - half_w * cos_h)] - for x, y in vectors: - p = Point3D() - p.x = point.x + x - p.y = point.y + y - p.z = point.z - points.append(p) - - return points - - -def load_descrptions(files): - """ - Load description files - """ - objects = [] - for file in files: - with open(file, 'r') as fp: - obstacles = simplejson.loads(fp.read()) - # Multiple obstacle in one file saves as a list[obstacles] - if isinstance(obstacles, list): - for obstacle in obstacles: - trace = obstacle.get('trace', []) - for i in range(1, len(trace)): - if same_point(trace[i], trace[i - 1]): - print('same trace point found in obstacle: %s' % obstacle["id"]) - return None - objects.append(obstacle) - else: # Default case. handles only one obstacle - obstacle = obstacles - trace = obstacle.get('trace', []) - for i in range(1, len(trace)): - if same_point(trace[i], trace[i - 1]): - print('same trace point found in obstacle: %s' % obstacle["id"]) - return None - objects.append(obstacle) - - return objects - - -def get_point(a, b, ratio): - """ - Get point from a to b with ratio - """ - p = Point3D() - p.x = a[0] + ratio * (b[0] - a[0]) - p.y = a[1] + ratio * (b[1] - a[1]) - p.z = a[2] + ratio * (b[2] - a[2]) - return p - - -def init_perception(description): - """ - Create perception from description - """ - perception = PerceptionObstacle() - perception.id = description["id"] - perception.position.x = description["position"][0] - perception.position.y = description["position"][1] - perception.position.z = description["position"][2] - perception.theta = description["theta"] - perception.velocity.CopyFrom(get_velocity( - description["theta"], description["speed"])) - perception.length = description["length"] - perception.width = description["width"] - perception.height = description["height"] - perception.polygon_point.extend(generate_polygon(perception.position, - perception.theta, - perception.length, - perception.width)) - perception.tracking_time = description["tracking_time"] - perception.type = PerceptionObstacle.Type.Value(description["type"]) - perception.timestamp = cyber_time.Time.now().to_sec() - - return perception - - -def same_point(a, b): - """ - Test if a and b are the same point - """ - return math.fabs(b[0] - a[0]) < _s_epsilon and \ - math.fabs(b[1] - a[1]) < _s_epsilon - - -def inner_product(a, b): - """ - Get the a, b inner product - """ - return a[0] * b[0] + a[1] * b[1] + a[2] * b[2] - - -def cross_product(a, b): - """ - Cross product - """ - return a[0] * b[1] - a[1] * b[0] - - -def distance(a, b): - """ - Return distance between a and b - """ - return math.sqrt((b[0] - a[0])**2 + (b[1] - a[1])**2 + (b[2] - a[2])**2) - - -def is_within(a, b, c): - """ - Check if c is in [a, b] - """ - if b < a: - b, a = a, b - return a - _s_epsilon < c < b + _s_epsilon - - -def on_segment(a, b, c): - """ - Test if c is in line segment a-b - """ - ab = (b[0] - a[0], b[1] - a[1], b[2] - a[2]) - ac = (c[0] - a[0], c[1] - a[1], c[2] - a[2]) - if math.fabs(cross_product(ac, ab)) > _s_epsilon: - return False - return is_within(a[0], b[0], c[0]) and is_within(a[1], b[1], c[1]) \ - and is_within(a[2], b[2], c[2]) - - -def linear_project_perception(description, prev_perception): - """ - Get perception from linear projection of description - """ - perception = PerceptionObstacle() - perception = prev_perception - perception.timestamp = cyber_time.Time.now().to_sec() - if "trace" not in description: - return perception - trace = description["trace"] - prev_point = (prev_perception.position.x, prev_perception.position.y, - prev_perception.position.z) - delta_s = description["speed"] * _s_delta_t - for i in range(1, len(trace)): - if on_segment(trace[i - 1], trace[i], prev_point): - dist = distance(trace[i - 1], trace[i]) - delta_s += distance(trace[i - 1], prev_point) - while dist < delta_s: - delta_s -= dist - i += 1 - if i < len(trace): - dist = distance(trace[i - 1], trace[i]) - else: - return init_perception(description) - ratio = delta_s / dist - perception.position.CopyFrom( - get_point(trace[i - 1], trace[i], ratio)) - perception.theta = math.atan2(trace[i][1] - trace[i - 1][1], - trace[i][0] - trace[i - 1][0]) - - perception.ClearField("polygon_point") - perception.polygon_point.extend(generate_polygon(perception.position, perception.theta, - perception.length, perception.width)) - return perception - - return perception - - -def generate_perception(perception_description, prev_perception): - """ - Generate perception data - """ - perceptions = PerceptionObstacles() - perceptions.header.sequence_num = get_seq_num() - perceptions.header.module_name = "perception" - perceptions.header.timestamp_sec = cyber_time.Time.now().to_sec() - if not perception_description: - return perceptions - if prev_perception is None: - for description in perception_description: - p = perceptions.perception_obstacle.add() - p.CopyFrom(init_perception(description)) - return perceptions - # Linear projection - description_dict = {desc["id"]: desc for desc in perception_description} - for obstacle in prev_perception.perception_obstacle: - description = description_dict[obstacle.id] - next_obstacle = linear_project_perception(description, obstacle) - perceptions.perception_obstacle.add().CopyFrom(next_obstacle) - return perceptions - - -def perception_publisher(perception_channel, files, period): - """ - Publisher - """ - cyber.init() - node = cyber.Node("perception") - writer = node.create_writer(perception_channel, PerceptionObstacles) - perception_description = load_descrptions(files) - sleep_time = int(1.0 / period) # 10Hz - global _s_delta_t - _s_delta_t = period - perception = None - while not cyber.is_shutdown(): - perception = generate_perception(perception_description, perception) - print(str(perception)) - writer.write(perception) - time.sleep(sleep_time) - - -if __name__ == '__main__': - parser = argparse.ArgumentParser(description="create fake perception obstacles", - prog="replay_perception.py") - parser.add_argument("files", action="store", type=str, nargs="*", - help="obstacle description files") - parser.add_argument("-c", "--channel", action="store", type=str, - default="/apollo/perception/obstacles", - help="set the perception channel") - parser.add_argument("-p", "--period", action="store", type=float, default=0.1, - help="set the perception channel publish time duration") - args = parser.parse_args() - - perception_publisher(args.channel, args.files, args.period) diff --git a/modules/tools/planning/data_pipelines/scripts/evaluate_trajectory.sh b/modules/tools/planning/data_pipelines/scripts/evaluate_trajectory.sh deleted file mode 100644 index 0e3b804e266..00000000000 --- a/modules/tools/planning/data_pipelines/scripts/evaluate_trajectory.sh +++ /dev/null @@ -1,33 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# 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. -############################################################################### - -SRC_DIR=$1 -TARGET_DIR=$2 - -set -e - -source /apollo/scripts/apollo_base.sh -source /apollo/cyber/setup.bash - -sudo mkdir -p ${TARGET_DIR} - -/apollo/bazel-bin/modules/planning/pipeline/evaluate_trajectory \ - --flagfile=/apollo/modules/planning/conf/planning.conf \ - --planning_offline_learning=true \ - --planning_source_dirs=${SRC_DIR} \ - --planning_data_dir=${TARGET_DIR} \ diff --git a/modules/tools/planning/data_pipelines/scripts/record_to_learning_data.sh b/modules/tools/planning/data_pipelines/scripts/record_to_learning_data.sh deleted file mode 100644 index 7a0fc3d8eca..00000000000 --- a/modules/tools/planning/data_pipelines/scripts/record_to_learning_data.sh +++ /dev/null @@ -1,40 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# 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. -############################################################################### - -SRC_DIR=$1 -TARGET_DIR=$2 - -set -e - -source /apollo/scripts/apollo_base.sh -source /apollo/cyber/setup.bash - -sudo mkdir -p ${TARGET_DIR} - -if [ -z "$3" ]; then - MAP_DIR="sunnyvale_with_two_offices" -else - MAP_DIR=$3 -fi - -/apollo/bazel-bin/modules/planning/pipeline/record_to_learning_data \ - --flagfile=/apollo/modules/planning/conf/planning.conf \ - --map_dir=/apollo/modules/map/data/${MAP_DIR} \ - --planning_offline_learning=true \ - --planning_offline_bags=${SRC_DIR} \ - --planning_data_dir=${TARGET_DIR} diff --git a/modules/tools/planning/plot_trajectory/BUILD b/modules/tools/planning/plot_trajectory/BUILD deleted file mode 100644 index ce39f4ec3e3..00000000000 --- a/modules/tools/planning/plot_trajectory/BUILD +++ /dev/null @@ -1,37 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -filegroup( - name = "runtime_files", - srcs = glob(["example_data/*"]) + ["run.sh"], -) - -py_binary( - name = "main", - srcs = ["main.py"], - data = [ - "//modules/tools/planning/plot_trajectory/example_data", - ], - deps = [ - ":mkz_polygon", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - "//modules/common_msgs/planning_msgs:planning_py_pb2", - "//modules/tools/common:proto_utils", - ], -) - -py_library( - name = "mkz_polygon", - srcs = ["mkz_polygon.py"], -) - -install( - name = "install", - data_dest = "tools/planning/plot_trajectory", - py_dest = "tools/planning/plot_trajectory", - targets = [ - ":main", - ] -) \ No newline at end of file diff --git a/modules/tools/planning/plot_trajectory/example_data/1_localization.pb.txt b/modules/tools/planning/plot_trajectory/example_data/1_localization.pb.txt deleted file mode 100644 index 12d69ff493c..00000000000 --- a/modules/tools/planning/plot_trajectory/example_data/1_localization.pb.txt +++ /dev/null @@ -1,34 +0,0 @@ -header { - timestamp_sec: 1178408221.7 - module_name: "localization" - sequence_num: 717699 -} -pose { - position { - x: -123.13666043742973 - y: 364.35546687249285 - z: -31.420322706922889 - } - orientation { - qx: 0.0055477773475503213 - qy: -0.0038590037118573272 - qz: -0.990379842317655 - qw: -0.13821034037911459 - } - heading: -1.732 - linear_velocity { - x: 0.00087471447426956314 - y: -0.0012088329450176513 - z: -0.0012369063243036489 - } - linear_acceleration { - x: -0.016531577551598127 - y: -0.018844718168206657 - z: -0.046939246111843365 - } - angular_velocity { - x: 0.001327747667490114 - y: -1.6716219241558373e-05 - z: 0.0004012993134012201 - } -} diff --git a/modules/tools/planning/plot_trajectory/example_data/1_planning.pb.txt b/modules/tools/planning/plot_trajectory/example_data/1_planning.pb.txt deleted file mode 100644 index e55d6a17c63..00000000000 --- a/modules/tools/planning/plot_trajectory/example_data/1_planning.pb.txt +++ /dev/null @@ -1,13011 +0,0 @@ -header { - timestamp_sec: 1494373003.683531 - module_name: "planning" - sequence_num: 1 -} -total_path_length: 32.38002780204 -total_path_time: 9.9800000190734863 -adc_trajectory_point { - x: -124.367072419 - y: 364.831849142 - z: -31.332377322 - - speed: 1.62222218513 - acceleration_s: 0.786162598236 - curvature: -0.00252617800322 - curvature_change_rate: 0 - relative_time: -0.089999914169311523 - theta: -1.81237826921 - accumulated_s: 0 -} -adc_trajectory_point { - x: -124.371192947 - y: 364.815408289 - z: -31.3321617292 - - speed: 1.63055551052 - acceleration_s: 0.823007905434 - curvature: -0.00248790128945 - curvature_change_rate: 0.00234746462335 - relative_time: -0.079999923706054688 - theta: -1.81246574077 - accumulated_s: 0.016305555109999981 -} -adc_trajectory_point { - x: -124.375298464 - y: 364.798862219 - z: -31.3319112528 - - speed: 1.63055551052 - acceleration_s: 0.939039433387 - curvature: -0.00248790128945 - curvature_change_rate: 0 - relative_time: -0.069999933242797852 - theta: -1.81246756399 - accumulated_s: 0.032611110209999961 -} -adc_trajectory_point { - x: -124.379445239 - y: 364.782260752 - z: -31.331748303 - - speed: 1.65555560589 - acceleration_s: 0.799533704679 - curvature: -0.00244962463489 - curvature_change_rate: 0.00231201262143 - relative_time: -0.059999942779541016 - theta: -1.81249667017 - accumulated_s: 0.0491666662700001 -} -adc_trajectory_point { - x: -124.379445239 - y: 364.782260752 - z: -31.331748303 - - speed: 1.65555560589 - acceleration_s: 0.799533704679 - curvature: -0.00244962463489 - curvature_change_rate: 0 - relative_time: -0.059999942779541016 - theta: -1.81249667017 - accumulated_s: 0.065722222330000024 -} -adc_trajectory_point { - x: -124.387812319 - y: 364.748792952 - z: -31.3314336967 - - speed: 1.67222225666 - acceleration_s: 0.709512194401 - curvature: -0.00241134803862 - curvature_change_rate: 0.00228896584236 - relative_time: -0.039999961853027344 - theta: -1.81252111016 - accumulated_s: 0.082444444899999914 -} -adc_trajectory_point { - x: -124.39208822 - y: 364.73193295 - z: -31.3311777441 - - speed: 1.67222225666 - acceleration_s: 0.885164961093 - curvature: -0.00241134803862 - curvature_change_rate: 0 - relative_time: -0.029999971389770508 - theta: -1.81259538169 - accumulated_s: 0.099166667460000024 -} -adc_trajectory_point { - x: -124.396360761 - y: 364.715008909 - z: -31.3310258063 - - speed: 1.6916667223 - acceleration_s: 0.840964839003 - curvature: -0.00241134803862 - curvature_change_rate: 0 - relative_time: -0.019999980926513672 - theta: -1.81260595807 - accumulated_s: 0.1160833346900001 -} -adc_trajectory_point { - x: -124.400686806 - y: 364.698015497 - z: -31.3307877881 - - speed: 1.6916667223 - acceleration_s: 0.79314550852 - curvature: -0.00241134803862 - curvature_change_rate: 0 - relative_time: -0.0099999904632568359 - theta: -1.81264478745 - accumulated_s: 0.13300000190999994 -} -adc_trajectory_point { - x: -124.404998184 - y: 364.68093016 - z: -31.330677554 - - speed: 1.70833337307 - acceleration_s: 0.79314550852 - curvature: -0.00237307149975 - curvature_change_rate: 0.00224057783324 - relative_time: 0 - theta: -1.81266143871 - accumulated_s: 0.15008333563999998 -} -adc_trajectory_point { - x: -124.404998184 - y: 364.68093016 - z: -31.330677554 - - speed: 1.70833337307 - acceleration_s: 0.848439761077 - curvature: -0.00237307149975 - curvature_change_rate: 0 - relative_time: 0 - theta: -1.81266143871 - accumulated_s: 0.16716666937000002 -} -adc_trajectory_point { - x: -124.413740829 - y: 364.646558161 - z: -31.330341435 - - speed: 1.7277777195 - acceleration_s: 0.839788102862 - curvature: -0.00233479501735 - curvature_change_rate: 0.00221535918454 - relative_time: 0.019999980926513672 - theta: -1.81271721372 - accumulated_s: 0.18444444656999992 -} -adc_trajectory_point { - x: -124.418160805 - y: 364.629263991 - z: -31.3301604046 - - speed: 1.7277777195 - acceleration_s: 0.796361476988 - curvature: -0.00233479501735 - curvature_change_rate: 0 - relative_time: 0.029999971389770508 - theta: -1.8127539742 - accumulated_s: 0.20172222376000004 -} -adc_trajectory_point { - x: -124.422587432 - y: 364.611881599 - z: -31.329923776 - - speed: 1.74166667461 - acceleration_s: 0.796361476988 - curvature: -0.00229651859052 - curvature_change_rate: 0.00219768956878 - relative_time: 0.039999961853027344 - theta: -1.81278276405 - accumulated_s: 0.21913889051000002 -} -adc_trajectory_point { - x: -124.42702661 - y: 364.59441933 - z: -31.329741355 - - speed: 1.74166667461 - acceleration_s: 0.79238461037 - curvature: -0.00229651859052 - curvature_change_rate: 0 - relative_time: 0.04999995231628418 - theta: -1.81281670152 - accumulated_s: 0.23655555725 -} -adc_trajectory_point { - x: -124.431486786 - y: 364.576916664 - z: -31.3295119135 - - speed: 1.75833332539 - acceleration_s: 0.623637235555 - curvature: -0.00229651859052 - curvature_change_rate: 0 - relative_time: 0.059999942779541016 - theta: -1.8128477221 - accumulated_s: 0.25413889050999994 -} -adc_trajectory_point { - x: -124.435979126 - y: 364.559317752 - z: -31.3293451639 - - speed: 1.75833332539 - acceleration_s: 0.78715534576 - curvature: -0.00229651859052 - curvature_change_rate: 0 - relative_time: 0.069999933242797852 - theta: -1.81292572329 - accumulated_s: 0.2717222237600001 -} -adc_trajectory_point { - x: -124.440512829 - y: 364.541682956 - z: -31.3291209918 - - speed: 1.7722222805 - acceleration_s: 0.651805683286 - curvature: -0.00225824221834 - curvature_change_rate: 0.00215979522414 - relative_time: 0.080000162124633789 - theta: -1.81300561803 - accumulated_s: 0.2894444465699999 -} -adc_trajectory_point { - x: -124.440512829 - y: 364.541682956 - z: -31.3291209918 - - speed: 1.7722222805 - acceleration_s: 0.651805683286 - curvature: -0.00225824221834 - curvature_change_rate: 0 - relative_time: 0.080000162124633789 - theta: -1.81300561803 - accumulated_s: 0.30716666936999992 -} -adc_trajectory_point { - x: -124.449549206 - y: 364.506162589 - z: -31.3285673754 - - speed: 1.78888893127 - acceleration_s: 0.710935224764 - curvature: -0.00221996589991 - curvature_change_rate: 0.00213966992371 - relative_time: 0.10000014305114746 - theta: -1.81308814408 - accumulated_s: 0.32505555867999991 -} -adc_trajectory_point { - x: -124.454089513 - y: 364.488330402 - z: -31.3283397462 - - speed: 1.78888893127 - acceleration_s: 0.570744609263 - curvature: -0.00221996589991 - curvature_change_rate: 0 - relative_time: 0.1100001335144043 - theta: -1.81312803791 - accumulated_s: 0.3429444479999999 -} -adc_trajectory_point { - x: -124.458653948 - y: 364.470391315 - z: -31.3280404089 - - speed: 1.80277776718 - acceleration_s: 0.765021682693 - curvature: -0.00218168963431 - curvature_change_rate: 0.00212318269586 - relative_time: 0.12000012397766113 - theta: -1.81320046776 - accumulated_s: 0.36097222567000009 -} -adc_trajectory_point { - x: -124.463241748 - y: 364.45241929 - z: -31.3277416844 - - speed: 1.80277776718 - acceleration_s: 0.654807529919 - curvature: -0.00218168963431 - curvature_change_rate: 0 - relative_time: 0.13000011444091797 - theta: -1.81324631449 - accumulated_s: 0.37900000334000006 -} -adc_trajectory_point { - x: -124.46783809 - y: 364.434363713 - z: -31.3274464924 - - speed: 1.81944441795 - acceleration_s: 0.654807529919 - curvature: -0.00214341342064 - curvature_change_rate: 0.00210373085859 - relative_time: 0.1400001049041748 - theta: -1.81332741838 - accumulated_s: 0.39719444752 -} -adc_trajectory_point { - x: -124.47245785 - y: 364.416250084 - z: -31.3270961335 - - speed: 1.81944441795 - acceleration_s: 0.674982832465 - curvature: -0.00214341342064 - curvature_change_rate: 0 - relative_time: 0.15000009536743164 - theta: -1.81337278819 - accumulated_s: 0.41538889169999993 -} -adc_trajectory_point { - x: -124.477095653 - y: 364.398088042 - z: -31.326754651 - - speed: 1.83611106873 - acceleration_s: 0.552212210239 - curvature: -0.00210513725798 - curvature_change_rate: 0.00208463220531 - relative_time: 0.16000008583068848 - theta: -1.813443323 - accumulated_s: 0.43375000239000006 -} -adc_trajectory_point { - x: -124.48176616 - y: 364.379838609 - z: -31.326410614 - - speed: 1.83611106873 - acceleration_s: 0.740273402835 - curvature: -0.00210513725798 - curvature_change_rate: 0 - relative_time: 0.17000007629394531 - theta: -1.81353389521 - accumulated_s: 0.45211111306999996 -} -adc_trajectory_point { - x: -124.486428356 - y: 364.361555494 - z: -31.3261427637 - - speed: 1.85000002384 - acceleration_s: 0.580707000797 - curvature: -0.00206686114541 - curvature_change_rate: 0.00206897903083 - relative_time: 0.18000006675720215 - theta: -1.81356533084 - accumulated_s: 0.47061111330999994 -} -adc_trajectory_point { - x: -124.491086517 - y: 364.343166634 - z: -31.3257930893 - - speed: 1.85000002384 - acceleration_s: 0.725814506272 - curvature: -0.00206686114541 - curvature_change_rate: 0 - relative_time: 0.19000005722045898 - theta: -1.81360825438 - accumulated_s: 0.48911111354999992 -} -adc_trajectory_point { - x: -124.491086517 - y: 364.343166634 - z: -31.3257930893 - - speed: 1.86388885975 - acceleration_s: 0.725814506272 - curvature: -0.00202858508204 - curvature_change_rate: 0.00205355931895 - relative_time: 0.19000005722045898 - theta: -1.81360825438 - accumulated_s: 0.5077500021500001 -} -adc_trajectory_point { - x: -124.500568552 - y: 364.306281933 - z: -31.3251117049 - - speed: 1.86388885975 - acceleration_s: 0.578514170379 - curvature: -0.00202858508204 - curvature_change_rate: 0 - relative_time: 0.21000003814697266 - theta: -1.81377712139 - accumulated_s: 0.52638889075000006 -} -adc_trajectory_point { - x: -124.505284561 - y: 364.287718639 - z: -31.3248510277 - - speed: 1.87777781487 - acceleration_s: 0.733719666282 - curvature: -0.00199030906694 - curvature_change_rate: 0.00203836762757 - relative_time: 0.22000002861022949 - theta: -1.81380727115 - accumulated_s: 0.54516666889000009 -} -adc_trajectory_point { - x: -124.510040247 - y: 364.269117353 - z: -31.3245309526 - - speed: 1.87777781487 - acceleration_s: 0.545171679849 - curvature: -0.00199030906694 - curvature_change_rate: 0 - relative_time: 0.23000001907348633 - theta: -1.81383336004 - accumulated_s: 0.56394444703999991 -} -adc_trajectory_point { - x: -124.514817529 - y: 364.250426387 - z: -31.3242240939 - - speed: 1.89166665077 - acceleration_s: 0.70451380624 - curvature: -0.00195203309921 - curvature_change_rate: 0.00202339919208 - relative_time: 0.24000000953674316 - theta: -1.8138975348 - accumulated_s: 0.58286111354999992 -} -adc_trajectory_point { - x: -124.519599994 - y: 364.231695691 - z: -31.3239948656 - - speed: 1.89166665077 - acceleration_s: 0.70451380624 - curvature: -0.00195203309921 - curvature_change_rate: 0 - relative_time: 0.25 - theta: -1.81392737 - accumulated_s: 0.60177778005999993 -} -adc_trajectory_point { - x: -124.524397496 - y: 364.212904296 - z: -31.3237304427 - - speed: 1.90833330154 - acceleration_s: 0.579897214634 - curvature: -0.00191375717794 - curvature_change_rate: 0.00200572516558 - relative_time: 0.25999999046325684 - theta: -1.81397067294 - accumulated_s: 0.62086111307000014 -} -adc_trajectory_point { - x: -124.529204006 - y: 364.194037175 - z: -31.3235090738 - - speed: 1.90833330154 - acceleration_s: 0.664043300769 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.26999998092651367 - theta: -1.81400750394 - accumulated_s: 0.6399444460899999 -} -adc_trajectory_point { - x: -124.534002209 - y: 364.175124421 - z: -31.3233041149 - - speed: 1.92222225666 - acceleration_s: 0.543693233875 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.27999997138977051 - theta: -1.81400097688 - accumulated_s: 0.65916666866000018 -} -adc_trajectory_point { - x: -124.538850304 - y: 364.156134098 - z: -31.3231071895 - - speed: 1.92222225666 - acceleration_s: 0.646040675764 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.28999996185302734 - theta: -1.81407158499 - accumulated_s: 0.67838889122 -} -adc_trajectory_point { - x: -124.543679992 - y: 364.137093008 - z: -31.3229501601 - - speed: 1.93611109257 - acceleration_s: 0.646040675764 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.29999995231628418 - theta: -1.81407281585 - accumulated_s: 0.69775000214999983 -} -adc_trajectory_point { - x: -124.548536345 - y: 364.117982962 - z: -31.3227286693 - - speed: 1.93611109257 - acceleration_s: 0.622100636076 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.309999942779541 - theta: -1.81411772979 - accumulated_s: 0.71711111307000008 -} -adc_trajectory_point { - x: -124.553410471 - y: 364.098815731 - z: -31.3226654641 - - speed: 1.94722223282 - acceleration_s: 0.684868392467 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.31999993324279785 - theta: -1.81417388783 - accumulated_s: 0.73658333540000021 -} -adc_trajectory_point { - x: -124.558283914 - y: 364.079585656 - z: -31.3224984268 - - speed: 1.94722223282 - acceleration_s: 0.573879708316 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.33000016212463379 - theta: -1.81419237818 - accumulated_s: 0.75605555772999988 -} -adc_trajectory_point { - x: -124.558283914 - y: 364.079585656 - z: -31.3224984268 - - speed: 1.96388888359 - acceleration_s: 0.573879708316 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.33000016212463379 - theta: -1.81419237818 - accumulated_s: 0.7756944465700002 -} -adc_trajectory_point { - x: -124.56804333 - y: 364.040941718 - z: -31.3223221367 - - speed: 1.96388888359 - acceleration_s: 0.603920311959 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.35000014305114746 - theta: -1.81423909981 - accumulated_s: 0.79533333540000006 -} -adc_trajectory_point { - x: -124.572951875 - y: 364.021539676 - z: -31.3221889641 - - speed: 1.9777777195 - acceleration_s: 0.555519021968 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.3600001335144043 - theta: -1.81427907955 - accumulated_s: 0.81511111259999991 -} -adc_trajectory_point { - x: -124.577850514 - y: 364.002080082 - z: -31.3222134952 - - speed: 1.9777777195 - acceleration_s: 0.61368027684 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.37000012397766113 - theta: -1.81433748319 - accumulated_s: 0.8348888897900002 -} -adc_trajectory_point { - x: -124.582810583 - y: 363.982557264 - z: -31.3221274754 - - speed: 1.98888885975 - acceleration_s: 0.578355004978 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.38000011444091797 - theta: -1.81440993028 - accumulated_s: 0.85477777838999991 -} -adc_trajectory_point { - x: -124.587728192 - y: 363.962979756 - z: -31.3221053937 - - speed: 1.98888885975 - acceleration_s: 0.537373855617 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.3900001049041748 - theta: -1.81445166373 - accumulated_s: 0.87466666699000006 -} -adc_trajectory_point { - x: -124.587728192 - y: 363.962979756 - z: -31.3221053937 - - speed: 2.00277781487 - acceleration_s: 0.537373855617 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.3900001049041748 - theta: -1.81445166373 - accumulated_s: 0.89469444513999985 -} -adc_trajectory_point { - x: -124.597654504 - y: 363.923691761 - z: -31.3219676949 - - speed: 2.00277781487 - acceleration_s: 0.405916936513 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.41000008583068848 - theta: -1.81460229183 - accumulated_s: 0.91472222328000008 -} -adc_trajectory_point { - x: -124.602613236 - y: 363.903946441 - z: -31.32195119 - - speed: 2.01666665077 - acceleration_s: 0.616783362769 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.42000007629394531 - theta: -1.81466837499 - accumulated_s: 0.93488888978999984 -} -adc_trajectory_point { - x: -124.607570356 - y: 363.884150608 - z: -31.3219562313 - - speed: 2.01666665077 - acceleration_s: 0.588264258574 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.43000006675720215 - theta: -1.8146952687 - accumulated_s: 0.9550555563 -} -adc_trajectory_point { - x: -124.612537258 - y: 363.864291562 - z: -31.3218616117 - - speed: 2.02777767181 - acceleration_s: 0.556305840073 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.440000057220459 - theta: -1.81476626065 - accumulated_s: 0.97533333302 -} -adc_trajectory_point { - x: -124.612537258 - y: 363.864291562 - z: -31.3218616117 - - speed: 2.02777767181 - acceleration_s: 0.556305840073 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.440000057220459 - theta: -1.81476626065 - accumulated_s: 0.99561110974 -} -adc_trajectory_point { - x: -124.622499358 - y: 363.824418458 - z: -31.3218937051 - - speed: 2.04166674614 - acceleration_s: 0.48222098721 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.46000003814697266 - theta: -1.81489784186 - accumulated_s: 1.0160277772000001 -} -adc_trajectory_point { - x: -124.627475438 - y: 363.804392094 - z: -31.3218720127 - - speed: 2.04166674614 - acceleration_s: 0.532368831835 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.47000002861022949 - theta: -1.81495720235 - accumulated_s: 1.0364444446599999 -} -adc_trajectory_point { - x: -124.632512007 - y: 363.784329814 - z: -31.3218311286 - - speed: 2.05277776718 - acceleration_s: 0.541348464225 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.48000001907348633 - theta: -1.81505135668 - accumulated_s: 1.0569722223300002 -} -adc_trajectory_point { - x: -124.63750936 - y: 363.76423134 - z: -31.3217679281 - - speed: 2.05277776718 - acceleration_s: 0.384251194079 - curvature: -0.00191375717794 - curvature_change_rate: 0 - relative_time: 0.49000000953674316 - theta: -1.8151075005 - accumulated_s: 1.0775000000000001 -} -adc_trajectory_point { - x: -124.64249871 - y: 363.744073275 - z: -31.3217562251 - - speed: 2.06666660309 - acceleration_s: 0.384251194079 - curvature: -0.00187548130221 - curvature_change_rate: 0.00185205855989 - relative_time: 0.5 - theta: -1.8151331721 - accumulated_s: 1.09816666603 -} -adc_trajectory_point { - x: -124.64249871 - y: 363.744073275 - z: -31.3217562251 - - speed: 2.06666660309 - acceleration_s: 0.471254936837 - curvature: -0.00187548130221 - curvature_change_rate: 0 - relative_time: 0.5 - theta: -1.8151331721 - accumulated_s: 1.11883333206 -} -adc_trajectory_point { - x: -124.65260313 - y: 363.703665697 - z: -31.3216385534 - - speed: 2.07500004768 - acceleration_s: 0.392185464525 - curvature: -0.00187548130221 - curvature_change_rate: 0 - relative_time: 0.51999998092651367 - theta: -1.81530989827 - accumulated_s: 1.13958333254 -} -adc_trajectory_point { - x: -124.657703511 - y: 363.683362708 - z: -31.3215296138 - - speed: 2.07500004768 - acceleration_s: 0.63036516098 - curvature: -0.00187548130221 - curvature_change_rate: 0 - relative_time: 0.52999997138977051 - theta: -1.81538619428 - accumulated_s: 1.16033333302 -} -adc_trajectory_point { - x: -124.662779303 - y: 363.663037709 - z: -31.3214895967 - - speed: 2.08333325386 - acceleration_s: 0.438201118283 - curvature: -0.00179892968375 - curvature_change_rate: 0.00367447782632 - relative_time: 0.53999996185302734 - theta: -1.81543663872 - accumulated_s: 1.1811666655600002 -} -adc_trajectory_point { - x: -124.667900187 - y: 363.642640381 - z: -31.3213308156 - - speed: 2.08333325386 - acceleration_s: 0.565809026914 - curvature: -0.00179892968375 - curvature_change_rate: 0 - relative_time: 0.54999995231628418 - theta: -1.81550191038 - accumulated_s: 1.2019999980999998 -} -adc_trajectory_point { - x: -124.673044801 - y: 363.622231883 - z: -31.3212905452 - - speed: 2.09722232819 - acceleration_s: 0.565809026914 - curvature: -0.0017606539392 - curvature_change_rate: 0.0018250685224 - relative_time: 0.559999942779541 - theta: -1.81555087063 - accumulated_s: 1.22297222138 -} -adc_trajectory_point { - x: -124.678227606 - y: 363.60177704 - z: -31.321100113 - - speed: 2.09722232819 - acceleration_s: 0.410090532827 - curvature: -0.0017606539392 - curvature_change_rate: 0 - relative_time: 0.56999993324279785 - theta: -1.81562391057 - accumulated_s: 1.2439444446599999 -} -adc_trajectory_point { - x: -124.683408173 - y: 363.581283104 - z: -31.321023169 - - speed: 2.10833334923 - acceleration_s: 0.449863896268 - curvature: -0.00168410257488 - curvature_change_rate: 0.00363089472296 - relative_time: 0.58000016212463379 - theta: -1.81565742152 - accumulated_s: 1.26502777815 -} -adc_trajectory_point { - x: -124.688631183 - y: 363.560746635 - z: -31.3208483625 - - speed: 2.10833334923 - acceleration_s: 0.44139750351 - curvature: -0.00168410257488 - curvature_change_rate: 0 - relative_time: 0.59000015258789062 - theta: -1.81570010868 - accumulated_s: 1.28611111164 -} -adc_trajectory_point { - x: -124.693826843 - y: 363.540166385 - z: -31.3206919003 - - speed: 2.1166665554 - acceleration_s: 0.44139750351 - curvature: -0.00160755137088 - curvature_change_rate: 0.00361659250512 - relative_time: 0.60000014305114746 - theta: -1.81572846193 - accumulated_s: 1.3072777772 -} -adc_trajectory_point { - x: -124.699096691 - y: 363.519545692 - z: -31.3205524767 - - speed: 2.1166665554 - acceleration_s: 0.507769781112 - curvature: -0.00160755137088 - curvature_change_rate: 0 - relative_time: 0.6100001335144043 - theta: -1.81579399972 - accumulated_s: 1.32844444275 -} -adc_trajectory_point { - x: -124.704331371 - y: 363.498896276 - z: -31.3203653041 - - speed: 2.125 - acceleration_s: 0.33837386187 - curvature: -0.00149272484953 - curvature_change_rate: 0.00540360100454 - relative_time: 0.62000012397766113 - theta: -1.815802083 - accumulated_s: 1.3496944427500002 -} -adc_trajectory_point { - x: -124.709628969 - y: 363.478187565 - z: -31.3201688137 - - speed: 2.125 - acceleration_s: 0.501408729412 - curvature: -0.00149272484953 - curvature_change_rate: 0 - relative_time: 0.630000114440918 - theta: -1.81587572212 - accumulated_s: 1.37094444275 -} -adc_trajectory_point { - x: -124.714943161 - y: 363.457429119 - z: -31.3199786805 - - speed: 2.1333334446 - acceleration_s: 0.554039056654 - curvature: -0.00137789864791 - curvature_change_rate: 0.00538247792035 - relative_time: 0.6400001049041748 - theta: -1.81592346159 - accumulated_s: 1.3922777772 -} -adc_trajectory_point { - x: -124.720250813 - y: 363.436649017 - z: -31.3197827172 - - speed: 2.1333334446 - acceleration_s: 0.395016178716 - curvature: -0.00137789864791 - curvature_change_rate: 0 - relative_time: 0.65000009536743164 - theta: -1.81597240124 - accumulated_s: 1.4136111116399999 -} -adc_trajectory_point { - x: -124.725576877 - y: 363.41580601 - z: -31.3195367893 - - speed: 2.14444446564 - acceleration_s: 0.395016178716 - curvature: -0.00130134790508 - curvature_change_rate: 0.00356972372356 - relative_time: 0.66000008583068848 - theta: -1.81600363529 - accumulated_s: 1.4350555563 -} -adc_trajectory_point { - x: -124.73087675 - y: 363.39494827 - z: -31.3193469858 - - speed: 2.14444446564 - acceleration_s: 0.318885692776 - curvature: -0.00130134790508 - curvature_change_rate: 0 - relative_time: 0.67000007629394531 - theta: -1.81600079944 - accumulated_s: 1.4565000009600002 -} -adc_trajectory_point { - x: -124.736216839 - y: 363.374057061 - z: -31.3190368135 - - speed: 2.15277767181 - acceleration_s: 0.333498077567 - curvature: -0.00122479739336 - curvature_change_rate: 0.0035558949131 - relative_time: 0.68000006675720215 - theta: -1.81606191847 - accumulated_s: 1.47802777767 -} -adc_trajectory_point { - x: -124.741576664 - y: 363.353124751 - z: -31.31877816 - - speed: 2.15277767181 - acceleration_s: 0.425183516383 - curvature: -0.00122479739336 - curvature_change_rate: 0 - relative_time: 0.690000057220459 - theta: -1.81611229004 - accumulated_s: 1.49955555439 -} -adc_trajectory_point { - x: -124.741576664 - y: 363.353124751 - z: -31.31877816 - - speed: 2.16111111641 - acceleration_s: 0.425183516383 - curvature: -0.00118652218167 - curvature_change_rate: 0.00177108948228 - relative_time: 0.690000057220459 - theta: -1.81611229004 - accumulated_s: 1.52116666556 -} -adc_trajectory_point { - x: -124.752221031 - y: 363.311269328 - z: -31.3181767426 - - speed: 2.16111111641 - acceleration_s: 0.424061091593 - curvature: -0.00118652218167 - curvature_change_rate: 0 - relative_time: 0.71000003814697266 - theta: -1.81618315245 - accumulated_s: 1.54277777672 -} -adc_trajectory_point { - x: -124.757590008 - y: 363.290219413 - z: -31.3178582489 - - speed: 2.16666674614 - acceleration_s: 0.403375544049 - curvature: -0.00114824699823 - curvature_change_rate: 0.00176654686347 - relative_time: 0.72000002861022949 - theta: -1.81622559154 - accumulated_s: 1.5644444441799998 -} -adc_trajectory_point { - x: -124.762941442 - y: 363.269138582 - z: -31.3174934853 - - speed: 2.16666674614 - acceleration_s: 0.326489423611 - curvature: -0.00114824699823 - curvature_change_rate: 0 - relative_time: 0.73000001907348633 - theta: -1.81625356007 - accumulated_s: 1.5861111116400002 -} -adc_trajectory_point { - x: -124.768338499 - y: 363.247992939 - z: -31.3171917684 - - speed: 2.17499995232 - acceleration_s: 0.519132437172 - curvature: -0.00110997184211 - curvature_change_rate: 0.00175977733142 - relative_time: 0.74000000953674316 - theta: -1.8162998717 - accumulated_s: 1.60786111117 -} -adc_trajectory_point { - x: -124.768338499 - y: 363.247992939 - z: -31.3171917684 - - speed: 2.17499995232 - acceleration_s: 0.519132437172 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.74000000953674316 - theta: -1.8162998717 - accumulated_s: 1.62961111069 -} -adc_trajectory_point { - x: -124.779094251 - y: 363.205595132 - z: -31.3165621795 - - speed: 2.18333339691 - acceleration_s: 0.397473427894 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.75999999046325684 - theta: -1.81634104056 - accumulated_s: 1.65144444466 -} -adc_trajectory_point { - x: -124.784453844 - y: 363.184287854 - z: -31.316247059 - - speed: 2.18333339691 - acceleration_s: 0.454685810527 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.76999998092651367 - theta: -1.8162850446 - accumulated_s: 1.6732777786300002 -} -adc_trajectory_point { - x: -124.789850241 - y: 363.16298002 - z: -31.3158767791 - - speed: 2.18333339691 - acceleration_s: 0.29593802736 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.77999997138977051 - theta: -1.81630023217 - accumulated_s: 1.6951111125999998 -} -adc_trajectory_point { - x: -124.795270183 - y: 363.141635367 - z: -31.3155408166 - - speed: 2.19166660309 - acceleration_s: 0.366713112667 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.78999996185302734 - theta: -1.8163197048 - accumulated_s: 1.71702777863 -} -adc_trajectory_point { - x: -124.800712164 - y: 363.120264703 - z: -31.3152514435 - - speed: 2.20000004768 - acceleration_s: 0.322351732867 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.79999995231628418 - theta: -1.81633196238 - accumulated_s: 1.7390277791100002 -} -adc_trajectory_point { - x: -124.806146552 - y: 363.098872199 - z: -31.3149091844 - - speed: 2.20000004768 - acceleration_s: 0.245755836194 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.809999942779541 - theta: -1.81635659266 - accumulated_s: 1.76102777958 -} -adc_trajectory_point { - x: -124.811598191 - y: 363.077421343 - z: -31.3145428207 - - speed: 2.205555439 - acceleration_s: 0.408752886651 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.81999993324279785 - theta: -1.81634827804 - accumulated_s: 1.78308333397 -} -adc_trajectory_point { - x: -124.81708544 - y: 363.055964991 - z: -31.3142130179 - - speed: 2.205555439 - acceleration_s: 0.312351941169 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.83000016212463379 - theta: -1.81639688851 - accumulated_s: 1.8051388883600001 -} -adc_trajectory_point { - x: -124.81708544 - y: 363.055964991 - z: -31.3142130179 - - speed: 2.21388888359 - acceleration_s: 0.312351941169 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.83000016212463379 - theta: -1.81639688851 - accumulated_s: 1.8272777772 -} -adc_trajectory_point { - x: -124.822590897 - y: 363.034458283 - z: -31.3138107536 - - speed: 2.21388888359 - acceleration_s: 0.435838020412 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.84000015258789062 - theta: -1.81646420911 - accumulated_s: 1.8494166660300002 -} -adc_trajectory_point { - x: -124.833592056 - y: 362.99131051 - z: -31.3131701481 - - speed: 2.22499990463 - acceleration_s: 0.332456477929 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.8600001335144043 - theta: -1.81650298808 - accumulated_s: 1.8716666650799998 -} -adc_trajectory_point { - x: -124.83909123 - y: 362.969675964 - z: -31.3128626989 - - speed: 2.22499990463 - acceleration_s: 0.403803181453 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.87000012397766113 - theta: -1.81650780592 - accumulated_s: 1.8939166641299998 -} -adc_trajectory_point { - x: -124.844627275 - y: 362.948035607 - z: -31.312549402 - - speed: 2.23333334923 - acceleration_s: 0.284167077771 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.880000114440918 - theta: -1.81654895806 - accumulated_s: 1.91624999762 -} -adc_trajectory_point { - x: -124.850138769 - y: 362.926365171 - z: -31.3121814989 - - speed: 2.23333334923 - acceleration_s: 0.219597182708 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.8900001049041748 - theta: -1.81656080112 - accumulated_s: 1.9385833311099998 -} -adc_trajectory_point { - x: -124.855733527 - y: 362.904661558 - z: -31.3118566293 - - speed: 2.2416665554 - acceleration_s: 0.358176007095 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.90000009536743164 - theta: -1.81666201751 - accumulated_s: 1.96099999666 -} -adc_trajectory_point { - x: -124.861246653 - y: 362.882922273 - z: -31.311575816 - - speed: 2.2416665554 - acceleration_s: 0.272688389046 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 0.91000008583068848 - theta: -1.81665735581 - accumulated_s: 1.9834166622199998 -} -adc_trajectory_point { - x: -124.866788905 - y: 362.861141033 - z: -31.3113530278 - - speed: 2.24722218513 - acceleration_s: 0.38116814692 - curvature: -0.0010716967124 - curvature_change_rate: 0.00170321964409 - relative_time: 0.92000007629394531 - theta: -1.81668984453 - accumulated_s: 2.00588888407 -} -adc_trajectory_point { - x: -124.872339689 - y: 362.839321604 - z: -31.3110525412 - - speed: 2.24722218513 - acceleration_s: 0.395045581062 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 0.93000006675720215 - theta: -1.81670429751 - accumulated_s: 2.02836110592 -} -adc_trajectory_point { - x: -124.877914017 - y: 362.817487959 - z: -31.3107835148 - - speed: 2.25277781487 - acceleration_s: 0.30269333311 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 0.940000057220459 - theta: -1.81677195389 - accumulated_s: 2.05088888407 -} -adc_trajectory_point { - x: -124.877914017 - y: 362.817487959 - z: -31.3107835148 - - speed: 2.25277781487 - acceleration_s: 0.30269333311 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 0.940000057220459 - theta: -1.81677195389 - accumulated_s: 2.07341666222 -} -adc_trajectory_point { - x: -124.88912335 - y: 362.773678888 - z: -31.3103790181 - - speed: 2.26111102104 - acceleration_s: 0.360417891351 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 0.96000003814697266 - theta: -1.81688383407 - accumulated_s: 2.09602777243 -} -adc_trajectory_point { - x: -124.894731201 - y: 362.751723765 - z: -31.3102013376 - - speed: 2.26111102104 - acceleration_s: 0.379883345667 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 0.97000002861022949 - theta: -1.81692629508 - accumulated_s: 2.11863888264 -} -adc_trajectory_point { - x: -124.900382966 - y: 362.72974915 - z: -31.3100582911 - - speed: 2.26944446564 - acceleration_s: 0.3383902173 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 0.98000001907348633 - theta: -1.8169942881 - accumulated_s: 2.1413333273 -} -adc_trajectory_point { - x: -124.906011486 - y: 362.707746991 - z: -31.3099116171 - - speed: 2.26944446564 - acceleration_s: 0.3383902173 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 0.99000000953674316 - theta: -1.81701167396 - accumulated_s: 2.16402777195 -} -adc_trajectory_point { - x: -124.911657594 - y: 362.685697221 - z: -31.3098106673 - - speed: 2.27777767181 - acceleration_s: 0.253441101364 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1 - theta: -1.81704007269 - accumulated_s: 2.18680554867 -} -adc_trajectory_point { - x: -124.917342271 - y: 362.663621334 - z: -31.3097051326 - - speed: 2.27777767181 - acceleration_s: 0.351491129558 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.0099999904632568 - theta: -1.817078017 - accumulated_s: 2.20958332539 -} -adc_trajectory_point { - x: -124.922997579 - y: 362.641505243 - z: -31.3096190887 - - speed: 2.28333330154 - acceleration_s: 0.335841421129 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.0199999809265137 - theta: -1.81708784507 - accumulated_s: 2.2324166584 -} -adc_trajectory_point { - x: -124.928712232 - y: 362.619380661 - z: -31.3095990429 - - speed: 2.28333330154 - acceleration_s: 0.320966118743 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.0299999713897705 - theta: -1.81714495953 - accumulated_s: 2.25524999142 -} -adc_trajectory_point { - x: -124.934424731 - y: 362.597219355 - z: -31.309548161 - - speed: 2.29166674614 - acceleration_s: 0.276110419835 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.0399999618530273 - theta: -1.81716699596 - accumulated_s: 2.27816665888 -} -adc_trajectory_point { - x: -124.940134488 - y: 362.575015263 - z: -31.309490839 - - speed: 2.29166674614 - acceleration_s: 0.276110419835 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.0499999523162842 - theta: -1.81718843848 - accumulated_s: 2.30108332634 -} -adc_trajectory_point { - x: -124.945890063 - y: 362.552795248 - z: -31.3095432203 - - speed: 2.29999995232 - acceleration_s: 0.354382152136 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.059999942779541 - theta: -1.81723244496 - accumulated_s: 2.3240833258699998 -} -adc_trajectory_point { - x: -124.951605962 - y: 362.530523981 - z: -31.3095214432 - - speed: 2.29999995232 - acceleration_s: 0.324520312094 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.0699999332427979 - theta: -1.81723087207 - accumulated_s: 2.34708332539 -} -adc_trajectory_point { - x: -124.957321709 - y: 362.508220335 - z: -31.3095393144 - - speed: 2.30555558205 - acceleration_s: 0.348487246706 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.0800001621246338 - theta: -1.81721876492 - accumulated_s: 2.37013888121 -} -adc_trajectory_point { - x: -124.963071922 - y: 362.485895519 - z: -31.3095405428 - - speed: 2.30555558205 - acceleration_s: 0.32138151059 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.0900001525878906 - theta: -1.81724543977 - accumulated_s: 2.39319443703 -} -adc_trajectory_point { - x: -124.968806615 - y: 362.463537572 - z: -31.3095670613 - - speed: 2.31388878822 - acceleration_s: 0.280537841948 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.1000001430511475 - theta: -1.81726134313 - accumulated_s: 2.41633332491 -} -adc_trajectory_point { - x: -124.974586177 - y: 362.441142231 - z: -31.3095919834 - - speed: 2.31388878822 - acceleration_s: 0.370225847881 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.1100001335144043 - theta: -1.81731874733 - accumulated_s: 2.43947221279 -} -adc_trajectory_point { - x: -124.980340511 - y: 362.418729208 - z: -31.3095278786 - - speed: 2.32222223282 - acceleration_s: 0.241979496989 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.1200001239776611 - theta: -1.81734233112 - accumulated_s: 2.46269443512 -} -adc_trajectory_point { - x: -124.986108794 - y: 362.396299265 - z: -31.3095189845 - - speed: 2.32222223282 - acceleration_s: 0.258339113235 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.130000114440918 - theta: -1.81741367267 - accumulated_s: 2.48591665745 -} -adc_trajectory_point { - x: -124.991854603 - y: 362.373844839 - z: -31.3094680347 - - speed: 2.32777786255 - acceleration_s: 0.206151345491 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.1400001049041748 - theta: -1.81742356958 - accumulated_s: 2.50919443608 -} -adc_trajectory_point { - x: -124.99761637 - y: 362.351373119 - z: -31.3094466757 - - speed: 2.32777786255 - acceleration_s: 0.206151345491 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.1500000953674316 - theta: -1.81747367091 - accumulated_s: 2.5324722147 -} -adc_trajectory_point { - x: -125.003396772 - y: 362.328847582 - z: -31.3093775567 - - speed: 2.33333325386 - acceleration_s: 0.379817082608 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.1600000858306885 - theta: -1.81754148719 - accumulated_s: 2.5558055472400003 -} -adc_trajectory_point { - x: -125.009165892 - y: 362.306293563 - z: -31.3092897991 - - speed: 2.33333325386 - acceleration_s: 0.299134172747 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.1700000762939453 - theta: -1.81757923795 - accumulated_s: 2.5791388797800003 -} -adc_trajectory_point { - x: -125.01491479 - y: 362.283695177 - z: -31.3091968307 - - speed: 2.33888888359 - acceleration_s: 0.360938366845 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.1800000667572021 - theta: -1.81761911764 - accumulated_s: 2.60252776861 -} -adc_trajectory_point { - x: -125.020689332 - y: 362.261076162 - z: -31.3090890879 - - speed: 2.33888888359 - acceleration_s: 0.349436649607 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.190000057220459 - theta: -1.81768910552 - accumulated_s: 2.6259166574500004 -} -adc_trajectory_point { - x: -125.020689332 - y: 362.261076162 - z: -31.3090890879 - - speed: 2.34722232819 - acceleration_s: 0.349436649607 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.190000057220459 - theta: -1.81768910552 - accumulated_s: 2.64938888073 -} -adc_trajectory_point { - x: -125.032223512 - y: 362.215734672 - z: -31.3088880777 - - speed: 2.34722232819 - acceleration_s: 0.382746253399 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.2100000381469727 - theta: -1.81779317675 - accumulated_s: 2.67286110401 -} -adc_trajectory_point { - x: -125.03801035 - y: 362.193008906 - z: -31.3087713663 - - speed: 2.35833334923 - acceleration_s: 0.355088601835 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.2200000286102295 - theta: -1.81784525819 - accumulated_s: 2.6964444375100003 -} -adc_trajectory_point { - x: -125.043777403 - y: 362.17025142 - z: -31.3086255761 - - speed: 2.35833334923 - acceleration_s: 0.293401082275 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.2300000190734863 - theta: -1.81789035034 - accumulated_s: 2.720027771 -} -adc_trajectory_point { - x: -125.049547628 - y: 362.147452091 - z: -31.3085405938 - - speed: 2.3666665554 - acceleration_s: 0.392681080735 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.2400000095367432 - theta: -1.81791038105 - accumulated_s: 2.7436944365500002 -} -adc_trajectory_point { - x: -125.055357917 - y: 362.124660437 - z: -31.3084632047 - - speed: 2.3666665554 - acceleration_s: 0.212717036543 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.25 - theta: -1.81798167142 - accumulated_s: 2.7673611021099997 -} -adc_trajectory_point { - x: -125.061163799 - y: 362.101799163 - z: -31.3083684873 - - speed: 2.37222218513 - acceleration_s: 0.402120536361 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.2599999904632568 - theta: -1.81802179654 - accumulated_s: 2.7910833239599997 -} -adc_trajectory_point { - x: -125.067021567 - y: 362.078912029 - z: -31.3083270611 - - speed: 2.37222218513 - acceleration_s: 0.40728875592 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.2699999809265137 - theta: -1.81809542476 - accumulated_s: 2.8148055458099996 -} -adc_trajectory_point { - x: -125.072829426 - y: 362.055975827 - z: -31.3082894357 - - speed: 2.37777781487 - acceleration_s: 0.384221677252 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.2799999713897705 - theta: -1.81809018366 - accumulated_s: 2.83858332396 -} -adc_trajectory_point { - x: -125.078695034 - y: 362.032988138 - z: -31.308244017 - - speed: 2.37777781487 - acceleration_s: 0.500380948926 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.2899999618530273 - theta: -1.81813979053 - accumulated_s: 2.8623611021100004 -} -adc_trajectory_point { - x: -125.084563219 - y: 362.00997671 - z: -31.3083070498 - - speed: 2.38611102104 - acceleration_s: 0.500380948926 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.2999999523162842 - theta: -1.81817159571 - accumulated_s: 2.88622221232 -} -adc_trajectory_point { - x: -125.090443743 - y: 361.986921063 - z: -31.3083240818 - - speed: 2.38611102104 - acceleration_s: 0.42359364563 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.309999942779541 - theta: -1.81820900677 - accumulated_s: 2.9100833225300002 -} -adc_trajectory_point { - x: -125.096382179 - y: 361.963823327 - z: -31.3084300598 - - speed: 2.39444446564 - acceleration_s: 0.441271914059 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.3199999332427979 - theta: -1.81826673453 - accumulated_s: 2.93402776718 -} -adc_trajectory_point { - x: -125.102305553 - y: 361.940693228 - z: -31.3084903685 - - speed: 2.39444446564 - acceleration_s: 0.371848661884 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.3300001621246338 - theta: -1.8182738089 - accumulated_s: 2.9579722118399996 -} -adc_trajectory_point { - x: -125.108232957 - y: 361.917510539 - z: -31.3085952336 - - speed: 2.40277767181 - acceleration_s: 0.430566906059 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.3400001525878906 - theta: -1.81827950286 - accumulated_s: 2.98199998856 -} -adc_trajectory_point { - x: -125.108232957 - y: 361.917510539 - z: -31.3085952336 - - speed: 2.40277767181 - acceleration_s: 0.430566906059 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.3400001525878906 - theta: -1.81827950286 - accumulated_s: 3.00602776528 -} -adc_trajectory_point { - x: -125.120187141 - y: 361.871080309 - z: -31.3087874381 - - speed: 2.41111111641 - acceleration_s: 0.327868528721 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.3600001335144043 - theta: -1.81832828484 - accumulated_s: 3.0301388764399997 -} -adc_trajectory_point { - x: -125.126181296 - y: 361.847791106 - z: -31.3088982496 - - speed: 2.41111111641 - acceleration_s: 0.451219002202 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.3700001239776611 - theta: -1.81832183957 - accumulated_s: 3.0542499875999995 -} -adc_trajectory_point { - x: -125.132231645 - y: 361.824497802 - z: -31.3090133145 - - speed: 2.41666674614 - acceleration_s: 0.356885881439 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.380000114440918 - theta: -1.81837974849 - accumulated_s: 3.07841665507 -} -adc_trajectory_point { - x: -125.138258952 - y: 361.801142214 - z: -31.3091033828 - - speed: 2.41666674614 - acceleration_s: 0.420614351144 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.3900001049041748 - theta: -1.81838505478 - accumulated_s: 3.10258332253 -} -adc_trajectory_point { - x: -125.138258952 - y: 361.801142214 - z: -31.3091033828 - - speed: 2.42777776718 - acceleration_s: 0.420614351144 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.3900001049041748 - theta: -1.81838505478 - accumulated_s: 3.1268611002 -} -adc_trajectory_point { - x: -125.1504013 - y: 361.754317185 - z: -31.3093132749 - - speed: 2.42777776718 - acceleration_s: 0.398169023032 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.4100000858306885 - theta: -1.81840952263 - accumulated_s: 3.1511388778700002 -} -adc_trajectory_point { - x: -125.156499401 - y: 361.730817079 - z: -31.3093788503 - - speed: 2.43611121178 - acceleration_s: 0.591555982708 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.4200000762939453 - theta: -1.81841737267 - accumulated_s: 3.1754999899899996 -} -adc_trajectory_point { - x: -125.162622415 - y: 361.70731755 - z: -31.3094226215 - - speed: 2.43611121178 - acceleration_s: 0.354240702412 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.4300000667572021 - theta: -1.81845171629 - accumulated_s: 3.19986110211 -} -adc_trajectory_point { - x: -125.168749178 - y: 361.683754857 - z: -31.3094495237 - - speed: 2.44166660309 - acceleration_s: 0.438057057872 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.440000057220459 - theta: -1.8184750244 - accumulated_s: 3.2242777681400003 -} -adc_trajectory_point { - x: -125.168749178 - y: 361.683754857 - z: -31.3094495237 - - speed: 2.44166660309 - acceleration_s: 0.438057057872 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.440000057220459 - theta: -1.8184750244 - accumulated_s: 3.24869443417 -} -adc_trajectory_point { - x: -125.181073192 - y: 361.636523244 - z: -31.3095965637 - - speed: 2.45277786255 - acceleration_s: 0.406559172215 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.4600000381469727 - theta: -1.81857129728 - accumulated_s: 3.2732222127900004 -} -adc_trajectory_point { - x: -125.187253533 - y: 361.612821763 - z: -31.3096149852 - - speed: 2.45277786255 - acceleration_s: 0.555435364511 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.4700000286102295 - theta: -1.81861428093 - accumulated_s: 3.29774999142 -} -adc_trajectory_point { - x: -125.193447694 - y: 361.589087084 - z: -31.3096721135 - - speed: 2.46111106873 - acceleration_s: 0.474561880611 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.4800000190734863 - theta: -1.81864823851 - accumulated_s: 3.3223611021100004 -} -adc_trajectory_point { - x: -125.199648161 - y: 361.565319286 - z: -31.3096358571 - - speed: 2.46111106873 - acceleration_s: 0.39098499412 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.4900000095367432 - theta: -1.81871111009 - accumulated_s: 3.34697221279 -} -adc_trajectory_point { - x: -125.205877684 - y: 361.541492939 - z: -31.3096838295 - - speed: 2.46944451332 - acceleration_s: 0.39098499412 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.5 - theta: -1.81876580215 - accumulated_s: 3.3716666579299996 -} -adc_trajectory_point { - x: -125.212107542 - y: 361.517644532 - z: -31.3097066302 - - speed: 2.46944451332 - acceleration_s: 0.378531990209 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.5099999904632568 - theta: -1.81882500449 - accumulated_s: 3.3963611030600003 -} -adc_trajectory_point { - x: -125.218346849 - y: 361.493731449 - z: -31.309656702 - - speed: 2.47499990463 - acceleration_s: 0.47112637066 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.5199999809265137 - theta: -1.81886503663 - accumulated_s: 3.4211111021100002 -} -adc_trajectory_point { - x: -125.224611842 - y: 361.469764138 - z: -31.3097078418 - - speed: 2.47499990463 - acceleration_s: 0.574009610061 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.5299999713897705 - theta: -1.818928914 - accumulated_s: 3.44586110115 -} -adc_trajectory_point { - x: -125.230903508 - y: 361.445775601 - z: -31.30969417 - - speed: 2.47499990463 - acceleration_s: 0.426942605328 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.5399999618530273 - theta: -1.81902915216 - accumulated_s: 3.4706111002 -} -adc_trajectory_point { - x: -125.237193935 - y: 361.421710391 - z: -31.3097933289 - - speed: 2.4777777195 - acceleration_s: 0.426942605328 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.5499999523162842 - theta: -1.81910561914 - accumulated_s: 3.49538887739 -} -adc_trajectory_point { - x: -125.243475659 - y: 361.397603752 - z: -31.3098835414 - - speed: 2.48611116409 - acceleration_s: 0.514772887587 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.559999942779541 - theta: -1.81914558193 - accumulated_s: 3.52024998904 -} -adc_trajectory_point { - x: -125.249806194 - y: 361.373444574 - z: -31.3098348845 - - speed: 2.48611116409 - acceleration_s: 0.48136122605 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.5699999332427979 - theta: -1.81924363629 - accumulated_s: 3.54511110068 -} -adc_trajectory_point { - x: -125.256129277 - y: 361.349208057 - z: -31.3098312309 - - speed: 2.49444437027 - acceleration_s: 0.650386793625 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.5800001621246338 - theta: -1.81930289222 - accumulated_s: 3.5700555443799997 -} -adc_trajectory_point { - x: -125.262467753 - y: 361.324961814 - z: -31.309970025 - - speed: 2.49444437027 - acceleration_s: 0.455046489661 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.5900001525878906 - theta: -1.81940221501 - accumulated_s: 3.5949999880799997 -} -adc_trajectory_point { - x: -125.262467753 - y: 361.324961814 - z: -31.309970025 - - speed: 2.49444437027 - acceleration_s: 0.455046489661 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.5900001525878906 - theta: -1.81940221501 - accumulated_s: 3.6199444317799996 -} -adc_trajectory_point { - x: -125.275156926 - y: 361.276277158 - z: -31.3101264155 - - speed: 2.50555562973 - acceleration_s: 0.504832206055 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.6100001335144043 - theta: -1.81951968729 - accumulated_s: 3.6449999880800004 -} -adc_trajectory_point { - x: -125.281505449 - y: 361.251891324 - z: -31.3101503132 - - speed: 2.51666665077 - acceleration_s: 0.330095511333 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.6200001239776611 - theta: -1.81957494803 - accumulated_s: 3.67016665459 -} -adc_trajectory_point { - x: -125.287885624 - y: 361.227417206 - z: -31.3101102514 - - speed: 2.51666665077 - acceleration_s: 0.623986480013 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.630000114440918 - theta: -1.81963084477 - accumulated_s: 3.6953333210999997 -} -adc_trajectory_point { - x: -125.294263067 - y: 361.202915719 - z: -31.3101540385 - - speed: 2.52500009537 - acceleration_s: 0.470652419138 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.6400001049041748 - theta: -1.81968285302 - accumulated_s: 3.7205833220500004 -} -adc_trajectory_point { - x: -125.300668029 - y: 361.178341563 - z: -31.3101223055 - - speed: 2.52500009537 - acceleration_s: 0.557301339731 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.6500000953674316 - theta: -1.81976648752 - accumulated_s: 3.7458333230000003 -} -adc_trajectory_point { - x: -125.307057381 - y: 361.153720209 - z: -31.3102796115 - - speed: 2.53333330154 - acceleration_s: 0.59587861808 - curvature: -0.00110997184211 - curvature_change_rate: -0.00151086040199 - relative_time: 1.6600000858306885 - theta: -1.8197875326 - accumulated_s: 3.77116665602 -} -adc_trajectory_point { - x: -125.313499771 - y: 361.129059883 - z: -31.3102807552 - - speed: 2.53333330154 - acceleration_s: 0.506494375233 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.6700000762939453 - theta: -1.81985507388 - accumulated_s: 3.79649998904 -} -adc_trajectory_point { - x: -125.319920217 - y: 361.104345721 - z: -31.3101786645 - - speed: 2.544444561 - acceleration_s: 0.487412846952 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.6800000667572021 - theta: -1.81988979221 - accumulated_s: 3.8219444346499998 -} -adc_trajectory_point { - x: -125.326348711 - y: 361.079596709 - z: -31.3101000581 - - speed: 2.544444561 - acceleration_s: 0.396641112764 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.690000057220459 - theta: -1.81993184901 - accumulated_s: 3.8473888802599996 -} -adc_trajectory_point { - x: -125.326348711 - y: 361.079596709 - z: -31.3101000581 - - speed: 2.55555558205 - acceleration_s: 0.396641112764 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.690000057220459 - theta: -1.81993184901 - accumulated_s: 3.87294443608 -} -adc_trajectory_point { - x: -125.339222556 - y: 361.029976296 - z: -31.3100965517 - - speed: 2.55555558205 - acceleration_s: 0.497112877228 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.7100000381469727 - theta: -1.82006312201 - accumulated_s: 3.8984999918999996 -} -adc_trajectory_point { - x: -125.345661169 - y: 361.005068195 - z: -31.3100165213 - - speed: 2.56388878822 - acceleration_s: 0.542388897611 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.7200000286102295 - theta: -1.82006347002 - accumulated_s: 3.92413887978 -} -adc_trajectory_point { - x: -125.352128438 - y: 360.980115994 - z: -31.3098779172 - - speed: 2.56388878822 - acceleration_s: 0.546547177071 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.7300000190734863 - theta: -1.82010562887 - accumulated_s: 3.9497777676599997 -} -adc_trajectory_point { - x: -125.358609364 - y: 360.955101644 - z: -31.3097669361 - - speed: 2.57500004768 - acceleration_s: 0.633001016486 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.7400000095367432 - theta: -1.82010467581 - accumulated_s: 3.97552776814 -} -adc_trajectory_point { - x: -125.365083092 - y: 360.930060616 - z: -31.3096202817 - - speed: 2.57500004768 - acceleration_s: 0.633001016486 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.75 - theta: -1.82009665155 - accumulated_s: 4.00127776861 -} -adc_trajectory_point { - x: -125.371579562 - y: 360.904948257 - z: -31.3094767677 - - speed: 2.58888888359 - acceleration_s: 0.53525839062 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.7599999904632568 - theta: -1.82012311264 - accumulated_s: 4.02716665745 -} -adc_trajectory_point { - x: -125.378124914 - y: 360.879822808 - z: -31.3093882594 - - speed: 2.58888888359 - acceleration_s: 0.487854860158 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.7699999809265137 - theta: -1.82016109208 - accumulated_s: 4.05305554629 -} -adc_trajectory_point { - x: -125.384642207 - y: 360.854632133 - z: -31.3092705887 - - speed: 2.6027777195 - acceleration_s: 0.478420581517 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.7799999713897705 - theta: -1.82014668287 - accumulated_s: 4.07908332348 -} -adc_trajectory_point { - x: -125.39118994 - y: 360.829372517 - z: -31.3091875464 - - speed: 2.6027777195 - acceleration_s: 0.544181263352 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.7899999618530273 - theta: -1.82013984538 - accumulated_s: 4.10511110068 -} -adc_trajectory_point { - x: -125.39118994 - y: 360.829372517 - z: -31.3091875464 - - speed: 2.61111116409 - acceleration_s: 0.544181263352 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.7899999618530273 - theta: -1.82013984538 - accumulated_s: 4.13122221232 -} -adc_trajectory_point { - x: -125.404328653 - y: 360.77872648 - z: -31.3089771597 - - speed: 2.61111116409 - acceleration_s: 0.520326750882 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.809999942779541 - theta: -1.82020182981 - accumulated_s: 4.15733332396 -} -adc_trajectory_point { - x: -125.410949124 - y: 360.753315992 - z: -31.3088780753 - - speed: 2.61944437027 - acceleration_s: 0.612627571447 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.8199999332427979 - theta: -1.82026439025 - accumulated_s: 4.18352776766 -} -adc_trajectory_point { - x: -125.417554649 - y: 360.727867656 - z: -31.3087214185 - - speed: 2.61944437027 - acceleration_s: 0.50038368782 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.8300001621246338 - theta: -1.82032107677 - accumulated_s: 4.20972221136 -} -adc_trajectory_point { - x: -125.424145847 - y: 360.702354047 - z: -31.308650543 - - speed: 2.63055562973 - acceleration_s: 0.549022600728 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.8400001525878906 - theta: -1.82034991872 - accumulated_s: 4.2360277676599996 -} -adc_trajectory_point { - x: -125.430732575 - y: 360.676786033 - z: -31.3086042292 - - speed: 2.63055562973 - acceleration_s: 0.529990838085 - curvature: -0.00110997184211 - curvature_change_rate: 0 - relative_time: 1.8500001430511475 - theta: -1.82037338242 - accumulated_s: 4.26233332396 -} -adc_trajectory_point { - x: -125.437348416 - y: 360.651184848 - z: -31.3085189508 - - speed: 2.63888883591 - acceleration_s: 0.454595254832 - curvature: -0.0010716967124 - curvature_change_rate: 0.00145042599683 - relative_time: 1.8600001335144043 - theta: -1.82047284755 - accumulated_s: 4.28872221232 -} -adc_trajectory_point { - x: -125.44396724 - y: 360.625511185 - z: -31.3084344761 - - speed: 2.63888883591 - acceleration_s: 0.57201560229 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.8700001239776611 - theta: -1.82055572354 - accumulated_s: 4.31511110068 -} -adc_trajectory_point { - x: -125.450578473 - y: 360.599791754 - z: -31.3083229689 - - speed: 2.65000009537 - acceleration_s: 0.50042079149 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.880000114440918 - theta: -1.8206187713 - accumulated_s: 4.34161110163 -} -adc_trajectory_point { - x: -125.457161235 - y: 360.573994903 - z: -31.3082961971 - - speed: 2.65000009537 - acceleration_s: 0.608957670273 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.8900001049041748 - theta: -1.82066638752 - accumulated_s: 4.36811110258 -} -adc_trajectory_point { - x: -125.457161235 - y: 360.573994903 - z: -31.3082961971 - - speed: 2.65833330154 - acceleration_s: 0.608957670273 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.8900001049041748 - theta: -1.82066638752 - accumulated_s: 4.3946944356 -} -adc_trajectory_point { - x: -125.470402386 - y: 360.522259867 - z: -31.3082394749 - - speed: 2.65833330154 - acceleration_s: 0.544343023852 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.9100000858306885 - theta: -1.82083360771 - accumulated_s: 4.42127776861 -} -adc_trajectory_point { - x: -125.477007638 - y: 360.496297447 - z: -31.308145876 - - speed: 2.669444561 - acceleration_s: 0.556709860971 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.9200000762939453 - theta: -1.82089204632 - accumulated_s: 4.44797221422 -} -adc_trajectory_point { - x: -125.483641068 - y: 360.470300722 - z: -31.3080749176 - - speed: 2.669444561 - acceleration_s: 0.487942274116 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.9300000667572021 - theta: -1.82098793755 - accumulated_s: 4.47466665983 -} -adc_trajectory_point { - x: -125.490256914 - y: 360.444221465 - z: -31.3080387702 - - speed: 2.68055558205 - acceleration_s: 0.625656329633 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.940000057220459 - theta: -1.8210536898 - accumulated_s: 4.50147221566 -} -adc_trajectory_point { - x: -125.490256914 - y: 360.444221465 - z: -31.3080387702 - - speed: 2.68055558205 - acceleration_s: 0.625656329633 - curvature: -0.0010716967124 - curvature_change_rate: 0 - relative_time: 1.940000057220459 - theta: -1.8210536898 - accumulated_s: 4.52827777148 -} -adc_trajectory_point { - x: -125.503575954 - y: 360.391941462 - z: -31.3079471681 - - speed: 2.68888878822 - acceleration_s: 0.540887660129 - curvature: -0.00103342160821 - curvature_change_rate: 0.00142345434168 - relative_time: 1.9600000381469727 - theta: -1.82117825628 - accumulated_s: 4.55516665936 -} -adc_trajectory_point { - x: -125.510265055 - y: 360.365728364 - z: -31.3078916818 - - speed: 2.68888878822 - acceleration_s: 0.521835524634 - curvature: -0.00103342160821 - curvature_change_rate: 0 - relative_time: 1.9700000286102295 - theta: -1.82125000892 - accumulated_s: 4.58205554724 -} -adc_trajectory_point { - x: -125.516998125 - y: 360.339492042 - z: -31.3078431217 - - speed: 2.70000004768 - acceleration_s: 0.444248635123 - curvature: -0.0009951465286 - curvature_change_rate: 0.00141759551589 - relative_time: 1.9800000190734863 - theta: -1.82132353561 - accumulated_s: 4.60905554772 -} -adc_trajectory_point { - x: -125.523724383 - y: 360.313171053 - z: -31.3077099975 - - speed: 2.70000004768 - acceleration_s: 0.566921838707 - curvature: -0.0009951465286 - curvature_change_rate: 0 - relative_time: 1.9900000095367432 - theta: -1.82134145734 - accumulated_s: 4.63605554819 -} -adc_trajectory_point { - x: -125.530534332 - y: 360.286794019 - z: -31.3076497242 - - speed: 2.71111106873 - acceleration_s: 0.566921838707 - curvature: -0.000956871472678 - curvature_change_rate: 0.00141178487166 - relative_time: 2 - theta: -1.82141192096 - accumulated_s: 4.66316665888 -} -adc_trajectory_point { - x: -125.537331069 - y: 360.260350394 - z: -31.3075449867 - - speed: 2.71111106873 - acceleration_s: 0.676986950806 - curvature: -0.000956871472678 - curvature_change_rate: 0 - relative_time: 2.0099999904632568 - theta: -1.82141578788 - accumulated_s: 4.69027776957 -} -adc_trajectory_point { - x: -125.544198795 - y: 360.233849652 - z: -31.3075140547 - - speed: 2.7277777195 - acceleration_s: 0.754657111552 - curvature: -0.000956871472678 - curvature_change_rate: 0 - relative_time: 2.0199999809265137 - theta: -1.82147078752 - accumulated_s: 4.71755554676 -} -adc_trajectory_point { - x: -125.551075619 - y: 360.207305452 - z: -31.3074306911 - - speed: 2.7277777195 - acceleration_s: 0.599208098093 - curvature: -0.000956871472678 - curvature_change_rate: 0 - relative_time: 2.0299999713897705 - theta: -1.82148683338 - accumulated_s: 4.74483332396 -} -adc_trajectory_point { - x: -125.557972773 - y: 360.180711174 - z: -31.3073444497 - - speed: 2.74444437027 - acceleration_s: 0.527593004511 - curvature: -0.000956871472678 - curvature_change_rate: 0 - relative_time: 2.0399999618530273 - theta: -1.82152201956 - accumulated_s: 4.77227776766 -} -adc_trajectory_point { - x: -125.564913014 - y: 360.154044359 - z: -31.3072374249 - - speed: 2.74444437027 - acceleration_s: 0.527593004511 - curvature: -0.000956871472678 - curvature_change_rate: 0 - relative_time: 2.0499999523162842 - theta: -1.82154290335 - accumulated_s: 4.79972221136 -} -adc_trajectory_point { - x: -125.571844636 - y: 360.12733583 - z: -31.3071987871 - - speed: 2.75555562973 - acceleration_s: 0.551526740126 - curvature: -0.000956871472678 - curvature_change_rate: 0 - relative_time: 2.059999942779541 - theta: -1.8215456165 - accumulated_s: 4.82727776766 -} -adc_trajectory_point { - x: -125.578797905 - y: 360.100558146 - z: -31.3072172794 - - speed: 2.75555562973 - acceleration_s: 0.629940975765 - curvature: -0.000956871472678 - curvature_change_rate: 0 - relative_time: 2.0699999332427979 - theta: -1.8215810715 - accumulated_s: 4.85483332396 -} -adc_trajectory_point { - x: -125.585730295 - y: 360.073723491 - z: -31.3071709732 - - speed: 2.76111102104 - acceleration_s: 0.573687721139 - curvature: -0.000918596439528 - curvature_change_rate: 0.00138621854965 - relative_time: 2.0800001621246338 - theta: -1.82154201657 - accumulated_s: 4.88244443417 -} -adc_trajectory_point { - x: -125.592715537 - y: 360.046865102 - z: -31.3070287984 - - speed: 2.76111102104 - acceleration_s: 0.397963546236 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.0900001525878906 - theta: -1.8215838674 - accumulated_s: 4.91005554438 -} -adc_trajectory_point { - x: -125.592715537 - y: 360.046865102 - z: -31.3070287984 - - speed: 2.76944446564 - acceleration_s: 0.397963546236 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.0900001525878906 - theta: -1.8215838674 - accumulated_s: 4.93774998904 -} -adc_trajectory_point { - x: -125.606705452 - y: 359.992944077 - z: -31.3069257466 - - speed: 2.76944446564 - acceleration_s: 0.605243806601 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.1100001335144043 - theta: -1.82160243601 - accumulated_s: 4.96544443369 -} -adc_trajectory_point { - x: -125.613715656 - y: 359.965900791 - z: -31.3069158401 - - speed: 2.77777767181 - acceleration_s: 0.587333040131 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.1200001239776611 - theta: -1.82163078158 - accumulated_s: 4.99322221041 -} -adc_trajectory_point { - x: -125.620781546 - y: 359.938791968 - z: -31.3069237191 - - speed: 2.77777767181 - acceleration_s: 0.727187893866 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.130000114440918 - theta: -1.82167773656 - accumulated_s: 5.02099998713 -} -adc_trajectory_point { - x: -125.627850631 - y: 359.911634144 - z: -31.306826652 - - speed: 2.79166674614 - acceleration_s: 0.549840667398 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.1400001049041748 - theta: -1.82168810328 - accumulated_s: 5.04891665459 -} -adc_trajectory_point { - x: -125.634956433 - y: 359.884418464 - z: -31.3067896031 - - speed: 2.79166674614 - acceleration_s: 0.549840667398 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.1500000953674316 - theta: -1.82171289445 - accumulated_s: 5.07683332205 -} -adc_trajectory_point { - x: -125.642046141 - y: 359.857149366 - z: -31.3068400882 - - speed: 2.80555558205 - acceleration_s: 0.542085416321 - curvature: -0.000880321428239 - curvature_change_rate: 0.00136425781524 - relative_time: 2.1600000858306885 - theta: -1.8216935938 - accumulated_s: 5.10488887787 -} -adc_trajectory_point { - x: -125.649150332 - y: 359.829835747 - z: -31.3069122797 - - speed: 2.80555558205 - acceleration_s: 0.477439146887 - curvature: -0.000880321428239 - curvature_change_rate: 0 - relative_time: 2.1700000762939453 - theta: -1.82170121117 - accumulated_s: 5.13294443369 -} -adc_trajectory_point { - x: -125.656310653 - y: 359.802464583 - z: -31.3069347879 - - speed: 2.81944441795 - acceleration_s: 0.573332582413 - curvature: -0.0008420464379 - curvature_change_rate: 0.0013575366159 - relative_time: 2.1800000667572021 - theta: -1.82174094854 - accumulated_s: 5.16113887787 -} -adc_trajectory_point { - x: -125.6634802 - y: 359.775052215 - z: -31.306938665 - - speed: 2.81944441795 - acceleration_s: 0.480953550981 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 2.190000057220459 - theta: -1.82174518821 - accumulated_s: 5.18933332205 -} -adc_trajectory_point { - x: -125.6634802 - y: 359.775052215 - z: -31.306938665 - - speed: 2.82777786255 - acceleration_s: 0.480953550981 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 2.190000057220459 - theta: -1.82174518821 - accumulated_s: 5.21761110068 -} -adc_trajectory_point { - x: -125.677938723 - y: 359.720041327 - z: -31.3069625562 - - speed: 2.82777786255 - acceleration_s: 0.601637167889 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 2.2100000381469727 - theta: -1.82184178694 - accumulated_s: 5.2458888793 -} -adc_trajectory_point { - x: -125.685189377 - y: 359.692458234 - z: -31.306962071 - - speed: 2.83888888359 - acceleration_s: 0.55047200077 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 2.2200000286102295 - theta: -1.82188540617 - accumulated_s: 5.27427776814 -} -adc_trajectory_point { - x: -125.692474208 - y: 359.664814508 - z: -31.3069400685 - - speed: 2.83888888359 - acceleration_s: 0.60241470639 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 2.2300000190734863 - theta: -1.82190412116 - accumulated_s: 5.30266665697 -} -adc_trajectory_point { - x: -125.699781684 - y: 359.637138023 - z: -31.3068766557 - - speed: 2.8527777195 - acceleration_s: 0.49892409539 - curvature: -0.000803771467601 - curvature_change_rate: 0.00134167376721 - relative_time: 2.2400000095367432 - theta: -1.82193041081 - accumulated_s: 5.33119443417 -} -adc_trajectory_point { - x: -125.699781684 - y: 359.637138023 - z: -31.3068766557 - - speed: 2.8527777195 - acceleration_s: 0.49892409539 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.2400000095367432 - theta: -1.82193041081 - accumulated_s: 5.35972221136 -} -adc_trajectory_point { - x: -125.714498953 - y: 359.581639177 - z: -31.3068493977 - - speed: 2.8666665554 - acceleration_s: 0.529323722547 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.2599999904632568 - theta: -1.82201650974 - accumulated_s: 5.38838887692 -} -adc_trajectory_point { - x: -125.721916183 - y: 359.553844569 - z: -31.3067936711 - - speed: 2.8666665554 - acceleration_s: 0.424356121029 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.2699999809265137 - theta: -1.82212695848 - accumulated_s: 5.41705554247 -} -adc_trajectory_point { - x: -125.729314593 - y: 359.525979479 - z: -31.3067365438 - - speed: 2.87777781487 - acceleration_s: 0.517916540761 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.2799999713897705 - theta: -1.82216632841 - accumulated_s: 5.44583332062 -} -adc_trajectory_point { - x: -125.736735465 - y: 359.498089687 - z: -31.3066623844 - - speed: 2.87777781487 - acceleration_s: 0.393867359235 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.2899999618530273 - theta: -1.82219917945 - accumulated_s: 5.47461109877 -} -adc_trajectory_point { - x: -125.744185916 - y: 359.470141154 - z: -31.3065668559 - - speed: 2.88611102104 - acceleration_s: 0.393867359235 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.2999999523162842 - theta: -1.82227869211 - accumulated_s: 5.50347220898 -} -adc_trajectory_point { - x: -125.751645886 - y: 359.442144392 - z: -31.3064575428 - - speed: 2.88611102104 - acceleration_s: 0.498139004173 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.309999942779541 - theta: -1.82232656535 - accumulated_s: 5.53233331919 -} -adc_trajectory_point { - x: -125.759104292 - y: 359.414105887 - z: -31.3063270031 - - speed: 2.89444446564 - acceleration_s: 0.471227514218 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.3199999332427979 - theta: -1.82237573828 - accumulated_s: 5.56127776385 -} -adc_trajectory_point { - x: -125.766606147 - y: 359.386024285 - z: -31.3062000703 - - speed: 2.89444446564 - acceleration_s: 0.525454236397 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.3300001621246338 - theta: -1.82246275229 - accumulated_s: 5.5902222085 -} -adc_trajectory_point { - x: -125.774096612 - y: 359.357892469 - z: -31.306101134 - - speed: 2.90555548668 - acceleration_s: 0.477311863712 - curvature: -0.00076549651643 - curvature_change_rate: 0.00131730236598 - relative_time: 2.3400001525878906 - theta: -1.82250837147 - accumulated_s: 5.61927776337 -} -adc_trajectory_point { - x: -125.781569154 - y: 359.329721161 - z: -31.3060243241 - - speed: 2.90555548668 - acceleration_s: 0.477311863712 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.3500001430511475 - theta: -1.82254222458 - accumulated_s: 5.64833331824 -} -adc_trajectory_point { - x: -125.789073629 - y: 359.301495396 - z: -31.3059554296 - - speed: 2.91388893127 - acceleration_s: 0.487612504816 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.3600001335144043 - theta: -1.82258890477 - accumulated_s: 5.67747220755 -} -adc_trajectory_point { - x: -125.79657766 - y: 359.273239694 - z: -31.3059446588 - - speed: 2.91388893127 - acceleration_s: 0.408425345148 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.3700001239776611 - theta: -1.82264715603 - accumulated_s: 5.70661109686 -} -adc_trajectory_point { - x: -125.804100799 - y: 359.244941955 - z: -31.3059203699 - - speed: 2.92222213745 - acceleration_s: 0.431552034778 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.380000114440918 - theta: -1.82272320719 - accumulated_s: 5.73583331824 -} -adc_trajectory_point { - x: -125.811639623 - y: 359.216596273 - z: -31.3058855822 - - speed: 2.92222213745 - acceleration_s: 0.414205557226 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.3900001049041748 - theta: -1.82277593601 - accumulated_s: 5.76505553961 -} -adc_trajectory_point { - x: -125.811639623 - y: 359.216596273 - z: -31.3058855822 - - speed: 2.93055558205 - acceleration_s: 0.414205557226 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.3900001049041748 - theta: -1.82277593601 - accumulated_s: 5.79436109543 -} -adc_trajectory_point { - x: -125.826727703 - y: 359.159788805 - z: -31.3060976537 - - speed: 2.93055558205 - acceleration_s: 0.41204758658 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.4100000858306885 - theta: -1.82286203351 - accumulated_s: 5.82366665125 -} -adc_trajectory_point { - x: -125.834298586 - y: 359.131348113 - z: -31.3061702913 - - speed: 2.94166660309 - acceleration_s: 0.29872526349 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.4200000762939453 - theta: -1.82291701216 - accumulated_s: 5.85308331728 -} -adc_trajectory_point { - x: -125.841885547 - y: 359.102839577 - z: -31.3061969932 - - speed: 2.94166660309 - acceleration_s: 0.444027572803 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.4300000667572021 - theta: -1.82294408081 - accumulated_s: 5.88249998331 -} -adc_trajectory_point { - x: -125.849468747 - y: 359.074320163 - z: -31.3063632268 - - speed: 2.95000004768 - acceleration_s: 0.30117113011 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.440000057220459 - theta: -1.82294981809 - accumulated_s: 5.91199998379 -} -adc_trajectory_point { - x: -125.849468747 - y: 359.074320163 - z: -31.3063632268 - - speed: 2.95000004768 - acceleration_s: 0.30117113011 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.440000057220459 - theta: -1.82294981809 - accumulated_s: 5.94149998427 -} -adc_trajectory_point { - x: -125.86470335 - y: 359.017140009 - z: -31.3069306035 - - speed: 2.95833325386 - acceleration_s: 0.367564584601 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.4600000381469727 - theta: -1.82300808145 - accumulated_s: 5.97108331681 -} -adc_trajectory_point { - x: -125.872341557 - y: 358.988489067 - z: -31.307096309 - - speed: 2.95833325386 - acceleration_s: 0.360293941012 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.4700000286102295 - theta: -1.82302397094 - accumulated_s: 6.00066664934 -} -adc_trajectory_point { - x: -125.880037888 - y: 358.959804402 - z: -31.3073657053 - - speed: 2.96944451332 - acceleration_s: 0.460884138127 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.4800000190734863 - theta: -1.82306031579 - accumulated_s: 6.03036109448 -} -adc_trajectory_point { - x: -125.887745816 - y: 358.931108792 - z: -31.3077072827 - - speed: 2.96944451332 - acceleration_s: 0.321661981102 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.4900000095367432 - theta: -1.8230438854 - accumulated_s: 6.06005553961 -} -adc_trajectory_point { - x: -125.895517405 - y: 358.902351345 - z: -31.3080882411 - - speed: 2.98055553436 - acceleration_s: 0.321661981102 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.5 - theta: -1.82307959727 - accumulated_s: 6.08986109495 -} -adc_trajectory_point { - x: -125.903316693 - y: 358.873560525 - z: -31.3085163888 - - speed: 2.98055553436 - acceleration_s: 0.464730193548 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.5099999904632568 - theta: -1.82307001711 - accumulated_s: 6.1196666503 -} -adc_trajectory_point { - x: -125.911163585 - y: 358.844739997 - z: -31.3088300247 - - speed: 2.99444437027 - acceleration_s: 0.383093978266 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.5199999809265137 - theta: -1.82308327876 - accumulated_s: 6.149611094 -} -adc_trajectory_point { - x: -125.919032533 - y: 358.815868283 - z: -31.3091887236 - - speed: 2.99444437027 - acceleration_s: 0.491155818915 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.5299999713897705 - theta: -1.82308549865 - accumulated_s: 6.1795555377 -} -adc_trajectory_point { - x: -125.926896637 - y: 358.786987422 - z: -31.3095703563 - - speed: 3.0083334446 - acceleration_s: 0.303688481265 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.5399999618530273 - theta: -1.82305372126 - accumulated_s: 6.20963887215 -} -adc_trajectory_point { - x: -125.934788487 - y: 358.75803987 - z: -31.309997268 - - speed: 3.0083334446 - acceleration_s: 0.470811416377 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.5499999523162842 - theta: -1.82305385113 - accumulated_s: 6.2397222066 -} -adc_trajectory_point { - x: -125.942672155 - y: 358.72905105 - z: -31.3104813183 - - speed: 3.0083334446 - acceleration_s: 0.496127967555 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.559999942779541 - theta: -1.82307027028 - accumulated_s: 6.26980554104 -} -adc_trajectory_point { - x: -125.950557125 - y: 358.70001789 - z: -31.3108385755 - - speed: 3.0222222805 - acceleration_s: 0.459179381124 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.5699999332427979 - theta: -1.82309299541 - accumulated_s: 6.30002776385 -} -adc_trajectory_point { - x: -125.958427402 - y: 358.670924304 - z: -31.3112333706 - - speed: 3.0222222805 - acceleration_s: 0.459677400509 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.5800001621246338 - theta: -1.82311852637 - accumulated_s: 6.33024998665 -} -adc_trajectory_point { - x: -125.966273613 - y: 358.641808143 - z: -31.3115684483 - - speed: 3.03333330154 - acceleration_s: 0.459677400509 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.5900001525878906 - theta: -1.8231428439 - accumulated_s: 6.36058331967 -} -adc_trajectory_point { - x: -125.974084814 - y: 358.612648583 - z: -31.312040519 - - speed: 3.03333330154 - acceleration_s: 0.319544190721 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.6000001430511475 - theta: -1.82318429305 - accumulated_s: 6.39091665268 -} -adc_trajectory_point { - x: -125.981874503 - y: 358.583403985 - z: -31.3123099208 - - speed: 3.044444561 - acceleration_s: 0.499313586165 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 2.6100001335144043 - theta: -1.82320408035 - accumulated_s: 6.42136109829 -} -adc_trajectory_point { - x: -125.989619091 - y: 358.554155402 - z: -31.3126276666 - - speed: 3.04999995232 - acceleration_s: 0.320399732615 - curvature: -0.000803771467601 - curvature_change_rate: -0.00125491645145 - relative_time: 2.6200001239776611 - theta: -1.82323937864 - accumulated_s: 6.45186109782 -} -adc_trajectory_point { - x: -125.997444216 - y: 358.524857352 - z: -31.3129913248 - - speed: 3.04999995232 - acceleration_s: 0.469653036493 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.630000114440918 - theta: -1.82335120105 - accumulated_s: 6.48236109734 -} -adc_trajectory_point { - x: -126.005200698 - y: 358.495540045 - z: -31.3134962507 - - speed: 3.05833339691 - acceleration_s: 0.311313962184 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.6400001049041748 - theta: -1.8233994009 - accumulated_s: 6.51294443131 -} -adc_trajectory_point { - x: -126.012948537 - y: 358.466132741 - z: -31.3138230573 - - speed: 3.05833339691 - acceleration_s: 0.454018653915 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.6500000953674316 - theta: -1.82343280294 - accumulated_s: 6.54352776528 -} -adc_trajectory_point { - x: -126.020727633 - y: 358.436689224 - z: -31.3139888011 - - speed: 3.06388878822 - acceleration_s: 0.443531903069 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.6600000858306885 - theta: -1.82345385402 - accumulated_s: 6.5741666531600007 -} -adc_trajectory_point { - x: -126.028530638 - y: 358.407219537 - z: -31.3142265771 - - speed: 3.06388878822 - acceleration_s: 0.413639588279 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.6700000762939453 - theta: -1.82349320987 - accumulated_s: 6.6048055410399993 -} -adc_trajectory_point { - x: -126.036354345 - y: 358.37772713 - z: -31.3146840679 - - speed: 3.06944441795 - acceleration_s: 0.413639588279 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.6800000667572021 - theta: -1.82359408573 - accumulated_s: 6.6354999852199992 -} -adc_trajectory_point { - x: -126.044157398 - y: 358.348197709 - z: -31.3150890348 - - speed: 3.06944441795 - acceleration_s: 0.326254765876 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.690000057220459 - theta: -1.82364311569 - accumulated_s: 6.6661944294000008 -} -adc_trajectory_point { - x: -126.044157398 - y: 358.348197709 - z: -31.3150890348 - - speed: 3.07500004768 - acceleration_s: 0.326254765876 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.690000057220459 - theta: -1.82364311569 - accumulated_s: 6.69694442988 -} -adc_trajectory_point { - x: -126.059855718 - y: 358.288982885 - z: -31.3155618459 - - speed: 3.07500004768 - acceleration_s: 0.46523362929 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 2.7100000381469727 - theta: -1.8237598578 - accumulated_s: 6.7276944303500006 -} -adc_trajectory_point { - x: -126.067677572 - y: 358.259321449 - z: -31.3159407303 - - speed: 3.08333325386 - acceleration_s: 0.506723991784 - curvature: -0.0008420464379 - curvature_change_rate: -0.00124135042008 - relative_time: 2.7200000286102295 - theta: -1.82377316375 - accumulated_s: 6.7585277628899991 -} -adc_trajectory_point { - x: -126.075541854 - y: 358.229580921 - z: -31.3163395924 - - speed: 3.08333325386 - acceleration_s: 0.563808783768 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 2.7300000190734863 - theta: -1.82382011107 - accumulated_s: 6.7893610954299994 -} -adc_trajectory_point { - x: -126.083392099 - y: 358.199824766 - z: -31.316745366 - - speed: 3.09166669846 - acceleration_s: 0.425152358643 - curvature: -0.000880321428239 - curvature_change_rate: -0.00123800506561 - relative_time: 2.7400000095367432 - theta: -1.82384748254 - accumulated_s: 6.82027776242 -} -adc_trajectory_point { - x: -126.091296726 - y: 358.169999322 - z: -31.3170797275 - - speed: 3.09166669846 - acceleration_s: 0.529039050034 - curvature: -0.000880321428239 - curvature_change_rate: 0 - relative_time: 2.75 - theta: -1.82392769881 - accumulated_s: 6.8511944294 -} -adc_trajectory_point { - x: -126.091296726 - y: 358.169999322 - z: -31.3170797275 - - speed: 3.09722232819 - acceleration_s: 0.529039050034 - curvature: -0.000880321428239 - curvature_change_rate: 0 - relative_time: 2.75 - theta: -1.82392769881 - accumulated_s: 6.8821666526800005 -} -adc_trajectory_point { - x: -126.107108815 - y: 358.110277742 - z: -31.3177725319 - - speed: 3.09722232819 - acceleration_s: 0.382627782371 - curvature: -0.000880321428239 - curvature_change_rate: 0 - relative_time: 2.7699999809265137 - theta: -1.82402766554 - accumulated_s: 6.91313887596 -} -adc_trajectory_point { - x: -126.1150425 - y: 358.080346963 - z: -31.3182779802 - - speed: 3.10555553436 - acceleration_s: 0.497540593076 - curvature: -0.000918596439528 - curvature_change_rate: -0.00123246906601 - relative_time: 2.7799999713897705 - theta: -1.82407606579 - accumulated_s: 6.9441944313100006 -} -adc_trajectory_point { - x: -126.122980671 - y: 358.050388892 - z: -31.3186851079 - - speed: 3.10555553436 - acceleration_s: 0.374230324395 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.7899999618530273 - theta: -1.8241204982 - accumulated_s: 6.9752499866500006 -} -adc_trajectory_point { - x: -126.130936993 - y: 358.020345633 - z: -31.3191264886 - - speed: 3.11388897896 - acceleration_s: 0.580999622577 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.7999999523162842 - theta: -1.82416021751 - accumulated_s: 7.0063888764400009 -} -adc_trajectory_point { - x: -126.138945684 - y: 357.990276143 - z: -31.3196149571 - - speed: 3.11388897896 - acceleration_s: 0.571256202308 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.809999942779541 - theta: -1.82425172481 - accumulated_s: 7.0375277662299993 -} -adc_trajectory_point { - x: -126.146892291 - y: 357.960134232 - z: -31.3200618271 - - speed: 3.125 - acceleration_s: 0.520164619607 - curvature: -0.000956871472678 - curvature_change_rate: -0.0012248010608 - relative_time: 2.8199999332427979 - theta: -1.82425692775 - accumulated_s: 7.0687777662299993 -} -adc_trajectory_point { - x: -126.154869846 - y: 357.929954192 - z: -31.3205484115 - - speed: 3.125 - acceleration_s: 0.501316150934 - curvature: -0.000956871472678 - curvature_change_rate: 0 - relative_time: 2.8300001621246338 - theta: -1.8243241516 - accumulated_s: 7.1000277662299993 -} -adc_trajectory_point { - x: -126.162832424 - y: 357.899732542 - z: -31.3210640308 - - speed: 3.13611102104 - acceleration_s: 0.383059567577 - curvature: -0.000956871472678 - curvature_change_rate: 0 - relative_time: 2.8400001525878906 - theta: -1.82436401959 - accumulated_s: 7.1313888764400009 -} -adc_trajectory_point { - x: -126.170812033 - y: 357.869454264 - z: -31.321619818 - - speed: 3.13611102104 - acceleration_s: 0.383059567577 - curvature: -0.000956871472678 - curvature_change_rate: 0 - relative_time: 2.8500001430511475 - theta: -1.8244479462 - accumulated_s: 7.1627499866500006 -} -adc_trajectory_point { - x: -126.178766382 - y: 357.839126963 - z: -31.3222097838 - - speed: 3.1472222805 - acceleration_s: 0.464772359593 - curvature: -0.000956871472678 - curvature_change_rate: 0 - relative_time: 2.8600001335144043 - theta: -1.82447236367 - accumulated_s: 7.1942222094599995 -} -adc_trajectory_point { - x: -126.186743378 - y: 357.808752627 - z: -31.3226710502 - - speed: 3.1472222805 - acceleration_s: 0.457433710587 - curvature: -0.000956871472678 - curvature_change_rate: 0 - relative_time: 2.8700001239776611 - theta: -1.82454997751 - accumulated_s: 7.2256944322599992 -} -adc_trajectory_point { - x: -126.194704008 - y: 357.778319877 - z: -31.3232655963 - - speed: 3.15555548668 - acceleration_s: 0.522979453222 - curvature: -0.000956871472678 - curvature_change_rate: 0 - relative_time: 2.880000114440918 - theta: -1.82459108363 - accumulated_s: 7.2572499871300007 -} -adc_trajectory_point { - x: -126.202693428 - y: 357.747852806 - z: -31.3239080766 - - speed: 3.15555548668 - acceleration_s: 0.455380615626 - curvature: -0.000956871472678 - curvature_change_rate: 0 - relative_time: 2.8900001049041748 - theta: -1.82464949137 - accumulated_s: 7.2888055419899995 -} -adc_trajectory_point { - x: -126.210694911 - y: 357.717305728 - z: -31.3244874831 - - speed: 3.16388893127 - acceleration_s: 0.455380615626 - curvature: -0.000918596439528 - curvature_change_rate: 0.00120974642225 - relative_time: 2.9000000953674316 - theta: -1.82470858106 - accumulated_s: 7.3204444313099994 -} -adc_trajectory_point { - x: -126.218712949 - y: 357.686723792 - z: -31.3250816101 - - speed: 3.16388893127 - acceleration_s: 0.503037514005 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.9100000858306885 - theta: -1.82474317059 - accumulated_s: 7.35208332062 -} -adc_trajectory_point { - x: -126.226761876 - y: 357.656090805 - z: -31.3256956702 - - speed: 3.17777776718 - acceleration_s: 0.534048393007 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.9200000762939453 - theta: -1.82479909581 - accumulated_s: 7.38386109829 -} -adc_trajectory_point { - x: -126.234841061 - y: 357.625433481 - z: -31.3264127029 - - speed: 3.17777776718 - acceleration_s: 0.509043883341 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.9300000667572021 - theta: -1.82488274067 - accumulated_s: 7.4156388759599992 -} -adc_trajectory_point { - x: -126.242926637 - y: 357.594723481 - z: -31.3271339554 - - speed: 3.19166660309 - acceleration_s: 0.453107629423 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.940000057220459 - theta: -1.82492478946 - accumulated_s: 7.4475555419900008 -} -adc_trajectory_point { - x: -126.242926637 - y: 357.594723481 - z: -31.3271339554 - - speed: 3.19166660309 - acceleration_s: 0.453107629423 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.940000057220459 - theta: -1.82492478946 - accumulated_s: 7.47947220803 -} -adc_trajectory_point { - x: -126.259181833 - y: 357.533099366 - z: -31.328906294 - - speed: 3.19722223282 - acceleration_s: 0.614675811852 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.9600000381469727 - theta: -1.82505297325 - accumulated_s: 7.51144443035 -} -adc_trajectory_point { - x: -126.267313914 - y: 357.502148787 - z: -31.3298393926 - - speed: 3.19722223282 - acceleration_s: 0.796355408066 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.9700000286102295 - theta: -1.8251012432 - accumulated_s: 7.5434166526799995 -} -adc_trajectory_point { - x: -126.275508208 - y: 357.471180796 - z: -31.3308216175 - - speed: 3.205555439 - acceleration_s: 0.629462267384 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.9800000190734863 - theta: -1.82522005594 - accumulated_s: 7.57547220707 -} -adc_trajectory_point { - x: -126.283680829 - y: 357.440122586 - z: -31.3317320691 - - speed: 3.205555439 - acceleration_s: 0.621641273573 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 2.9900000095367432 - theta: -1.82528217867 - accumulated_s: 7.60752776146 -} -adc_trajectory_point { - x: -126.291893912 - y: 357.4090488 - z: -31.3326069424 - - speed: 3.21388888359 - acceleration_s: 0.621641273573 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 3 - theta: -1.82537641226 - accumulated_s: 7.6396666503000006 -} -adc_trajectory_point { - x: -126.300109163 - y: 357.377939678 - z: -31.3334607286 - - speed: 3.21388888359 - acceleration_s: 0.352646051338 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 3.0099999904632568 - theta: -1.82543024597 - accumulated_s: 7.67180553913 -} -adc_trajectory_point { - x: -126.308303954 - y: 357.346792906 - z: -31.3343978049 - - speed: 3.2277777195 - acceleration_s: 0.362813741162 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 3.0199999809265137 - theta: -1.82544284689 - accumulated_s: 7.7040833163299993 -} -adc_trajectory_point { - x: -126.316550762 - y: 357.315653427 - z: -31.335456715 - - speed: 3.2277777195 - acceleration_s: 0.232629772995 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 3.0299999713897705 - theta: -1.82552119025 - accumulated_s: 7.7363610935199993 -} -adc_trajectory_point { - x: -126.324832741 - y: 357.284433166 - z: -31.3363997387 - - speed: 3.2277777195 - acceleration_s: 0.232629772995 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 3.0399999618530273 - theta: -1.82564221475 - accumulated_s: 7.76863887072 -} -adc_trajectory_point { - x: -126.333088492 - y: 357.253151252 - z: -31.337216489 - - speed: 3.23888897896 - acceleration_s: 0.546959754019 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 3.0499999523162842 - theta: -1.82569642273 - accumulated_s: 7.8010277605099994 -} -adc_trajectory_point { - x: -126.341357353 - y: 357.221766901 - z: -31.3379224408 - - speed: 3.25 - acceleration_s: 0.763328602658 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 3.059999942779541 - theta: -1.82571571216 - accumulated_s: 7.83352776051 -} -adc_trajectory_point { - x: -126.349677904 - y: 357.190412597 - z: -31.3388488209 - - speed: 3.25 - acceleration_s: 0.492292654727 - curvature: -0.000918596439528 - curvature_change_rate: 0 - relative_time: 3.0699999332427979 - theta: -1.82583419304 - accumulated_s: 7.8660277605100006 -} -adc_trajectory_point { - x: -126.357958179 - y: 357.158974798 - z: -31.3395972587 - - speed: 3.26111102104 - acceleration_s: 0.464564854836 - curvature: -0.000880321428239 - curvature_change_rate: 0.00117368010601 - relative_time: 3.0800001621246338 - theta: -1.8258701716 - accumulated_s: 7.8986388707199993 -} -adc_trajectory_point { - x: -126.36625774 - y: 357.127544982 - z: -31.3403570335 - - speed: 3.26111102104 - acceleration_s: 0.296031596052 - curvature: -0.000880321428239 - curvature_change_rate: 0 - relative_time: 3.0900001525878906 - theta: -1.82594556362 - accumulated_s: 7.93124998093 -} -adc_trajectory_point { - x: -126.36625774 - y: 357.127544982 - z: -31.3403570335 - - speed: 3.26944446564 - acceleration_s: 0.296031596052 - curvature: -0.000880321428239 - curvature_change_rate: 0 - relative_time: 3.0900001525878906 - theta: -1.82594556362 - accumulated_s: 7.96394442559 -} -adc_trajectory_point { - x: -126.382883895 - y: 357.064596002 - z: -31.3415422123 - - speed: 3.26944446564 - acceleration_s: 0.290829079588 - curvature: -0.000880321428239 - curvature_change_rate: 0 - relative_time: 3.1100001335144043 - theta: -1.82601293343 - accumulated_s: 7.99663887024 -} -adc_trajectory_point { - x: -126.391256508 - y: 357.033119968 - z: -31.3421462085 - - speed: 3.27777767181 - acceleration_s: 0.128096931288 - curvature: -0.000880321428239 - curvature_change_rate: 0 - relative_time: 3.1200001239776611 - theta: -1.8261001025 - accumulated_s: 8.02941664696 -} -adc_trajectory_point { - x: -126.39960812 - y: 357.001552905 - z: -31.3426318364 - - speed: 3.27777767181 - acceleration_s: 0.4808557379 - curvature: -0.000880321428239 - curvature_change_rate: 0 - relative_time: 3.130000114440918 - theta: -1.82611571164 - accumulated_s: 8.06219442368 -} -adc_trajectory_point { - x: -126.407998766 - y: 356.970002409 - z: -31.3430617405 - - speed: 3.28888893127 - acceleration_s: 0.286767132188 - curvature: -0.0008420464379 - curvature_change_rate: 0.00116376658314 - relative_time: 3.1400001049041748 - theta: -1.82614509679 - accumulated_s: 8.09508331299 -} -adc_trajectory_point { - x: -126.416460821 - y: 356.938375203 - z: -31.3433212331 - - speed: 3.28888893127 - acceleration_s: 0.286767132188 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.1500000953674316 - theta: -1.82619763602 - accumulated_s: 8.1279722023 -} -adc_trajectory_point { - x: -126.424894005 - y: 356.906737938 - z: -31.3437340027 - - speed: 3.29999995232 - acceleration_s: 0.428438433349 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.1600000858306885 - theta: -1.8261957026 - accumulated_s: 8.16097220183 -} -adc_trajectory_point { - x: -126.433370464 - y: 356.875058806 - z: -31.3439121805 - - speed: 3.29999995232 - acceleration_s: 0.36476578847 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.1700000762939453 - theta: -1.82619254194 - accumulated_s: 8.19397220135 -} -adc_trajectory_point { - x: -126.441893076 - y: 356.843338796 - z: -31.3441874972 - - speed: 3.30833339691 - acceleration_s: 0.5167637741 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.1800000667572021 - theta: -1.82622539305 - accumulated_s: 8.22705553532 -} -adc_trajectory_point { - x: -126.450440938 - y: 356.811614783 - z: -31.3443374243 - - speed: 3.30833339691 - acceleration_s: 0.301862609745 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.190000057220459 - theta: -1.82626537346 - accumulated_s: 8.26013886929 -} -adc_trajectory_point { - x: -126.450440938 - y: 356.811614783 - z: -31.3443374243 - - speed: 3.31666660309 - acceleration_s: 0.301862609745 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.190000057220459 - theta: -1.82626537346 - accumulated_s: 8.29330553532 -} -adc_trajectory_point { - x: -126.467585246 - y: 356.748054621 - z: -31.3445607657 - - speed: 3.31666660309 - acceleration_s: 0.239822784622 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.2100000381469727 - theta: -1.82633228994 - accumulated_s: 8.32647220135 -} -adc_trajectory_point { - x: -126.476163793 - y: 356.716236298 - z: -31.3445254369 - - speed: 3.32500004768 - acceleration_s: 0.267242042689 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.2200000286102295 - theta: -1.82634928064 - accumulated_s: 8.35972220183 -} -adc_trajectory_point { - x: -126.484763992 - y: 356.684400349 - z: -31.3445740202 - - speed: 3.32500004768 - acceleration_s: 0.245883502081 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.2300000190734863 - theta: -1.82638943777 - accumulated_s: 8.3929722023 -} -adc_trajectory_point { - x: -126.493362471 - y: 356.652523506 - z: -31.3444986399 - - speed: 3.330555439 - acceleration_s: 0.341762154716 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.2400000095367432 - theta: -1.82641776818 - accumulated_s: 8.42627775669 -} -adc_trajectory_point { - x: -126.501961865 - y: 356.620630121 - z: -31.3444468398 - - speed: 3.330555439 - acceleration_s: 0.341762154716 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.25 - theta: -1.82646394466 - accumulated_s: 8.45958331108 -} -adc_trajectory_point { - x: -126.510528434 - y: 356.588665449 - z: -31.3442180054 - - speed: 3.33611106873 - acceleration_s: 0.371268099975 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.2599999904632568 - theta: -1.82645211648 - accumulated_s: 8.49294442177 -} -adc_trajectory_point { - x: -126.519111453 - y: 356.556708783 - z: -31.3442060826 - - speed: 3.33611106873 - acceleration_s: 0.332246549914 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.2699999809265137 - theta: -1.82648901874 - accumulated_s: 8.52630553246 -} -adc_trajectory_point { - x: -126.52768735 - y: 356.524684258 - z: -31.3439824898 - - speed: 3.33888888359 - acceleration_s: 0.386355482026 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.2799999713897705 - theta: -1.82653384011 - accumulated_s: 8.55969442134 -} -adc_trajectory_point { - x: -126.53627215 - y: 356.492655285 - z: -31.3438073667 - - speed: 3.33888888359 - acceleration_s: 0.319144863026 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.2899999618530273 - theta: -1.82661869089 - accumulated_s: 8.59308331014 -} -adc_trajectory_point { - x: -126.544859835 - y: 356.460560798 - z: -31.3433333337 - - speed: 3.34444451332 - acceleration_s: 0.319144863026 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.2999999523162842 - theta: -1.82668673606 - accumulated_s: 8.62652775524 -} -adc_trajectory_point { - x: -126.55341621 - y: 356.428520827 - z: -31.3430436049 - - speed: 3.34444451332 - acceleration_s: 0.0399907940701 - curvature: -0.0008420464379 - curvature_change_rate: 0 - relative_time: 3.309999942779541 - theta: -1.82672008051 - accumulated_s: 8.65997220044 -} -adc_trajectory_point { - x: -126.562034607 - y: 356.396460461 - z: -31.3427345473 - - speed: 3.34722232819 - acceleration_s: 0.0891820167262 - curvature: -0.000803771467601 - curvature_change_rate: 0.00114348455366 - relative_time: 3.3199999332427979 - theta: -1.82678882025 - accumulated_s: 8.69344442364 -} -adc_trajectory_point { - x: -126.570648927 - y: 356.364378675 - z: -31.3422306031 - - speed: 3.34722232819 - acceleration_s: 0.121640972454 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 3.3300001621246338 - theta: -1.8268125683 - accumulated_s: 8.72691664694 -} -adc_trajectory_point { - x: -126.579282816 - y: 356.332271847 - z: -31.3416289231 - - speed: 3.3527777195 - acceleration_s: 0.180193809259 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 3.3400001525878906 - theta: -1.82681842755 - accumulated_s: 8.76044442414 -} -adc_trajectory_point { - x: -126.587904617 - y: 356.300163992 - z: -31.3409582535 - - speed: 3.3527777195 - acceleration_s: 0.105942443261 - curvature: -0.000803771467601 - curvature_change_rate: 0 - relative_time: 3.3500001430511475 - theta: -1.82683405334 - accumulated_s: 8.79397220134 -} -adc_trajectory_point { - x: -126.596606582 - y: 356.268053779 - z: -31.3404062809 - - speed: 3.36111116409 - acceleration_s: 0.105942443261 - curvature: -0.00076549651643 - curvature_change_rate: 0.00113875885986 - relative_time: 3.3600001335144043 - theta: -1.82687475275 - accumulated_s: 8.82758331304 -} -adc_trajectory_point { - x: -126.605334888 - y: 356.23593129 - z: -31.339665141 - - speed: 3.36111116409 - acceleration_s: 0.174192509194 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 3.3700001239776611 - theta: -1.8269203204 - accumulated_s: 8.86119442464 -} -adc_trajectory_point { - x: -126.614117099 - y: 356.203813035 - z: -31.3390399422 - - speed: 3.36944437027 - acceleration_s: 0.175419474684 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 3.380000114440918 - theta: -1.82693997226 - accumulated_s: 8.89488886834 -} -adc_trajectory_point { - x: -126.622915637 - y: 356.171656799 - z: -31.3382517239 - - speed: 3.36944437027 - acceleration_s: 0.255379637482 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 3.3900001049041748 - theta: -1.82698160888 - accumulated_s: 8.92858331204 -} -adc_trajectory_point { - x: -126.622915637 - y: 356.171656799 - z: -31.3382517239 - - speed: 3.37222218513 - acceleration_s: 0.255379637482 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 3.3900001049041748 - theta: -1.82698160888 - accumulated_s: 8.96230553384 -} -adc_trajectory_point { - x: -126.640551366 - y: 356.10725683 - z: -31.3369481983 - - speed: 3.37222218513 - acceleration_s: 0.416432213131 - curvature: -0.00076549651643 - curvature_change_rate: 0 - relative_time: 3.4100000858306885 - theta: -1.82701748655 - accumulated_s: 8.99602775574 -} -adc_trajectory_point { - x: -126.649407871 - y: 356.075053046 - z: -31.3362821704 - - speed: 3.37222218513 - acceleration_s: 0.18251066419 - curvature: -0.000727221583477 - curvature_change_rate: 0.00113500626151 - relative_time: 3.4200000762939453 - theta: -1.82707758232 - accumulated_s: 9.02974997764 -} -adc_trajectory_point { - x: -126.658247953 - y: 356.042762856 - z: -31.33576738 - - speed: 3.37222218513 - acceleration_s: 0.365772374337 - curvature: -0.000727221583477 - curvature_change_rate: 0 - relative_time: 3.4300000667572021 - theta: -1.82712424605 - accumulated_s: 9.06347219944 -} -adc_trajectory_point { - x: -126.667064499 - y: 356.010471259 - z: -31.3352754069 - - speed: 3.37777781487 - acceleration_s: 0.231852483685 - curvature: -0.00068894666783 - curvature_change_rate: 0.00113313893763 - relative_time: 3.440000057220459 - theta: -1.8271772763 - accumulated_s: 9.09724997764 -} -adc_trajectory_point { - x: -126.667064499 - y: 356.010471259 - z: -31.3352754069 - - speed: 3.37777781487 - acceleration_s: 0.231852483685 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.440000057220459 - theta: -1.8271772763 - accumulated_s: 9.13102775574 -} -adc_trajectory_point { - x: -126.684674625 - y: 355.945731248 - z: -31.3343479773 - - speed: 3.3833334446 - acceleration_s: 0.351494436829 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.4600000381469727 - theta: -1.82731511949 - accumulated_s: 9.16486109014 -} -adc_trajectory_point { - x: -126.693424055 - y: 355.913307342 - z: -31.3340699114 - - speed: 3.3833334446 - acceleration_s: 0.289788923925 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.4700000286102295 - theta: -1.82734949638 - accumulated_s: 9.19869442464 -} -adc_trajectory_point { - x: -126.702200971 - y: 355.88083369 - z: -31.3338288246 - - speed: 3.38888883591 - acceleration_s: 0.398475929312 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.4800000190734863 - theta: -1.82744159828 - accumulated_s: 9.23258331304 -} -adc_trajectory_point { - x: -126.710930873 - y: 355.84831332 - z: -31.3336686827 - - speed: 3.38888883591 - acceleration_s: 0.348416867207 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.4900000095367432 - theta: -1.82750114409 - accumulated_s: 9.26647220134 -} -adc_trajectory_point { - x: -126.719671587 - y: 355.815735623 - z: -31.3335086247 - - speed: 3.3972222805 - acceleration_s: 0.348416867207 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.5 - theta: -1.82756009136 - accumulated_s: 9.30044442414 -} -adc_trajectory_point { - x: -126.728400714 - y: 355.783148232 - z: -31.3335562842 - - speed: 3.3972222805 - acceleration_s: 0.366865734413 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.5099999904632568 - theta: -1.82763237866 - accumulated_s: 9.33441664694 -} -adc_trajectory_point { - x: -126.737119489 - y: 355.750478834 - z: -31.3335927948 - - speed: 3.40000009537 - acceleration_s: 0.398196786697 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.5199999809265137 - theta: -1.8276711613 - accumulated_s: 9.36841664794 -} -adc_trajectory_point { - x: -126.745890392 - y: 355.717802627 - z: -31.3338405546 - - speed: 3.40000009537 - acceleration_s: 0.407056699459 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.5299999713897705 - theta: -1.82776593486 - accumulated_s: 9.40241664884 -} -adc_trajectory_point { - x: -126.754648152 - y: 355.685051341 - z: -31.3340082122 - - speed: 3.40833330154 - acceleration_s: 0.462455457942 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.5399999618530273 - theta: -1.8278023492 - accumulated_s: 9.43649998184 -} -adc_trajectory_point { - x: -126.763448495 - y: 355.652292972 - z: -31.3342609107 - - speed: 3.40833330154 - acceleration_s: 0.381562232842 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.5499999523162842 - theta: -1.82787046192 - accumulated_s: 9.47058331494 -} -adc_trajectory_point { - x: -126.772282738 - y: 355.619491568 - z: -31.3345955834 - - speed: 3.41666674614 - acceleration_s: 0.410086796217 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.559999942779541 - theta: -1.82795142686 - accumulated_s: 9.50474998234 -} -adc_trajectory_point { - x: -126.781133488 - y: 355.586678912 - z: -31.3350851275 - - speed: 3.41666674614 - acceleration_s: 0.35893928034 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.5699999332427979 - theta: -1.8280057622 - accumulated_s: 9.53891664984 -} -adc_trajectory_point { - x: -126.790019684 - y: 355.553830693 - z: -31.335596595 - - speed: 3.42222213745 - acceleration_s: 0.331296594619 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.5800001621246338 - theta: -1.82807393538 - accumulated_s: 9.57313887124 -} -adc_trajectory_point { - x: -126.798896547 - y: 355.520951207 - z: -31.3360372046 - - speed: 3.42222213745 - acceleration_s: 0.276233157637 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.5900001525878906 - theta: -1.82808393272 - accumulated_s: 9.60736109254 -} -adc_trajectory_point { - x: -126.807794633 - y: 355.48805057 - z: -31.3366070502 - - speed: 3.43055558205 - acceleration_s: 0.276233157637 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.6000001430511475 - theta: -1.82810108706 - accumulated_s: 9.64166664844 -} -adc_trajectory_point { - x: -126.816726871 - y: 355.45512329 - z: -31.3371098014 - - speed: 3.43055558205 - acceleration_s: 0.32429213174 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.6100001335144043 - theta: -1.82814618418 - accumulated_s: 9.67597220424 -} -adc_trajectory_point { - x: -126.825647108 - y: 355.422181404 - z: -31.3377116378 - - speed: 3.43611121178 - acceleration_s: 0.218353440849 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.6200001239776611 - theta: -1.82816388197 - accumulated_s: 9.71033331634 -} -adc_trajectory_point { - x: -126.834592031 - y: 355.389185418 - z: -31.3381782286 - - speed: 3.43611121178 - acceleration_s: 0.378146566685 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.630000114440918 - theta: -1.82820396907 - accumulated_s: 9.74469442844 -} -adc_trajectory_point { - x: -126.843524209 - y: 355.356204879 - z: -31.3388533639 - - speed: 3.44166660309 - acceleration_s: 0.155025798903 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.6400001049041748 - theta: -1.82822069599 - accumulated_s: 9.77911109444 -} -adc_trajectory_point { - x: -126.843524209 - y: 355.356204879 - z: -31.3388533639 - - speed: 3.44166660309 - acceleration_s: 0.155025798903 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.6400001049041748 - theta: -1.82822069599 - accumulated_s: 9.81352776054 -} -adc_trajectory_point { - x: -126.843524209 - y: 355.356204879 - z: -31.3388533639 - - speed: 3.45000004768 - acceleration_s: 0.155025798903 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.6400001049041748 - theta: -1.82822069599 - accumulated_s: 9.84802776094 -} -adc_trajectory_point { - x: -126.870397211 - y: 355.257037275 - z: -31.3403574452 - - speed: 3.45000004768 - acceleration_s: 0.254390886898 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.6700000762939453 - theta: -1.82831717659 - accumulated_s: 9.88252776144 -} -adc_trajectory_point { - x: -126.879311763 - y: 355.22398288 - z: -31.340970126 - - speed: 3.455555439 - acceleration_s: 0.0126645717709 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.6800000667572021 - theta: -1.82833517327 - accumulated_s: 9.91708331584 -} -adc_trajectory_point { - x: -126.888256094 - y: 355.190846419 - z: -31.3412571475 - - speed: 3.455555439 - acceleration_s: 0.24582949855 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.690000057220459 - theta: -1.8283773573 - accumulated_s: 9.95163887024 -} -adc_trajectory_point { - x: -126.888256094 - y: 355.190846419 - z: -31.3412571475 - - speed: 3.46111106873 - acceleration_s: 0.24582949855 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.690000057220459 - theta: -1.8283773573 - accumulated_s: 9.98624998094 -} -adc_trajectory_point { - x: -126.906090232 - y: 355.124632865 - z: -31.3422407927 - - speed: 3.46111106873 - acceleration_s: 0.156962958221 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.7100000381469727 - theta: -1.82848761211 - accumulated_s: 10.02086109164 -} -adc_trajectory_point { - x: -126.914983567 - y: 355.091498265 - z: -31.3426592052 - - speed: 3.46666669846 - acceleration_s: 0.156962958221 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.7200000286102295 - theta: -1.82849070383 - accumulated_s: 10.05552775864 -} -adc_trajectory_point { - x: -126.923887147 - y: 355.058330606 - z: -31.3429553006 - - speed: 3.46666669846 - acceleration_s: 0.169272815993 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.7300000190734863 - theta: -1.82852467193 - accumulated_s: 10.09019442554 -} -adc_trajectory_point { - x: -126.932845484 - y: 355.025188265 - z: -31.3433769848 - - speed: 3.47222232819 - acceleration_s: 0.128742064854 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.7400000095367432 - theta: -1.82861436689 - accumulated_s: 10.12491664884 -} -adc_trajectory_point { - x: -126.94178364 - y: 354.992004229 - z: -31.3436619332 - - speed: 3.47222232819 - acceleration_s: 0.128742064854 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.75 - theta: -1.82867596843 - accumulated_s: 10.15963887214 -} -adc_trajectory_point { - x: -126.950761742 - y: 354.958826794 - z: -31.3439055979 - - speed: 3.4777777195 - acceleration_s: 0.135960393918 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.7599999904632568 - theta: -1.8287491962 - accumulated_s: 10.19441664934 -} -adc_trajectory_point { - x: -126.959732795 - y: 354.925645279 - z: -31.3440575274 - - speed: 3.4777777195 - acceleration_s: 0.0921660935908 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.7699999809265137 - theta: -1.82878160535 - accumulated_s: 10.22919442654 -} -adc_trajectory_point { - x: -126.968845043 - y: 354.892225725 - z: -31.3443499766 - - speed: 3.4777777195 - acceleration_s: 0.104852912322 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.7799999713897705 - theta: -1.82886115252 - accumulated_s: 10.26397220374 -} -adc_trajectory_point { - x: -126.977920106 - y: 354.858845057 - z: -31.3445986081 - - speed: 3.48611116409 - acceleration_s: 0.0743572609513 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.7899999618530273 - theta: -1.82888331647 - accumulated_s: 10.29883331534 -} -adc_trajectory_point { - x: -126.987026937 - y: 354.825460923 - z: -31.3446845347 - - speed: 3.48611116409 - acceleration_s: 0.0743572609513 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.7999999523162842 - theta: -1.82893094731 - accumulated_s: 10.33369442704 -} -adc_trajectory_point { - x: -126.996118589 - y: 354.792068672 - z: -31.344827082 - - speed: 3.48888897896 - acceleration_s: 0.070383169644 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.809999942779541 - theta: -1.82893262628 - accumulated_s: 10.36858331684 -} -adc_trajectory_point { - x: -127.005245278 - y: 354.7586637 - z: -31.3449398251 - - speed: 3.48888897896 - acceleration_s: 0.119709390437 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.8199999332427979 - theta: -1.82897739732 - accumulated_s: 10.40347220664 -} -adc_trajectory_point { - x: -127.014377668 - y: 354.72526672 - z: -31.3451361712 - - speed: 3.49444437027 - acceleration_s: 0.0751073695378 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.8300001621246338 - theta: -1.82904601912 - accumulated_s: 10.43841665034 -} -adc_trajectory_point { - x: -127.023511394 - y: 354.691835324 - z: -31.3451459203 - - speed: 3.49444437027 - acceleration_s: 0.140743091578 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.8400001525878906 - theta: -1.82911105592 - accumulated_s: 10.47336109404 -} -adc_trajectory_point { - x: -127.032643564 - y: 354.65840443 - z: -31.3451923309 - - speed: 3.49722218513 - acceleration_s: 0.129740223018 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.8500001430511475 - theta: -1.82915697214 - accumulated_s: 10.50833331584 -} -adc_trajectory_point { - x: -127.041741357 - y: 354.624959016 - z: -31.345202636 - - speed: 3.49722218513 - acceleration_s: 0.0698403466267 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.8600001335144043 - theta: -1.82918546224 - accumulated_s: 10.54330553774 -} -adc_trajectory_point { - x: -127.050838768 - y: 354.591507994 - z: -31.3452956183 - - speed: 3.49722218513 - acceleration_s: 0.102952163422 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.8700001239776611 - theta: -1.8292184562 - accumulated_s: 10.57827775954 -} -adc_trajectory_point { - x: -127.059920682 - y: 354.558039646 - z: -31.3453835277 - - speed: 3.49722218513 - acceleration_s: 0.125030207742 - curvature: -0.00068894666783 - curvature_change_rate: 0 - relative_time: 3.880000114440918 - theta: -1.82930011786 - accumulated_s: 10.61324998144 -} -adc_trajectory_point { - x: -127.069007327 - y: 354.524558985 - z: -31.3454027781 - - speed: 3.49722218513 - acceleration_s: 0.100108782099 - curvature: -0.000650671714967 - curvature_change_rate: 0.00109443869554 - relative_time: 3.8900001049041748 - theta: -1.82935923457 - accumulated_s: 10.64822220324 -} -adc_trajectory_point { - x: -127.069007327 - y: 354.524558985 - z: -31.3454027781 - - speed: 3.49722218513 - acceleration_s: 0.100108782099 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 3.8900001049041748 - theta: -1.82935923457 - accumulated_s: 10.68319442514 -} -adc_trajectory_point { - x: -127.087131159 - y: 354.457564805 - z: -31.3453779882 - - speed: 3.49722218513 - acceleration_s: 0.136465245228 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 3.9100000858306885 - theta: -1.82945501367 - accumulated_s: 10.71816664694 -} -adc_trajectory_point { - x: -127.09618456 - y: 354.424078302 - z: -31.3453200571 - - speed: 3.49722218513 - acceleration_s: -0.0660130467235 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 3.9200000762939453 - theta: -1.82948641199 - accumulated_s: 10.75313886884 -} -adc_trajectory_point { - x: -127.105212885 - y: 354.390589505 - z: -31.3452071091 - - speed: 3.49722218513 - acceleration_s: -0.0249797199174 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 3.9300000667572021 - theta: -1.82951068129 - accumulated_s: 10.78811109064 -} -adc_trajectory_point { - x: -127.114306368 - y: 354.357115855 - z: -31.3451743815 - - speed: 3.49722218513 - acceleration_s: -0.048503940321 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 3.940000057220459 - theta: -1.82959902092 - accumulated_s: 10.82308331254 -} -adc_trajectory_point { - x: -127.114306368 - y: 354.357115855 - z: -31.3451743815 - - speed: 3.5 - acceleration_s: -0.048503940321 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 3.940000057220459 - theta: -1.82959902092 - accumulated_s: 10.85808331254 -} -adc_trajectory_point { - x: -127.132468752 - y: 354.29014 - z: -31.3449956318 - - speed: 3.5 - acceleration_s: 0.00437034875301 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 3.9600000381469727 - theta: -1.82967998586 - accumulated_s: 10.89308331254 -} -adc_trajectory_point { - x: -127.141546712 - y: 354.256640033 - z: -31.3447698774 - - speed: 3.5 - acceleration_s: 0.0539961257544 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 3.9700000286102295 - theta: -1.82967703275 - accumulated_s: 10.92808331254 -} -adc_trajectory_point { - x: -127.150674473 - y: 354.223174755 - z: -31.3446746515 - - speed: 3.5 - acceleration_s: 0.0166207486735 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 3.9800000190734863 - theta: -1.82973850988 - accumulated_s: 10.96308331254 -} -adc_trajectory_point { - x: -127.159820198 - y: 354.189687125 - z: -31.3445321759 - - speed: 3.50277781487 - acceleration_s: 0.0610884625379 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 3.9900000095367432 - theta: -1.82976633702 - accumulated_s: 10.99811109064 -} -adc_trajectory_point { - x: -127.168969071 - y: 354.156205111 - z: -31.3444438847 - - speed: 3.50277781487 - acceleration_s: 0.0610884625379 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4 - theta: -1.82977832509 - accumulated_s: 11.03313886884 -} -adc_trajectory_point { - x: -127.178129942 - y: 354.122715923 - z: -31.3441801267 - - speed: 3.50555562973 - acceleration_s: 0.0171917654006 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.0099999904632568 - theta: -1.82979912619 - accumulated_s: 11.06819442514 -} -adc_trajectory_point { - x: -127.1872916 - y: 354.08924327 - z: -31.3440388041 - - speed: 3.50555562973 - acceleration_s: -0.0246935139104 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.0199999809265137 - theta: -1.82983598313 - accumulated_s: 11.10324998144 -} -adc_trajectory_point { - x: -127.196444175 - y: 354.055745947 - z: -31.343894613 - - speed: 3.50555562973 - acceleration_s: 0.029217316152 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.0299999713897705 - theta: -1.82984557377 - accumulated_s: 11.13830553774 -} -adc_trajectory_point { - x: -127.205629271 - y: 354.022270959 - z: -31.3438157281 - - speed: 3.50555562973 - acceleration_s: 0.0632390704121 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.0399999618530273 - theta: -1.82992024271 - accumulated_s: 11.17336109404 -} -adc_trajectory_point { - x: -127.214820714 - y: 353.988772922 - z: -31.343679429 - - speed: 3.5083334446 - acceleration_s: 0.0632390704121 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.0499999523162842 - theta: -1.82999209665 - accumulated_s: 11.20844442844 -} -adc_trajectory_point { - x: -127.223934396 - y: 353.955248469 - z: -31.3435372906 - - speed: 3.5083334446 - acceleration_s: 0.080489073689 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.059999942779541 - theta: -1.82998936836 - accumulated_s: 11.24352776294 -} -adc_trajectory_point { - x: -127.233079158 - y: 353.921744536 - z: -31.3434529463 - - speed: 3.51111102104 - acceleration_s: -0.0491628331971 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.0699999332427979 - theta: -1.83003833333 - accumulated_s: 11.27863887314 -} -adc_trajectory_point { - x: -127.242215302 - y: 353.888209575 - z: -31.3433400812 - - speed: 3.51111102104 - acceleration_s: 0.125815518791 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.0800001621246338 - theta: -1.83008827199 - accumulated_s: 11.31374998334 -} -adc_trajectory_point { - x: -127.25133237 - y: 353.854701581 - z: -31.343334713 - - speed: 3.51111102104 - acceleration_s: -0.0753108616618 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.0900001525878906 - theta: -1.83012063751 - accumulated_s: 11.34886109354 -} -adc_trajectory_point { - x: -127.25133237 - y: 353.854701581 - z: -31.343334713 - - speed: 3.51111102104 - acceleration_s: -0.0753108616618 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.0900001525878906 - theta: -1.83012063751 - accumulated_s: 11.38397220374 -} -adc_trajectory_point { - x: -127.260465701 - y: 353.821174366 - z: -31.3431319427 - - speed: 3.51111102104 - acceleration_s: 0.0284058578204 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.1000001430511475 - theta: -1.83018895846 - accumulated_s: 11.41908331394 -} -adc_trajectory_point { - x: -127.278645517 - y: 353.75417139 - z: -31.3427735092 - - speed: 3.5083334446 - acceleration_s: -0.143244759665 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.1200001239776611 - theta: -1.83033064983 - accumulated_s: 11.45416664844 -} -adc_trajectory_point { - x: -127.287726602 - y: 353.720680013 - z: -31.3427321464 - - speed: 3.5083334446 - acceleration_s: 0.0137720136515 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.130000114440918 - theta: -1.83032837069 - accumulated_s: 11.48924998284 -} -adc_trajectory_point { - x: -127.296827498 - y: 353.687184372 - z: -31.342702006 - - speed: 3.51111102104 - acceleration_s: -0.0666400244512 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.1400001049041748 - theta: -1.83040303824 - accumulated_s: 11.52436109304 -} -adc_trajectory_point { - x: -127.305958054 - y: 353.653664985 - z: -31.3424840998 - - speed: 3.51111102104 - acceleration_s: 0.154026797915 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.1500000953674316 - theta: -1.83048015605 - accumulated_s: 11.55947220324 -} -adc_trajectory_point { - x: -127.315100194 - y: 353.620166606 - z: -31.34229057 - - speed: 3.51388883591 - acceleration_s: -0.0498033602618 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.1600000858306885 - theta: -1.83052274121 - accumulated_s: 11.59461109164 -} -adc_trajectory_point { - x: -127.324251173 - y: 353.586648334 - z: -31.3422872778 - - speed: 3.51388883591 - acceleration_s: 0.162973212394 - curvature: -0.000650671714967 - curvature_change_rate: 0 - relative_time: 4.1700000762939453 - theta: -1.83056090677 - accumulated_s: 11.62974997994 -} -adc_trajectory_point { - x: -127.333418671 - y: 353.553179486 - z: -31.3423312837 - - speed: 3.51111102104 - acceleration_s: -0.141101185711 - curvature: -0.000612396831201 - curvature_change_rate: 0.001090107477 - relative_time: 4.1800000667572021 - theta: -1.83058190642 - accumulated_s: 11.66486109014 -} -adc_trajectory_point { - x: -127.342681013 - y: 353.519700849 - z: -31.3420709325 - - speed: 3.51111102104 - acceleration_s: -0.0517334296119 - curvature: -0.000612396831201 - curvature_change_rate: 0 - relative_time: 4.190000057220459 - theta: -1.83064560254 - accumulated_s: 11.69997220044 -} -adc_trajectory_point { - x: -127.342681013 - y: 353.519700849 - z: -31.3420709325 - - speed: 3.5083334446 - acceleration_s: -0.0517334296119 - curvature: -0.000612396831201 - curvature_change_rate: 0 - relative_time: 4.190000057220459 - theta: -1.83064560254 - accumulated_s: 11.73505553484 -} -adc_trajectory_point { - x: -127.36116599 - y: 353.452817985 - z: -31.3417495564 - - speed: 3.5083334446 - acceleration_s: -0.0942125079577 - curvature: -0.000612396831201 - curvature_change_rate: 0 - relative_time: 4.2100000381469727 - theta: -1.83073502772 - accumulated_s: 11.77013886924 -} -adc_trajectory_point { - x: -127.37042041 - y: 353.419382693 - z: -31.3417761633 - - speed: 3.50555562973 - acceleration_s: -0.0336458274378 - curvature: -0.000574121962009 - curvature_change_rate: 0.00109183459727 - relative_time: 4.2200000286102295 - theta: -1.83074813734 - accumulated_s: 11.80519442554 -} -adc_trajectory_point { - x: -127.379685011 - y: 353.385927859 - z: -31.341597436 - - speed: 3.50555562973 - acceleration_s: 0.0668762718841 - curvature: -0.000574121962009 - curvature_change_rate: 0 - relative_time: 4.2300000190734863 - theta: -1.8307699959 - accumulated_s: 11.84024998184 -} -adc_trajectory_point { - x: -127.38893948 - y: 353.352510714 - z: -31.3415910527 - - speed: 3.50555562973 - acceleration_s: -0.0624050681945 - curvature: -0.00053584710648 - curvature_change_rate: 0.00109183420752 - relative_time: 4.2400000095367432 - theta: -1.83080014569 - accumulated_s: 11.87530553814 -} -adc_trajectory_point { - x: -127.38893948 - y: 353.352510714 - z: -31.3415910527 - - speed: 3.50555562973 - acceleration_s: -0.0624050681945 - curvature: -0.00053584710648 - curvature_change_rate: 0 - relative_time: 4.2400000095367432 - theta: -1.83080014569 - accumulated_s: 11.91036109444 -} -adc_trajectory_point { - x: -127.407486713 - y: 353.285614588 - z: -31.3412877694 - - speed: 3.50555562973 - acceleration_s: -0.0603550657043 - curvature: -0.00053584710648 - curvature_change_rate: 0 - relative_time: 4.2599999904632568 - theta: -1.83091574367 - accumulated_s: 11.94541665074 -} -adc_trajectory_point { - x: -127.41675961 - y: 353.252149643 - z: -31.3411435066 - - speed: 3.50277781487 - acceleration_s: 0.0943058075574 - curvature: -0.00053584710648 - curvature_change_rate: 0 - relative_time: 4.2699999809265137 - theta: -1.83096402222 - accumulated_s: 11.98044442894 -} -adc_trajectory_point { - x: -127.425972495 - y: 353.218729213 - z: -31.3410838377 - - speed: 3.50277781487 - acceleration_s: -0.140005243068 - curvature: -0.00053584710648 - curvature_change_rate: 0 - relative_time: 4.2799999713897705 - theta: -1.83097341345 - accumulated_s: 12.01547220704 -} -adc_trajectory_point { - x: -127.435203826 - y: 353.185267974 - z: -31.3408259097 - - speed: 3.50277781487 - acceleration_s: -0.0260910511436 - curvature: -0.000459297432768 - curvature_change_rate: 0.00218539906777 - relative_time: 4.2899999618530273 - theta: -1.8310217043 - accumulated_s: 12.05049998524 -} -adc_trajectory_point { - x: -127.444435751 - y: 353.151844245 - z: -31.3408429427 - - speed: 3.50277781487 - acceleration_s: -0.0616759587855 - curvature: -0.000459297432768 - curvature_change_rate: 0 - relative_time: 4.2999999523162842 - theta: -1.83107682585 - accumulated_s: 12.08552776334 -} -adc_trajectory_point { - x: -127.45365022 - y: 353.118401612 - z: -31.3407579828 - - speed: 3.5 - acceleration_s: -0.0203062887987 - curvature: -0.000382747802778 - curvature_change_rate: 0.00218713228543 - relative_time: 4.309999942779541 - theta: -1.83113331783 - accumulated_s: 12.12052776334 -} -adc_trajectory_point { - x: -127.462881144 - y: 353.084978017 - z: -31.3406273052 - - speed: 3.5 - acceleration_s: -0.0723565693088 - curvature: -0.000382747802778 - curvature_change_rate: 0 - relative_time: 4.3199999332427979 - theta: -1.83119552366 - accumulated_s: 12.15552776334 -} -adc_trajectory_point { - x: -127.462881144 - y: 353.084978017 - z: -31.3406273052 - - speed: 3.50277781487 - acceleration_s: -0.0723565693088 - curvature: -0.000267923397025 - curvature_change_rate: 0.0032780956093 - relative_time: 4.3199999332427979 - theta: -1.83119552366 - accumulated_s: 12.19055554154 -} -adc_trajectory_point { - x: -127.481292053 - y: 353.018133317 - z: -31.3403774407 - - speed: 3.50277781487 - acceleration_s: -0.128554803024 - curvature: -0.000267923397025 - curvature_change_rate: 0 - relative_time: 4.3400001525878906 - theta: -1.83126742553 - accumulated_s: 12.22558331964 -} -adc_trajectory_point { - x: -127.490530961 - y: 352.984730905 - z: -31.3403131105 - - speed: 3.5 - acceleration_s: -0.128554803024 - curvature: -0.00022964861801 - curvature_change_rate: 0.00109356511473 - relative_time: 4.3500001430511475 - theta: -1.83133791977 - accumulated_s: 12.26058331964 -} -adc_trajectory_point { - x: -127.499761733 - y: 352.951312686 - z: -31.3401267733 - - speed: 3.5 - acceleration_s: 0.00202995199734 - curvature: -0.00022964861801 - curvature_change_rate: 0 - relative_time: 4.3600001335144043 - theta: -1.83139367929 - accumulated_s: 12.29558331964 -} -adc_trajectory_point { - x: -127.509002213 - y: 352.917914714 - z: -31.340024651 - - speed: 3.5 - acceleration_s: -0.0230681211466 - curvature: -0.000153099062061 - curvature_change_rate: 0.00218713016998 - relative_time: 4.3700001239776611 - theta: -1.83144360265 - accumulated_s: 12.33058331964 -} -adc_trajectory_point { - x: -127.518221677 - y: 352.884498307 - z: -31.339929861 - - speed: 3.5 - acceleration_s: 0.064519298669 - curvature: -0.000153099062061 - curvature_change_rate: 0 - relative_time: 4.380000114440918 - theta: -1.83148658053 - accumulated_s: 12.36558331964 -} -adc_trajectory_point { - x: -127.527448428 - y: 352.851115155 - z: -31.3398054801 - - speed: 3.50277781487 - acceleration_s: -0.103607147081 - curvature: -7.65495273868e-05 - curvature_change_rate: 0.0021853950984 - relative_time: 4.3900001049041748 - theta: -1.83153713873 - accumulated_s: 12.40061109784 -} -adc_trajectory_point { - x: -127.527448428 - y: 352.851115155 - z: -31.3398054801 - - speed: 3.50277781487 - acceleration_s: -0.103607147081 - curvature: -7.65495273868e-05 - curvature_change_rate: 0 - relative_time: 4.3900001049041748 - theta: -1.83153713873 - accumulated_s: 12.43563887594 -} -adc_trajectory_point { - x: -127.545900064 - y: 352.784346422 - z: -31.33951113 - - speed: 3.50277781487 - acceleration_s: -0.0562023025099 - curvature: 0 - curvature_change_rate: 0.00218539489036 - relative_time: 4.4100000858306885 - theta: -1.83166178602 - accumulated_s: 12.47066665414 -} -adc_trajectory_point { - x: -127.555063447 - y: 352.750948452 - z: -31.3394007226 - - speed: 3.50277781487 - acceleration_s: -0.0452948144891 - curvature: 0 - curvature_change_rate: 0 - relative_time: 4.4200000762939453 - theta: -1.83164595044 - accumulated_s: 12.50569443224 -} -adc_trajectory_point { - x: -127.564226747 - y: 352.717566443 - z: -31.339252756 - - speed: 3.50277781487 - acceleration_s: -0.10394213781 - curvature: 3.8274763238e-05 - curvature_change_rate: 0.00109269743218 - relative_time: 4.4300000667572021 - theta: -1.83168737663 - accumulated_s: 12.54072221044 -} -adc_trajectory_point { - x: -127.573422248 - y: 352.684193594 - z: -31.339159444 - - speed: 3.50277781487 - acceleration_s: -0.0592971113935 - curvature: 3.8274763238e-05 - curvature_change_rate: 0 - relative_time: 4.440000057220459 - theta: -1.83173225633 - accumulated_s: 12.57574998854 -} -adc_trajectory_point { - x: -127.573422248 - y: 352.684193594 - z: -31.339159444 - - speed: 3.50555562973 - acceleration_s: -0.0592971113935 - curvature: 0.000114824296708 - curvature_change_rate: 0.00218366334914 - relative_time: 4.440000057220459 - theta: -1.83173225633 - accumulated_s: 12.61080554484 -} -adc_trajectory_point { - x: -127.591775516 - y: 352.617499289 - z: -31.3388572838 - - speed: 3.50555562973 - acceleration_s: -0.10332422624 - curvature: 0.000114824296708 - curvature_change_rate: 0 - relative_time: 4.4600000381469727 - theta: -1.8317986102 - accumulated_s: 12.64586110114 -} -adc_trajectory_point { - x: -127.600959198 - y: 352.58413393 - z: -31.3385668267 - - speed: 3.50277781487 - acceleration_s: 0.036427094581 - curvature: 0.000114824296708 - curvature_change_rate: 0 - relative_time: 4.4700000286102295 - theta: -1.83184783483 - accumulated_s: 12.68088887934 -} -adc_trajectory_point { - x: -127.610081204 - y: 352.550819193 - z: -31.338401326 - - speed: 3.50277781487 - acceleration_s: -0.220284014485 - curvature: 0.000114824296708 - curvature_change_rate: 0 - relative_time: 4.4800000190734863 - theta: -1.83184542029 - accumulated_s: 12.71591665744 -} -adc_trajectory_point { - x: -127.619241505 - y: 352.517469776 - z: -31.3382468 - - speed: 3.5 - acceleration_s: 0.0616668466865 - curvature: 0.000153099062061 - curvature_change_rate: 0.00109356472436 - relative_time: 4.4900000095367432 - theta: -1.83188878236 - accumulated_s: 12.75091665744 -} -adc_trajectory_point { - x: -127.619241505 - y: 352.517469776 - z: -31.3382468 - - speed: 3.5 - acceleration_s: 0.0616668466865 - curvature: 0.000153099062061 - curvature_change_rate: 0 - relative_time: 4.4900000095367432 - theta: -1.83188878236 - accumulated_s: 12.78591665744 -} -adc_trajectory_point { - x: -127.637512671 - y: 352.450853478 - z: -31.3376777451 - - speed: 3.49722218513 - acceleration_s: -0.105173996676 - curvature: 0.00022964861801 - curvature_change_rate: 0.00218886738951 - relative_time: 4.5099999904632568 - theta: -1.83190611893 - accumulated_s: 12.82088887934 -} -adc_trajectory_point { - x: -127.646605363 - y: 352.417550727 - z: -31.3374220422 - - speed: 3.49722218513 - acceleration_s: -0.138525113976 - curvature: 0.00022964861801 - curvature_change_rate: 0 - relative_time: 4.5199999809265137 - theta: -1.83194340833 - accumulated_s: 12.85586110114 -} -adc_trajectory_point { - x: -127.655725274 - y: 352.384269714 - z: -31.3373159245 - - speed: 3.49722218513 - acceleration_s: -0.0892186163574 - curvature: 0.000267923397025 - curvature_change_rate: 0.00109443372452 - relative_time: 4.5299999713897705 - theta: -1.83198817165 - accumulated_s: 12.89083332304 -} -adc_trajectory_point { - x: -127.664766556 - y: 352.35097541 - z: -31.3371274434 - - speed: 3.49722218513 - acceleration_s: -0.110796774377 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 4.5399999618530273 - theta: -1.83197210021 - accumulated_s: 12.92580554484 -} -adc_trajectory_point { - x: -127.673871586 - y: 352.317713472 - z: -31.3367670989 - - speed: 3.49444437027 - acceleration_s: -0.110796774377 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 4.5499999523162842 - theta: -1.83203277637 - accumulated_s: 12.96074998854 -} -adc_trajectory_point { - x: -127.682924838 - y: 352.284454014 - z: -31.3363768291 - - speed: 3.49444437027 - acceleration_s: -0.164934767576 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 4.559999942779541 - theta: -1.83203575236 - accumulated_s: 12.99569443224 -} -adc_trajectory_point { - x: -127.69197512 - y: 352.251221667 - z: -31.3362560766 - - speed: 3.49444437027 - acceleration_s: -0.168375974979 - curvature: 0.000344473001902 - curvature_change_rate: 0.0021906087711 - relative_time: 4.5699999332427979 - theta: -1.83206012701 - accumulated_s: 13.03063887594 -} -adc_trajectory_point { - x: -127.701075862 - y: 352.217973001 - z: -31.3358970415 - - speed: 3.49444437027 - acceleration_s: 0.00372759671715 - curvature: 0.000344473001902 - curvature_change_rate: 0 - relative_time: 4.5800001621246338 - theta: -1.83212536817 - accumulated_s: 13.06558331964 -} -adc_trajectory_point { - x: -127.701075862 - y: 352.217973001 - z: -31.3358970415 - - speed: 3.49444437027 - acceleration_s: 0.00372759671715 - curvature: 0.000382747802778 - curvature_change_rate: 0.00109530434086 - relative_time: 4.5800001621246338 - theta: -1.83212536817 - accumulated_s: 13.10052776334 -} -adc_trajectory_point { - x: -127.719167513 - y: 352.151519105 - z: -31.3352947813 - - speed: 3.49444437027 - acceleration_s: -0.0288038778254 - curvature: 0.000382747802778 - curvature_change_rate: 0 - relative_time: 4.6000001430511475 - theta: -1.83212690918 - accumulated_s: 13.13547220704 -} -adc_trajectory_point { - x: -127.728217748 - y: 352.118314562 - z: -31.3352246499 - - speed: 3.49444437027 - acceleration_s: -0.11820502083 - curvature: 0.000459297432768 - curvature_change_rate: 0.00219060948978 - relative_time: 4.6100001335144043 - theta: -1.83216226657 - accumulated_s: 13.17041665074 -} -adc_trajectory_point { - x: -127.737284009 - y: 352.085089415 - z: -31.3348650029 - - speed: 3.49444437027 - acceleration_s: -0.0531890101833 - curvature: 0.000459297432768 - curvature_change_rate: 0 - relative_time: 4.6200001239776611 - theta: -1.83218983511 - accumulated_s: 13.20536109444 -} -adc_trajectory_point { - x: -127.746316119 - y: 352.051884421 - z: -31.3347293595 - - speed: 3.49444437027 - acceleration_s: -0.0470023655957 - curvature: 0.00053584710648 - curvature_change_rate: 0.00219061074096 - relative_time: 4.630000114440918 - theta: -1.83219678742 - accumulated_s: 13.24030553814 -} -adc_trajectory_point { - x: -127.755379258 - y: 352.018669332 - z: -31.3345220741 - - speed: 3.49444437027 - acceleration_s: -0.00745154333254 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 4.6400001049041748 - theta: -1.83221628957 - accumulated_s: 13.27524998184 -} -adc_trajectory_point { - x: -127.764413044 - y: 351.985459773 - z: -31.3343663076 - - speed: 3.49444437027 - acceleration_s: -0.0239191625422 - curvature: 0.000574121962009 - curvature_change_rate: 0.00109530590484 - relative_time: 4.6500000953674316 - theta: -1.83220767276 - accumulated_s: 13.31019442554 -} -adc_trajectory_point { - x: -127.773489504 - y: 351.95224056 - z: -31.3341953186 - - speed: 3.49444437027 - acceleration_s: -0.00434879322893 - curvature: 0.000574121962009 - curvature_change_rate: 0 - relative_time: 4.6600000858306885 - theta: -1.83224257355 - accumulated_s: 13.34513886924 -} -adc_trajectory_point { - x: -127.782530946 - y: 351.919025975 - z: -31.3340980159 - - speed: 3.49722218513 - acceleration_s: 0.0305157160983 - curvature: 0.000612396831201 - curvature_change_rate: 0.00109443630304 - relative_time: 4.6700000762939453 - theta: -1.8322637484 - accumulated_s: 13.38011109114 -} -adc_trajectory_point { - x: -127.791579028 - y: 351.885819526 - z: -31.3340129573 - - speed: 3.49722218513 - acceleration_s: -0.0801850819625 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 4.6800000667572021 - theta: -1.8322688425 - accumulated_s: 13.41508331304 -} -adc_trajectory_point { - x: -127.800627977 - y: 351.852610815 - z: -31.3338932684 - - speed: 3.49722218513 - acceleration_s: -0.0318863733843 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 4.690000057220459 - theta: -1.83229720076 - accumulated_s: 13.45005553484 -} -adc_trajectory_point { - x: -127.800627977 - y: 351.852610815 - z: -31.3338932684 - - speed: 3.49722218513 - acceleration_s: -0.0318863733843 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 4.690000057220459 - theta: -1.83229720076 - accumulated_s: 13.48502775674 -} -adc_trajectory_point { - x: -127.818702223 - y: 351.786185824 - z: -31.3336895285 - - speed: 3.49722218513 - acceleration_s: 0.0986010473449 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 4.7100000381469727 - theta: -1.83228232381 - accumulated_s: 13.51999997854 -} -adc_trajectory_point { - x: -127.827759872 - y: 351.752971154 - z: -31.3336588815 - - speed: 3.49722218513 - acceleration_s: 0.0382934250362 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 4.7200000286102295 - theta: -1.83229801983 - accumulated_s: 13.55497220044 -} -adc_trajectory_point { - x: -127.836847606 - y: 351.719759317 - z: -31.3336090865 - - speed: 3.49444437027 - acceleration_s: 0.081440974817 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 4.7300000190734863 - theta: -1.83234181352 - accumulated_s: 13.58991664414 -} -adc_trajectory_point { - x: -127.845952569 - y: 351.686565803 - z: -31.333643714 - - speed: 3.49444437027 - acceleration_s: 0.0209780932665 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 4.7400000095367432 - theta: -1.83239281915 - accumulated_s: 13.62486108784 -} -adc_trajectory_point { - x: -127.855011926 - y: 351.653337572 - z: -31.3334456477 - - speed: 3.4916665554 - acceleration_s: 0.0209780932665 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 4.75 - theta: -1.83232234836 - accumulated_s: 13.65977775334 -} -adc_trajectory_point { - x: -127.864136526 - y: 351.620136288 - z: -31.3333633449 - - speed: 3.4916665554 - acceleration_s: 0.0100937873768 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 4.7599999904632568 - theta: -1.83233665346 - accumulated_s: 13.69469441894 -} -adc_trajectory_point { - x: -127.873235968 - y: 351.586976341 - z: -31.3333423594 - - speed: 3.4916665554 - acceleration_s: 0.0576327186021 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 4.7699999809265137 - theta: -1.83235880506 - accumulated_s: 13.72961108444 -} -adc_trajectory_point { - x: -127.882284648 - y: 351.553899762 - z: -31.3333647577 - - speed: 3.4916665554 - acceleration_s: 0.021545202312 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 4.7799999713897705 - theta: -1.83235729889 - accumulated_s: 13.76452775004 -} -adc_trajectory_point { - x: -127.891345597 - y: 351.520796852 - z: -31.3332146611 - - speed: 3.4916665554 - acceleration_s: 0.0539346592736 - curvature: 0.000574121962009 - curvature_change_rate: -0.00109617767289 - relative_time: 4.7899999618530273 - theta: -1.83232611012 - accumulated_s: 13.79944441554 -} -adc_trajectory_point { - x: -127.900472174 - y: 351.487701684 - z: -31.3330173064 - - speed: 3.4916665554 - acceleration_s: 0.10874125944 - curvature: 0.000574121962009 - curvature_change_rate: 0 - relative_time: 4.7999999523162842 - theta: -1.83232937515 - accumulated_s: 13.83436108114 -} -adc_trajectory_point { - x: -127.909547697 - y: 351.454601005 - z: -31.3329471787 - - speed: 3.48888897896 - acceleration_s: 0.0580133361244 - curvature: 0.00053584710648 - curvature_change_rate: -0.00109704997091 - relative_time: 4.809999942779541 - theta: -1.83227496228 - accumulated_s: 13.86924997094 -} -adc_trajectory_point { - x: -127.918651362 - y: 351.421491066 - z: -31.3328811266 - - speed: 3.48888897896 - acceleration_s: 0.126041599598 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 4.8199999332427979 - theta: -1.83228128078 - accumulated_s: 13.90413886074 -} -adc_trajectory_point { - x: -127.927735111 - y: 351.3883593 - z: -31.3327781893 - - speed: 3.48888897896 - acceleration_s: 0.103582712995 - curvature: 0.000497572263703 - curvature_change_rate: -0.0010970496054 - relative_time: 4.8300001621246338 - theta: -1.83225309008 - accumulated_s: 13.93902775054 -} -adc_trajectory_point { - x: -127.936852555 - y: 351.355237961 - z: -31.3326249309 - - speed: 3.48888897896 - acceleration_s: 0.0987043389986 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 4.8400001525878906 - theta: -1.83225678098 - accumulated_s: 13.97391664024 -} -adc_trajectory_point { - x: -127.945946783 - y: 351.322088963 - z: -31.3325914145 - - speed: 3.4916665554 - acceleration_s: 0.125243887153 - curvature: 0.000459297432768 - curvature_change_rate: -0.00109617657723 - relative_time: 4.8500001430511475 - theta: -1.83225725673 - accumulated_s: 14.00883330584 -} -adc_trajectory_point { - x: -127.955074316 - y: 351.288940788 - z: -31.3324934971 - - speed: 3.4916665554 - acceleration_s: 0.121261153979 - curvature: 0.000459297432768 - curvature_change_rate: 0 - relative_time: 4.8600001335144043 - theta: -1.83230175825 - accumulated_s: 14.04374997144 -} -adc_trajectory_point { - x: -127.964154214 - y: 351.255774262 - z: -31.3324116757 - - speed: 3.4916665554 - acceleration_s: 0.0387133948109 - curvature: 0.000459297432768 - curvature_change_rate: 0 - relative_time: 4.8700001239776611 - theta: -1.83227376243 - accumulated_s: 14.07866663694 -} -adc_trajectory_point { - x: -127.973293048 - y: 351.222600333 - z: -31.3323044209 - - speed: 3.4916665554 - acceleration_s: 0.128501307565 - curvature: 0.000459297432768 - curvature_change_rate: 0 - relative_time: 4.880000114440918 - theta: -1.83231098077 - accumulated_s: 14.11358330254 -} -adc_trajectory_point { - x: -127.982415681 - y: 351.189416085 - z: -31.332248074 - - speed: 3.48888897896 - acceleration_s: 0.130341510986 - curvature: 0.000459297432768 - curvature_change_rate: 0 - relative_time: 4.8900001049041748 - theta: -1.83234969531 - accumulated_s: 14.14847219234 -} -adc_trajectory_point { - x: -127.982415681 - y: 351.189416085 - z: -31.332248074 - - speed: 3.48888897896 - acceleration_s: 0.130341510986 - curvature: 0.000459297432768 - curvature_change_rate: 0 - relative_time: 4.8900001049041748 - theta: -1.83234969531 - accumulated_s: 14.18336108204 -} -adc_trajectory_point { - x: -128.000654248 - y: 351.122957373 - z: -31.3320949441 - - speed: 3.4916665554 - acceleration_s: 0.2155785191 - curvature: 0.000421022612763 - curvature_change_rate: -0.00109617626418 - relative_time: 4.9100000858306885 - theta: -1.83237155489 - accumulated_s: 14.21827774764 -} -adc_trajectory_point { - x: -128.009766732 - y: 351.089731207 - z: -31.3320094375 - - speed: 3.4916665554 - acceleration_s: 0.100030454833 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 4.9200000762939453 - theta: -1.83240200657 - accumulated_s: 14.25319441314 -} -adc_trajectory_point { - x: -128.018885109 - y: 351.056451235 - z: -31.3319301745 - - speed: 3.49444437027 - acceleration_s: 0.143884005672 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 4.9300000667572021 - theta: -1.83243906988 - accumulated_s: 14.28813885694 -} -adc_trajectory_point { - x: -128.028005427 - y: 351.023190788 - z: -31.3318837518 - - speed: 3.49444437027 - acceleration_s: 0.0935759258599 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 4.940000057220459 - theta: -1.8324763839 - accumulated_s: 14.32308330064 -} -adc_trajectory_point { - x: -128.028005427 - y: 351.023190788 - z: -31.3318837518 - - speed: 3.49722218513 - acceleration_s: 0.0935759258599 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 4.940000057220459 - theta: -1.8324763839 - accumulated_s: 14.35805552244 -} -adc_trajectory_point { - x: -128.046248474 - y: 350.956570532 - z: -31.3317727968 - - speed: 3.49722218513 - acceleration_s: 0.267789469281 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 4.9600000381469727 - theta: -1.83252221827 - accumulated_s: 14.39302774434 -} -adc_trajectory_point { - x: -128.0553701 - y: 350.923208525 - z: -31.3316713916 - - speed: 3.5 - acceleration_s: 0.300834012677 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 4.9700000286102295 - theta: -1.83251562589 - accumulated_s: 14.42802774434 -} -adc_trajectory_point { - x: -128.064498592 - y: 350.889851981 - z: -31.3316573771 - - speed: 3.5 - acceleration_s: 0.300834012677 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 4.9800000190734863 - theta: -1.83254537574 - accumulated_s: 14.46302774434 -} -adc_trajectory_point { - x: -128.073636577 - y: 350.856438601 - z: -31.3316250695 - - speed: 3.50277781487 - acceleration_s: 0.314520331335 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 4.9900000095367432 - theta: -1.8325462399 - accumulated_s: 14.49805552244 -} -adc_trajectory_point { - x: -128.082787373 - y: 350.823041185 - z: -31.3316455074 - - speed: 3.50277781487 - acceleration_s: 0.191534841341 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5 - theta: -1.83257440941 - accumulated_s: 14.53308330064 -} -adc_trajectory_point { - x: -128.091951244 - y: 350.789584174 - z: -31.3315293901 - - speed: 3.5083334446 - acceleration_s: 0.278952635039 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.0099999904632568 - theta: -1.8325975532 - accumulated_s: 14.56816663504 -} -adc_trajectory_point { - x: -128.101075177 - y: 350.756130082 - z: -31.3315945743 - - speed: 3.5083334446 - acceleration_s: 0.191646118787 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.0199999809265137 - theta: -1.83257251866 - accumulated_s: 14.60324996944 -} -adc_trajectory_point { - x: -128.110279538 - y: 350.722644539 - z: -31.3315375568 - - speed: 3.51388883591 - acceleration_s: 0.24373886012 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.0299999713897705 - theta: -1.8326153807 - accumulated_s: 14.638388857839999 -} -adc_trajectory_point { - x: -128.119464702 - y: 350.689158674 - z: -31.3316792473 - - speed: 3.51388883591 - acceleration_s: 0.24373886012 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.0399999618530273 - theta: -1.83261570322 - accumulated_s: 14.673527746240001 -} -adc_trajectory_point { - x: -128.128655979 - y: 350.655615012 - z: -31.3316125404 - - speed: 3.51944446564 - acceleration_s: 0.282552998313 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.0499999523162842 - theta: -1.83260241097 - accumulated_s: 14.70872219084 -} -adc_trajectory_point { - x: -128.137851861 - y: 350.622082697 - z: -31.3317606011 - - speed: 3.51944446564 - acceleration_s: 0.197898992004 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.059999942779541 - theta: -1.83258402011 - accumulated_s: 14.74391663554 -} -adc_trajectory_point { - x: -128.147065919 - y: 350.588508171 - z: -31.3316363096 - - speed: 3.5222222805 - acceleration_s: 0.272153550929 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.0699999332427979 - theta: -1.83255494728 - accumulated_s: 14.779138858340001 -} -adc_trajectory_point { - x: -128.156294813 - y: 350.554938211 - z: -31.3317528339 - - speed: 3.5222222805 - acceleration_s: 0.110982785082 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.0800001621246338 - theta: -1.83258109914 - accumulated_s: 14.81436108114 -} -adc_trajectory_point { - x: -128.165535716 - y: 350.521308584 - z: -31.331666356 - - speed: 3.52500009537 - acceleration_s: 0.297725012227 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.0900001525878906 - theta: -1.83256878867 - accumulated_s: 14.84961108204 -} -adc_trajectory_point { - x: -128.174725033 - y: 350.487702558 - z: -31.3318907274 - - speed: 3.52500009537 - acceleration_s: 0.297725012227 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.1000001430511475 - theta: -1.8325495662 - accumulated_s: 14.88486108304 -} -adc_trajectory_point { - x: -128.183981673 - y: 350.454038662 - z: -31.3317321083 - - speed: 3.52777767181 - acceleration_s: 0.252304635167 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.1100001335144043 - theta: -1.83253365994 - accumulated_s: 14.92013885974 -} -adc_trajectory_point { - x: -128.193227797 - y: 350.420404838 - z: -31.3318322925 - - speed: 3.52777767181 - acceleration_s: 0.0967302183985 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.1200001239776611 - theta: -1.83252496302 - accumulated_s: 14.955416636439999 -} -adc_trajectory_point { - x: -128.202487239 - y: 350.386699526 - z: -31.3316989904 - - speed: 3.53333330154 - acceleration_s: 0.277927346566 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.130000114440918 - theta: -1.83248562268 - accumulated_s: 14.99074996944 -} -adc_trajectory_point { - x: -128.211753702 - y: 350.35303416 - z: -31.3317653527 - - speed: 3.53333330154 - acceleration_s: 0.0591837094689 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.1400001049041748 - theta: -1.8324770861 - accumulated_s: 15.026083302539998 -} -adc_trajectory_point { - x: -128.221040402 - y: 350.319296927 - z: -31.3315984681 - - speed: 3.53888893127 - acceleration_s: 0.0591837094689 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.1500000953674316 - theta: -1.83244599081 - accumulated_s: 15.06147219184 -} -adc_trajectory_point { - x: -128.230326119 - y: 350.285590336 - z: -31.3316497104 - - speed: 3.53888893127 - acceleration_s: 0.116584209373 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.1600000858306885 - theta: -1.83244779888 - accumulated_s: 15.096861081139998 -} -adc_trajectory_point { - x: -128.239626669 - y: 350.251828692 - z: -31.3315357789 - - speed: 3.544444561 - acceleration_s: 0.278030473616 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.1700000762939453 - theta: -1.83241519981 - accumulated_s: 15.132305526740002 -} -adc_trajectory_point { - x: -128.248921672 - y: 350.218048481 - z: -31.3314207131 - - speed: 3.544444561 - acceleration_s: 0.251109438944 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.1800000667572021 - theta: -1.83239257782 - accumulated_s: 15.167749972340001 -} -adc_trajectory_point { - x: -128.258228341 - y: 350.184290043 - z: -31.3312912183 - - speed: 3.55277776718 - acceleration_s: 0.0693685625957 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.190000057220459 - theta: -1.83240719298 - accumulated_s: 15.203277750040002 -} -adc_trajectory_point { - x: -128.258228341 - y: 350.184290043 - z: -31.3312912183 - - speed: 3.55277776718 - acceleration_s: 0.0693685625957 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.190000057220459 - theta: -1.83240719298 - accumulated_s: 15.23880552764 -} -adc_trajectory_point { - x: -128.276844285 - y: 350.116681007 - z: -31.3311293265 - - speed: 3.55833339691 - acceleration_s: 0.171843816258 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.2100000381469727 - theta: -1.83241144526 - accumulated_s: 15.274388861639999 -} -adc_trajectory_point { - x: -128.286184325 - y: 350.082838437 - z: -31.3308680477 - - speed: 3.55833339691 - acceleration_s: 0.252683910327 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.2200000286102295 - theta: -1.83242163866 - accumulated_s: 15.30997219564 -} -adc_trajectory_point { - x: -128.295507588 - y: 350.048981868 - z: -31.3308513397 - - speed: 3.56388878822 - acceleration_s: 0.226768789061 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.2300000190734863 - theta: -1.83243355955 - accumulated_s: 15.34561108354 -} -adc_trajectory_point { - x: -128.304856069 - y: 350.01507061 - z: -31.3306626277 - - speed: 3.56388878822 - acceleration_s: 0.358421376831 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.2400000095367432 - theta: -1.83246714706 - accumulated_s: 15.381249971439999 -} -adc_trajectory_point { - x: -128.314177374 - y: 349.981168523 - z: -31.3305751467 - - speed: 3.56666660309 - acceleration_s: 0.130028481229 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.25 - theta: -1.83248746453 - accumulated_s: 15.41691663744 -} -adc_trajectory_point { - x: -128.323523061 - y: 349.947221703 - z: -31.3304684926 - - speed: 3.56666660309 - acceleration_s: 0.270673775212 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.2599999904632568 - theta: -1.83250387909 - accumulated_s: 15.45258330344 -} -adc_trajectory_point { - x: -128.332869921 - y: 349.913273211 - z: -31.3304520212 - - speed: 3.57222223282 - acceleration_s: 0.223202365437 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.2699999809265137 - theta: -1.83253571663 - accumulated_s: 15.48830552574 -} -adc_trajectory_point { - x: -128.342196025 - y: 349.879284826 - z: -31.3302414361 - - speed: 3.57222223282 - acceleration_s: 0.203264498641 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.2799999713897705 - theta: -1.83251360385 - accumulated_s: 15.52402774814 -} -adc_trajectory_point { - x: -128.35158589 - y: 349.845269713 - z: -31.3300502952 - - speed: 3.57777786255 - acceleration_s: 0.290100372709 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.2899999618530273 - theta: -1.83255322038 - accumulated_s: 15.55980552674 -} -adc_trajectory_point { - x: -128.36088326 - y: 349.811245014 - z: -31.3299333937 - - speed: 3.57777786255 - acceleration_s: 0.290100372709 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.2999999523162842 - theta: -1.83250645039 - accumulated_s: 15.59558330534 -} -adc_trajectory_point { - x: -128.370264566 - y: 349.777203763 - z: -31.3298768196 - - speed: 3.57777786255 - acceleration_s: 0.270945996076 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.309999942779541 - theta: -1.83260130435 - accumulated_s: 15.63136108394 -} -adc_trajectory_point { - x: -128.379618839 - y: 349.743159154 - z: -31.3297989694 - - speed: 3.57777786255 - acceleration_s: 0.135216470502 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.3199999332427979 - theta: -1.83264110082 - accumulated_s: 15.667138862640002 -} -adc_trajectory_point { - x: -128.38898418 - y: 349.709078116 - z: -31.3294439595 - - speed: 3.58333325386 - acceleration_s: 0.158682610034 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.3300001621246338 - theta: -1.83265476587 - accumulated_s: 15.70297219514 -} -adc_trajectory_point { - x: -128.398356682 - y: 349.674983551 - z: -31.3292951919 - - speed: 3.58333325386 - acceleration_s: 0.247491454149 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.3400001525878906 - theta: -1.83267354789 - accumulated_s: 15.73880552764 -} -adc_trajectory_point { - x: -128.407741547 - y: 349.64085883 - z: -31.3290389087 - - speed: 3.58888888359 - acceleration_s: 0.257360962182 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.3500001430511475 - theta: -1.83269688785 - accumulated_s: 15.774694416540001 -} -adc_trajectory_point { - x: -128.417126691 - y: 349.606716634 - z: -31.3288660683 - - speed: 3.58888888359 - acceleration_s: 0.252492361769 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.3600001335144043 - theta: -1.83273828427 - accumulated_s: 15.81058330534 -} -adc_trajectory_point { - x: -128.426512813 - y: 349.572536216 - z: -31.328538863 - - speed: 3.59166669846 - acceleration_s: 0.270461365569 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.3700001239776611 - theta: -1.83272536053 - accumulated_s: 15.846499972339998 -} -adc_trajectory_point { - x: -128.435929135 - y: 349.538388079 - z: -31.3283021813 - - speed: 3.59166669846 - acceleration_s: 0.0745257854394 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.380000114440918 - theta: -1.83276970424 - accumulated_s: 15.88241663934 -} -adc_trajectory_point { - x: -128.445327148 - y: 349.504209446 - z: -31.3279309906 - - speed: 3.59166669846 - acceleration_s: 0.14209022716 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.3900001049041748 - theta: -1.83277794851 - accumulated_s: 15.91833330634 -} -adc_trajectory_point { - x: -128.445327148 - y: 349.504209446 - z: -31.3279309906 - - speed: 3.59166669846 - acceleration_s: 0.14209022716 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.3900001049041748 - theta: -1.83277794851 - accumulated_s: 15.954249973340001 -} -adc_trajectory_point { - x: -128.464161002 - y: 349.435832216 - z: -31.3273048056 - - speed: 3.59166669846 - acceleration_s: 0.182318692509 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.4100000858306885 - theta: -1.83284020618 - accumulated_s: 15.990166640239998 -} -adc_trajectory_point { - x: -128.473580038 - y: 349.401608023 - z: -31.3269274253 - - speed: 3.59166669846 - acceleration_s: 0.186614034787 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.4200000762939453 - theta: -1.83285290131 - accumulated_s: 16.02608330724 -} -adc_trajectory_point { - x: -128.483028135 - y: 349.367368334 - z: -31.3265979541 - - speed: 3.59166669846 - acceleration_s: 0.256491736264 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.4300000667572021 - theta: -1.83288330014 - accumulated_s: 16.06199997424 -} -adc_trajectory_point { - x: -128.492464849 - y: 349.33311293 - z: -31.3262703242 - - speed: 3.59166669846 - acceleration_s: 0.193695838626 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.440000057220459 - theta: -1.8328975954 - accumulated_s: 16.09791664124 -} -adc_trajectory_point { - x: -128.492464849 - y: 349.33311293 - z: -31.3262703242 - - speed: 3.59444451332 - acceleration_s: 0.193695838626 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.440000057220459 - theta: -1.8328975954 - accumulated_s: 16.13386108634 -} -adc_trajectory_point { - x: -128.50190389 - y: 349.298837083 - z: -31.3259477625 - - speed: 3.59444451332 - acceleration_s: 0.155372344536 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.4500000476837158 - theta: -1.832898318 - accumulated_s: 16.16980553154 -} -adc_trajectory_point { - x: -128.520810944 - y: 349.230235123 - z: -31.3252398837 - - speed: 3.59444451332 - acceleration_s: 0.112043222129 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.4700000286102295 - theta: -1.83294695796 - accumulated_s: 16.20574997664 -} -adc_trajectory_point { - x: -128.530256259 - y: 349.195893834 - z: -31.3248800915 - - speed: 3.59444451332 - acceleration_s: 0.222878830587 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.4800000190734863 - theta: -1.83292248995 - accumulated_s: 16.24169442174 -} -adc_trajectory_point { - x: -128.539725901 - y: 349.161573111 - z: -31.3246459132 - - speed: 3.59722232819 - acceleration_s: 0.120873011999 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.4900000095367432 - theta: -1.83298261698 - accumulated_s: 16.27766664504 -} -adc_trajectory_point { - x: -128.549184134 - y: 349.12720088 - z: -31.3242900204 - - speed: 3.59722232819 - acceleration_s: 0.120873011999 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.5 - theta: -1.83300233614 - accumulated_s: 16.31363886834 -} -adc_trajectory_point { - x: -128.558619875 - y: 349.092842303 - z: -31.3240769766 - - speed: 3.59999990463 - acceleration_s: 0.0899515923125 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.5099999904632568 - theta: -1.83300530132 - accumulated_s: 16.34963886734 -} -adc_trajectory_point { - x: -128.568065056 - y: 349.05845142 - z: -31.3237765981 - - speed: 3.59999990463 - acceleration_s: 0.133486449623 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 5.5199999809265137 - theta: -1.83300882946 - accumulated_s: 16.38563886644 -} -adc_trajectory_point { - x: -128.57752828 - y: 349.024049204 - z: -31.3234935207 - - speed: 3.60555553436 - acceleration_s: 0.133486449623 - curvature: 0.000382747802778 - curvature_change_rate: -0.00106155097655 - relative_time: 5.5299999713897705 - theta: -1.83304047453 - accumulated_s: 16.42169442174 -} -adc_trajectory_point { - x: -128.586962949 - y: 348.989640534 - z: -31.3232645057 - - speed: 3.60555553436 - acceleration_s: 0.161516872723 - curvature: 0.000382747802778 - curvature_change_rate: 0 - relative_time: 5.5399999618530273 - theta: -1.8330598369 - accumulated_s: 16.45774997714 -} -adc_trajectory_point { - x: -128.586962949 - y: 348.989640534 - z: -31.3232645057 - - speed: 3.60833334923 - acceleration_s: 0.161516872723 - curvature: 0.000382747802778 - curvature_change_rate: 0 - relative_time: 5.5399999618530273 - theta: -1.8330598369 - accumulated_s: 16.49383331064 -} -adc_trajectory_point { - x: -128.60579751 - y: 348.920744031 - z: -31.3229042711 - - speed: 3.60833334923 - acceleration_s: 0.0788558856532 - curvature: 0.000382747802778 - curvature_change_rate: 0 - relative_time: 5.559999942779541 - theta: -1.83306868542 - accumulated_s: 16.52991664414 -} -adc_trajectory_point { - x: -128.615225254 - y: 348.886270789 - z: -31.322625909 - - speed: 3.61111116409 - acceleration_s: 0.140590028968 - curvature: 0.000382747802778 - curvature_change_rate: 0 - relative_time: 5.5699999332427979 - theta: -1.83309581878 - accumulated_s: 16.56602775574 -} -adc_trajectory_point { - x: -128.624648865 - y: 348.851799461 - z: -31.3225083668 - - speed: 3.61111116409 - acceleration_s: 0.108884639798 - curvature: 0.000382747802778 - curvature_change_rate: 0 - relative_time: 5.5800001621246338 - theta: -1.83316790317 - accumulated_s: 16.60213886734 -} -adc_trajectory_point { - x: -128.63400663 - y: 348.817254923 - z: -31.3223352255 - - speed: 3.61388897896 - acceleration_s: 0.267570724127 - curvature: 0.000344473001902 - curvature_change_rate: -0.00105910284182 - relative_time: 5.5900001525878906 - theta: -1.833142604 - accumulated_s: 16.63827775714 -} -adc_trajectory_point { - x: -128.643438154 - y: 348.782758455 - z: -31.3224043744 - - speed: 3.61388897896 - acceleration_s: 0.267570724127 - curvature: 0.000344473001902 - curvature_change_rate: 0 - relative_time: 5.6000001430511475 - theta: -1.83321108238 - accumulated_s: 16.67441664694 -} -adc_trajectory_point { - x: -128.652846624 - y: 348.748181911 - z: -31.3223548932 - - speed: 3.61944437027 - acceleration_s: 0.244506235761 - curvature: 0.000344473001902 - curvature_change_rate: 0 - relative_time: 5.6100001335144043 - theta: -1.83324851316 - accumulated_s: 16.71061109064 -} -adc_trajectory_point { - x: -128.662263863 - y: 348.713605837 - z: -31.3224831503 - - speed: 3.61944437027 - acceleration_s: 0.268928460073 - curvature: 0.000344473001902 - curvature_change_rate: 0 - relative_time: 5.6200001239776611 - theta: -1.83326296881 - accumulated_s: 16.74680553434 -} -adc_trajectory_point { - x: -128.671698662 - y: 348.679020583 - z: -31.3223722065 - - speed: 3.62222218513 - acceleration_s: 0.0920260062903 - curvature: 0.000306198182417 - curvature_change_rate: -0.0010566668064 - relative_time: 5.630000114440918 - theta: -1.83326929087 - accumulated_s: 16.78302775624 -} -adc_trajectory_point { - x: -128.681123508 - y: 348.64439284 - z: -31.3223687503 - - speed: 3.62222218513 - acceleration_s: 0.181258060653 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.6400001049041748 - theta: -1.83324653406 - accumulated_s: 16.81924997804 -} -adc_trajectory_point { - x: -128.690588488 - y: 348.609798131 - z: -31.3223931799 - - speed: 3.625 - acceleration_s: 0.0756049361894 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.6500000953674316 - theta: -1.83326931385 - accumulated_s: 16.85549997804 -} -adc_trajectory_point { - x: -128.700010708 - y: 348.575180874 - z: -31.3224781249 - - speed: 3.625 - acceleration_s: 0.0695705007903 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.6600000858306885 - theta: -1.83324714793 - accumulated_s: 16.89174997804 -} -adc_trajectory_point { - x: -128.709466647 - y: 348.540562228 - z: -31.322558241 - - speed: 3.62777781487 - acceleration_s: 0.12094733008 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.6700000762939453 - theta: -1.83324677267 - accumulated_s: 16.92802775624 -} -adc_trajectory_point { - x: -128.718943556 - y: 348.50592714 - z: -31.3225481119 - - speed: 3.62777781487 - acceleration_s: 0.0852303491131 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.6800000667572021 - theta: -1.83327378221 - accumulated_s: 16.96430553434 -} -adc_trajectory_point { - x: -128.728403355 - y: 348.471275138 - z: -31.3226837125 - - speed: 3.6333334446 - acceleration_s: 0.174760376493 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.690000057220459 - theta: -1.83325703247 - accumulated_s: 17.00063886884 -} -adc_trajectory_point { - x: -128.728403355 - y: 348.471275138 - z: -31.3226837125 - - speed: 3.6333334446 - acceleration_s: 0.174760376493 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.690000057220459 - theta: -1.83325703247 - accumulated_s: 17.03697220324 -} -adc_trajectory_point { - x: -128.747422586 - y: 348.40193836 - z: -31.3225899553 - - speed: 3.63611102104 - acceleration_s: 0.152009968214 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.7100000381469727 - theta: -1.83330329738 - accumulated_s: 17.07333331344 -} -adc_trajectory_point { - x: -128.756907795 - y: 348.367262238 - z: -31.3225059584 - - speed: 3.63611102104 - acceleration_s: 0.064294085383 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.7200000286102295 - theta: -1.83330186521 - accumulated_s: 17.10969442364 -} -adc_trajectory_point { - x: -128.766423463 - y: 348.332610435 - z: -31.3225499941 - - speed: 3.63888883591 - acceleration_s: -0.00213218683621 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.7300000190734863 - theta: -1.83335389482 - accumulated_s: 17.14608331204 -} -adc_trajectory_point { - x: -128.775925212 - y: 348.297941251 - z: -31.3223879905 - - speed: 3.63888883591 - acceleration_s: -0.0206811253025 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.7400000095367432 - theta: -1.83337620271 - accumulated_s: 17.18247220044 -} -adc_trajectory_point { - x: -128.775925212 - y: 348.297941251 - z: -31.3223879905 - - speed: 3.64444446564 - acceleration_s: -0.0206811253025 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.7400000095367432 - theta: -1.83337620271 - accumulated_s: 17.21891664504 -} -adc_trajectory_point { - x: -128.794884444 - y: 348.228594425 - z: -31.3221440855 - - speed: 3.64444446564 - acceleration_s: 0.0664189717464 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.7599999904632568 - theta: -1.83340947483 - accumulated_s: 17.25536108974 -} -adc_trajectory_point { - x: -128.80435476 - y: 348.193421867 - z: -31.3222793574 - - speed: 3.6472222805 - acceleration_s: -0.010451624836 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.7699999809265137 - theta: -1.8333847907 - accumulated_s: 17.29183331254 -} -adc_trajectory_point { - x: -128.813877908 - y: 348.158109563 - z: -31.3220262099 - - speed: 3.6472222805 - acceleration_s: 0.116941144297 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.7799999713897705 - theta: -1.83340538993 - accumulated_s: 17.32830553534 -} -adc_trajectory_point { - x: -128.823362703 - y: 348.122826438 - z: -31.3219631752 - - speed: 3.65000009537 - acceleration_s: -0.0559222445909 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.7899999618530273 - theta: -1.83342351629 - accumulated_s: 17.36480553624 -} -adc_trajectory_point { - x: -128.832914021 - y: 348.087507412 - z: -31.3216921715 - - speed: 3.65000009537 - acceleration_s: -0.0559222445909 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.7999999523162842 - theta: -1.83350584857 - accumulated_s: 17.40130553724 -} -adc_trajectory_point { - x: -128.842405713 - y: 348.052218361 - z: -31.3216255363 - - speed: 3.65555548668 - acceleration_s: -0.0521618486926 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.809999942779541 - theta: -1.83355365372 - accumulated_s: 17.43786109214 -} -adc_trajectory_point { - x: -128.851915135 - y: 348.016897349 - z: -31.3213174194 - - speed: 3.65555548668 - acceleration_s: 0.0526837508852 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.8199999332427979 - theta: -1.83360922393 - accumulated_s: 17.47441664694 -} -adc_trajectory_point { - x: -128.861414637 - y: 347.981596382 - z: -31.3211349919 - - speed: 3.65833330154 - acceleration_s: -0.0406594875565 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.8300001621246338 - theta: -1.8336526204 - accumulated_s: 17.51099997994 -} -adc_trajectory_point { - x: -128.870914301 - y: 347.946283142 - z: -31.320840802 - - speed: 3.65833330154 - acceleration_s: 0.0116797323649 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.8400001525878906 - theta: -1.83369876334 - accumulated_s: 17.54758331304 -} -adc_trajectory_point { - x: -128.880418295 - y: 347.910989636 - z: -31.3206666745 - - speed: 3.65833330154 - acceleration_s: -0.0861593151846 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.8500001430511475 - theta: -1.83373288708 - accumulated_s: 17.58416664604 -} -adc_trajectory_point { - x: -128.889907116 - y: 347.875693631 - z: -31.3203567239 - - speed: 3.65833330154 - acceleration_s: -0.00489268748598 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.8600001335144043 - theta: -1.83375240354 - accumulated_s: 17.62074997904 -} -adc_trajectory_point { - x: -128.899410634 - y: 347.840401963 - z: -31.320089044 - - speed: 3.66111111641 - acceleration_s: -0.0935783389757 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.8700001239776611 - theta: -1.83378538875 - accumulated_s: 17.65736109014 -} -adc_trajectory_point { - x: -128.908926725 - y: 347.805111515 - z: -31.3197257882 - - speed: 3.66111111641 - acceleration_s: -0.00380495882305 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.880000114440918 - theta: -1.8338147345 - accumulated_s: 17.69397220134 -} -adc_trajectory_point { - x: -128.918434719 - y: 347.769833174 - z: -31.3194898563 - - speed: 3.65833330154 - acceleration_s: -0.024698227929 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.8900001049041748 - theta: -1.83381612764 - accumulated_s: 17.73055553434 -} -adc_trajectory_point { - x: -128.918434719 - y: 347.769833174 - z: -31.3194898563 - - speed: 3.65833330154 - acceleration_s: -0.024698227929 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.8900001049041748 - theta: -1.83381612764 - accumulated_s: 17.76713886734 -} -adc_trajectory_point { - x: -128.937535935 - y: 347.699291058 - z: -31.3188980063 - - speed: 3.65555548668 - acceleration_s: 0.0180014027825 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.9100000858306885 - theta: -1.83388981528 - accumulated_s: 17.80369442224 -} -adc_trajectory_point { - x: -128.947072595 - y: 347.664025092 - z: -31.3186933706 - - speed: 3.65555548668 - acceleration_s: -0.03026701293 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.9200000762939453 - theta: -1.83388177205 - accumulated_s: 17.84024997714 -} -adc_trajectory_point { - x: -128.956668694 - y: 347.628740485 - z: -31.3183895247 - - speed: 3.65555548668 - acceleration_s: 0.10998179492 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.9300000667572021 - theta: -1.83392784622 - accumulated_s: 17.87680553194 -} -adc_trajectory_point { - x: -128.966223331 - y: 347.593491841 - z: -31.3182755476 - - speed: 3.65555548668 - acceleration_s: -0.0843506970322 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.940000057220459 - theta: -1.83391813803 - accumulated_s: 17.91336108684 -} -adc_trajectory_point { - x: -128.966223331 - y: 347.593491841 - z: -31.3182755476 - - speed: 3.65555548668 - acceleration_s: -0.0843506970322 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.940000057220459 - theta: -1.83391813803 - accumulated_s: 17.94991664174 -} -adc_trajectory_point { - x: -128.985374137 - y: 347.522983376 - z: -31.3178532086 - - speed: 3.65555548668 - acceleration_s: -0.166950694257 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.9600000381469727 - theta: -1.83398346852 - accumulated_s: 17.98647219654 -} -adc_trajectory_point { - x: -128.994965177 - y: 347.487720583 - z: -31.3176200092 - - speed: 3.65555548668 - acceleration_s: -0.0204511831544 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.9700000286102295 - theta: -1.83403976228 - accumulated_s: 18.02302775144 -} -adc_trajectory_point { - x: -129.004474712 - y: 347.452464119 - z: -31.3176097563 - - speed: 3.65555548668 - acceleration_s: -0.0320633572315 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.9800000190734863 - theta: -1.83403677768 - accumulated_s: 18.05958330634 -} -adc_trajectory_point { - x: -129.013974239 - y: 347.41719439 - z: -31.3173825247 - - speed: 3.65555548668 - acceleration_s: -0.0599299942827 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 5.9900000095367432 - theta: -1.83402678259 - accumulated_s: 18.09613886114 -} -adc_trajectory_point { - x: -129.023503848 - y: 347.381925744 - z: -31.3173442446 - - speed: 3.65555548668 - acceleration_s: 0.046905108494 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6 - theta: -1.83408365707 - accumulated_s: 18.13269441604 -} -adc_trajectory_point { - x: -129.032967857 - y: 347.346680499 - z: -31.3172769025 - - speed: 3.65277767181 - acceleration_s: -0.0940034228063 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.0099999904632568 - theta: -1.83411593178 - accumulated_s: 18.16922219274 -} -adc_trajectory_point { - x: -129.042459873 - y: 347.311387587 - z: -31.3172792448 - - speed: 3.65277767181 - acceleration_s: -0.00645543837631 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.0199999809265137 - theta: -1.83414534893 - accumulated_s: 18.20574996944 -} -adc_trajectory_point { - x: -129.051890313 - y: 347.276123018 - z: -31.3172597084 - - speed: 3.65277767181 - acceleration_s: -0.116689519955 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.0299999713897705 - theta: -1.83415775234 - accumulated_s: 18.24227774624 -} -adc_trajectory_point { - x: -129.061341013 - y: 347.240850585 - z: -31.317135131 - - speed: 3.65277767181 - acceleration_s: -0.0758492513875 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.0399999618530273 - theta: -1.83417909744 - accumulated_s: 18.27880552294 -} -adc_trajectory_point { - x: -129.070799785 - y: 347.20560676 - z: -31.3171576904 - - speed: 3.65277767181 - acceleration_s: -0.0758492513875 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.0499999523162842 - theta: -1.83422177769 - accumulated_s: 18.31533329964 -} -adc_trajectory_point { - x: -129.080239181 - y: 347.170351132 - z: -31.3171366313 - - speed: 3.65277767181 - acceleration_s: -0.0493748088374 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.059999942779541 - theta: -1.83423459994 - accumulated_s: 18.35186107634 -} -adc_trajectory_point { - x: -129.089707704 - y: 347.135114686 - z: -31.3172168136 - - speed: 3.65277767181 - acceleration_s: -0.0393327362459 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.0699999332427979 - theta: -1.83426627105 - accumulated_s: 18.38838885304 -} -adc_trajectory_point { - x: -129.099169334 - y: 347.099885947 - z: -31.3171445988 - - speed: 3.65277767181 - acceleration_s: -0.111501511766 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.0800001621246338 - theta: -1.83428312571 - accumulated_s: 18.42491662984 -} -adc_trajectory_point { - x: -129.099169334 - y: 347.099885947 - z: -31.3171445988 - - speed: 3.65555548668 - acceleration_s: -0.111501511766 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.0800001621246338 - theta: -1.83428312571 - accumulated_s: 18.46147218464 -} -adc_trajectory_point { - x: -129.118160491 - y: 347.029486236 - z: -31.3170640124 - - speed: 3.65555548668 - acceleration_s: -0.121724568634 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.1000001430511475 - theta: -1.83429098538 - accumulated_s: 18.49802773954 -} -adc_trajectory_point { - x: -129.127653655 - y: 346.994317179 - z: -31.3171625827 - - speed: 3.65555548668 - acceleration_s: -0.0777160575482 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.1100001335144043 - theta: -1.8342636569 - accumulated_s: 18.53458329444 -} -adc_trajectory_point { - x: -129.137223893 - y: 346.959146591 - z: -31.3170938743 - - speed: 3.65555548668 - acceleration_s: -0.0415945226229 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.1200001239776611 - theta: -1.83429679067 - accumulated_s: 18.57113884924 -} -adc_trajectory_point { - x: -129.146768627 - y: 346.923996494 - z: -31.3171985019 - - speed: 3.65833330154 - acceleration_s: -0.067983565307 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.130000114440918 - theta: -1.83428711919 - accumulated_s: 18.60772218224 -} -adc_trajectory_point { - x: -129.15633304 - y: 346.888835191 - z: -31.3170995079 - - speed: 3.65833330154 - acceleration_s: -0.0289771275254 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.1400001049041748 - theta: -1.83425172795 - accumulated_s: 18.64430551534 -} -adc_trajectory_point { - x: -129.165939199 - y: 346.853721589 - z: -31.317190879 - - speed: 3.65833330154 - acceleration_s: -0.154710205289 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.1500000953674316 - theta: -1.83428649298 - accumulated_s: 18.68088884834 -} -adc_trajectory_point { - x: -129.175521357 - y: 346.818567896 - z: -31.317110558 - - speed: 3.65833330154 - acceleration_s: 0.0080517503164 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.1600000858306885 - theta: -1.83426406695 - accumulated_s: 18.71747218134 -} -adc_trajectory_point { - x: -129.185120789 - y: 346.783470788 - z: -31.3172390172 - - speed: 3.65555548668 - acceleration_s: -0.173907420916 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.1700000762939453 - theta: -1.83427122892 - accumulated_s: 18.75402773614 -} -adc_trajectory_point { - x: -129.194717279 - y: 346.748338709 - z: -31.3171520624 - - speed: 3.65555548668 - acceleration_s: -0.0136844627285 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.1800000667572021 - theta: -1.83425937592 - accumulated_s: 18.79058329104 -} -adc_trajectory_point { - x: -129.204289177 - y: 346.713234305 - z: -31.3172889994 - - speed: 3.65555548668 - acceleration_s: -0.0766979134373 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.190000057220459 - theta: -1.8342377925 - accumulated_s: 18.82713884594 -} -adc_trajectory_point { - x: -129.204289177 - y: 346.713234305 - z: -31.3172889994 - - speed: 3.65555548668 - acceleration_s: -0.0766979134373 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.190000057220459 - theta: -1.8342377925 - accumulated_s: 18.86369440084 -} -adc_trajectory_point { - x: -129.22347362 - y: 346.643051338 - z: -31.3173899129 - - speed: 3.65555548668 - acceleration_s: -0.0928290252008 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.2100000381469727 - theta: -1.83427336071 - accumulated_s: 18.90024995564 -} -adc_trajectory_point { - x: -129.233027734 - y: 346.607958597 - z: -31.3174155634 - - speed: 3.65555548668 - acceleration_s: -0.0608976298893 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.2200000286102295 - theta: -1.83427157498 - accumulated_s: 18.93680551054 -} -adc_trajectory_point { - x: -129.24257554 - y: 346.572877518 - z: -31.3175391993 - - speed: 3.65555548668 - acceleration_s: -0.0807961446278 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.2300000190734863 - theta: -1.83426821445 - accumulated_s: 18.97336106544 -} -adc_trajectory_point { - x: -129.24257554 - y: 346.572877518 - z: -31.3175391993 - - speed: 3.65277767181 - acceleration_s: -0.0807961446278 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.2300000190734863 - theta: -1.83426821445 - accumulated_s: 19.00988884214 -} -adc_trajectory_point { - x: -129.261661659 - y: 346.502707847 - z: -31.3178131804 - - speed: 3.65000009537 - acceleration_s: 0.0277393465352 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.25 - theta: -1.83432744281 - accumulated_s: 19.04638884304 -} -adc_trajectory_point { - x: -129.27116566 - y: 346.467611702 - z: -31.3180493098 - - speed: 3.65000009537 - acceleration_s: 0.0201547352708 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.2599999904632568 - theta: -1.83433005243 - accumulated_s: 19.08288884404 -} -adc_trajectory_point { - x: -129.28069172 - y: 346.432518376 - z: -31.3181998422 - - speed: 3.6472222805 - acceleration_s: -3.78345936202e-05 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.2699999809265137 - theta: -1.83436799068 - accumulated_s: 19.11936106684 -} -adc_trajectory_point { - x: -129.290214216 - y: 346.397426349 - z: -31.3184478153 - - speed: 3.6472222805 - acceleration_s: 0.0270069061289 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.2799999713897705 - theta: -1.83440787542 - accumulated_s: 19.15583328964 -} -adc_trajectory_point { - x: -129.299697771 - y: 346.36232914 - z: -31.3187334156 - - speed: 3.6472222805 - acceleration_s: -0.0223318928808 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.2899999618530273 - theta: -1.83441522696 - accumulated_s: 19.19230551244 -} -adc_trajectory_point { - x: -129.30921575 - y: 346.327241022 - z: -31.3190805996 - - speed: 3.6472222805 - acceleration_s: -0.0223318928808 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.2999999523162842 - theta: -1.83447799964 - accumulated_s: 19.22877773524 -} -adc_trajectory_point { - x: -129.31870989 - y: 346.292146098 - z: -31.3193545844 - - speed: 3.6472222805 - acceleration_s: -0.0226427361261 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.309999942779541 - theta: -1.83451173078 - accumulated_s: 19.26524995804 -} -adc_trajectory_point { - x: -129.328200009 - y: 346.257048146 - z: -31.319717533 - - speed: 3.6472222805 - acceleration_s: 0.0168420478447 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.3199999332427979 - theta: -1.83454723527 - accumulated_s: 19.30172218084 -} -adc_trajectory_point { - x: -129.337699279 - y: 346.221964525 - z: -31.3200687738 - - speed: 3.6472222805 - acceleration_s: 0.0134572723884 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.3300001621246338 - theta: -1.83459977678 - accumulated_s: 19.33819440364 -} -adc_trajectory_point { - x: -129.347183501 - y: 346.186866407 - z: -31.3205622882 - - speed: 3.6472222805 - acceleration_s: -0.0429886752916 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.3400001525878906 - theta: -1.83462852659 - accumulated_s: 19.37466662644 -} -adc_trajectory_point { - x: -129.356636595 - y: 346.151760793 - z: -31.3209341029 - - speed: 3.65000009537 - acceleration_s: -0.0429886752916 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.3500001430511475 - theta: -1.83464524903 - accumulated_s: 19.41116662744 -} -adc_trajectory_point { - x: -129.366116578 - y: 346.116670792 - z: -31.3213783717 - - speed: 3.65000009537 - acceleration_s: -0.0344350005933 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.3600001335144043 - theta: -1.8346970933 - accumulated_s: 19.44766662834 -} -adc_trajectory_point { - x: -129.375580078 - y: 346.081570938 - z: -31.3217631578 - - speed: 3.65277767181 - acceleration_s: -0.0155522188036 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.3700001239776611 - theta: -1.83473265181 - accumulated_s: 19.48419440504 -} -adc_trajectory_point { - x: -129.385038758 - y: 346.046469238 - z: -31.3222754272 - - speed: 3.65277767181 - acceleration_s: 0.00546380045835 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.380000114440918 - theta: -1.83476715968 - accumulated_s: 19.52072218184 -} -adc_trajectory_point { - x: -129.394471084 - y: 346.011374456 - z: -31.3226575432 - - speed: 3.65277767181 - acceleration_s: -0.0777018669801 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.3900001049041748 - theta: -1.83479002852 - accumulated_s: 19.55724995854 -} -adc_trajectory_point { - x: -129.394471084 - y: 346.011374456 - z: -31.3226575432 - - speed: 3.65277767181 - acceleration_s: -0.0777018669801 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.3900001049041748 - theta: -1.83479002852 - accumulated_s: 19.59377773524 -} -adc_trajectory_point { - x: -129.413317017 - y: 345.941201373 - z: -31.323369341 - - speed: 3.65277767181 - acceleration_s: -0.0862688680924 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.4100000858306885 - theta: -1.83485060831 - accumulated_s: 19.63030551194 -} -adc_trajectory_point { - x: -129.422707584 - y: 345.906143231 - z: -31.3237910457 - - speed: 3.65277767181 - acceleration_s: -0.180415417519 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.4200000762939453 - theta: -1.83485909853 - accumulated_s: 19.66683328864 -} -adc_trajectory_point { - x: -129.432143564 - y: 345.871078195 - z: -31.3240548242 - - speed: 3.65277767181 - acceleration_s: 0.0094313715807 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.4300000667572021 - theta: -1.8348882783 - accumulated_s: 19.70336106544 -} -adc_trajectory_point { - x: -129.441548011 - y: 345.836032091 - z: -31.3244027384 - - speed: 3.65277767181 - acceleration_s: -0.121457069227 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.440000057220459 - theta: -1.8349131293 - accumulated_s: 19.73988884214 -} -adc_trajectory_point { - x: -129.441548011 - y: 345.836032091 - z: -31.3244027384 - - speed: 3.6472222805 - acceleration_s: -0.121457069227 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.440000057220459 - theta: -1.8349131293 - accumulated_s: 19.77636106494 -} -adc_trajectory_point { - x: -129.460422038 - y: 345.765960823 - z: -31.3248903314 - - speed: 3.6472222805 - acceleration_s: -0.0917973651491 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.4600000381469727 - theta: -1.83494818864 - accumulated_s: 19.81283328774 -} -adc_trajectory_point { - x: -129.469852748 - y: 345.730945114 - z: -31.3251484316 - - speed: 3.65277767181 - acceleration_s: -0.0846483845587 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.4700000286102295 - theta: -1.83495723802 - accumulated_s: 19.84936106444 -} -adc_trajectory_point { - x: -129.479317847 - y: 345.69594344 - z: -31.3253113199 - - speed: 3.65277767181 - acceleration_s: -0.0746387294766 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.4800000190734863 - theta: -1.83496375991 - accumulated_s: 19.88588884114 -} -adc_trajectory_point { - x: -129.488778186 - y: 345.660933118 - z: -31.3255431205 - - speed: 3.65277767181 - acceleration_s: -0.0300390884564 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.4900000095367432 - theta: -1.8349934192 - accumulated_s: 19.92241661784 -} -adc_trajectory_point { - x: -129.498214949 - y: 345.625922892 - z: -31.3257153593 - - speed: 3.65277767181 - acceleration_s: -0.0185303335792 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.5 - theta: -1.83494739731 - accumulated_s: 19.95894439464 -} -adc_trajectory_point { - x: -129.507687542 - y: 345.590936906 - z: -31.3258919828 - - speed: 3.6472222805 - acceleration_s: -0.0500041541476 - curvature: 0.000344473001902 - curvature_change_rate: 0.00104942382287 - relative_time: 6.5099999904632568 - theta: -1.83497135339 - accumulated_s: 19.99541661744 -} -adc_trajectory_point { - x: -129.517164619 - y: 345.555963603 - z: -31.3259384055 - - speed: 3.6472222805 - acceleration_s: -0.100189193698 - curvature: 0.000344473001902 - curvature_change_rate: 0 - relative_time: 6.5199999809265137 - theta: -1.83498922676 - accumulated_s: 20.03188884024 -} -adc_trajectory_point { - x: -129.526626922 - y: 345.52100996 - z: -31.3260490689 - - speed: 3.64444446564 - acceleration_s: -0.124155160463 - curvature: 0.000306198182417 - curvature_change_rate: -0.00105022369926 - relative_time: 6.5299999713897705 - theta: -1.83499340889 - accumulated_s: 20.06833328484 -} -adc_trajectory_point { - x: -129.536081936 - y: 345.486043899 - z: -31.3260735376 - - speed: 3.64444446564 - acceleration_s: -0.0670091040972 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.5399999618530273 - theta: -1.83499570125 - accumulated_s: 20.10477772954 -} -adc_trajectory_point { - x: -129.545535788 - y: 345.451094071 - z: -31.3261832111 - - speed: 3.64166665077 - acceleration_s: -0.0408489272938 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.5499999523162842 - theta: -1.83501733108 - accumulated_s: 20.14119439604 -} -adc_trajectory_point { - x: -129.554993532 - y: 345.41615812 - z: -31.3260969017 - - speed: 3.64166665077 - acceleration_s: -0.132184730869 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.559999942779541 - theta: -1.83503692337 - accumulated_s: 20.17761106254 -} -adc_trajectory_point { - x: -129.564437439 - y: 345.381213626 - z: -31.3260549838 - - speed: 3.63888883591 - acceleration_s: -0.0357402259984 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.5699999332427979 - theta: -1.83502961453 - accumulated_s: 20.21399995084 -} -adc_trajectory_point { - x: -129.573875596 - y: 345.346308868 - z: -31.3259546869 - - speed: 3.63888883591 - acceleration_s: -0.179218478733 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.5800001621246338 - theta: -1.83505595463 - accumulated_s: 20.25038883924 -} -adc_trajectory_point { - x: -129.583295079 - y: 345.311400863 - z: -31.3258660883 - - speed: 3.63611102104 - acceleration_s: -0.14104756078 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.5900001525878906 - theta: -1.83504353384 - accumulated_s: 20.28674994944 -} -adc_trajectory_point { - x: -129.592745155 - y: 345.276516173 - z: -31.3256460568 - - speed: 3.63611102104 - acceleration_s: -0.14104756078 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 6.6000001430511475 - theta: -1.83510684167 - accumulated_s: 20.32311105964 -} -adc_trajectory_point { - x: -129.602163877 - y: 345.241656153 - z: -31.3255364103 - - speed: 3.63055562973 - acceleration_s: -0.202637106058 - curvature: 0.000344473001902 - curvature_change_rate: 0.00105424137207 - relative_time: 6.6100001335144043 - theta: -1.8351174499 - accumulated_s: 20.35941661594 -} -adc_trajectory_point { - x: -129.611589604 - y: 345.206780468 - z: -31.325259841 - - speed: 3.63055562973 - acceleration_s: -0.0529375409386 - curvature: 0.000344473001902 - curvature_change_rate: 0 - relative_time: 6.6200001239776611 - theta: -1.83514459552 - accumulated_s: 20.39572217224 -} -adc_trajectory_point { - x: -129.621012792 - y: 345.171960242 - z: -31.3250496518 - - speed: 3.62777781487 - acceleration_s: -0.228524209812 - curvature: 0.000344473001902 - curvature_change_rate: 0 - relative_time: 6.630000114440918 - theta: -1.83520069842 - accumulated_s: 20.43199995044 -} -adc_trajectory_point { - x: -129.630431507 - y: 345.137122284 - z: -31.3246317841 - - speed: 3.62777781487 - acceleration_s: -0.147046015386 - curvature: 0.000344473001902 - curvature_change_rate: 0 - relative_time: 6.6400001049041748 - theta: -1.83521659013 - accumulated_s: 20.46827772854 -} -adc_trajectory_point { - x: -129.639826233 - y: 345.102335135 - z: -31.3244052771 - - speed: 3.625 - acceleration_s: -0.272404638527 - curvature: 0.000344473001902 - curvature_change_rate: 0 - relative_time: 6.6500000953674316 - theta: -1.83523313511 - accumulated_s: 20.50452772854 -} -adc_trajectory_point { - x: -129.649232566 - y: 345.067548398 - z: -31.3239967572 - - speed: 3.625 - acceleration_s: -0.192874921616 - curvature: 0.000344473001902 - curvature_change_rate: 0 - relative_time: 6.6600000858306885 - theta: -1.83524611124 - accumulated_s: 20.54077772854 -} -adc_trajectory_point { - x: -129.658667824 - y: 345.032790706 - z: -31.3236352932 - - speed: 3.62222218513 - acceleration_s: -0.15964150738 - curvature: 0.000382747802778 - curvature_change_rate: 0.00105666629269 - relative_time: 6.6700000762939453 - theta: -1.83528687864 - accumulated_s: 20.57699995044 -} -adc_trajectory_point { - x: -129.668077114 - y: 344.998025352 - z: -31.3231557216 - - speed: 3.62222218513 - acceleration_s: -0.0776846328398 - curvature: 0.000382747802778 - curvature_change_rate: 0 - relative_time: 6.6800000667572021 - theta: -1.83531775266 - accumulated_s: 20.61322217224 -} -adc_trajectory_point { - x: -129.677514907 - y: 344.963309309 - z: -31.3228179542 - - speed: 3.6166665554 - acceleration_s: -0.19631417218 - curvature: 0.000382747802778 - curvature_change_rate: 0 - relative_time: 6.690000057220459 - theta: -1.8353728734 - accumulated_s: 20.64938883784 -} -adc_trajectory_point { - x: -129.677514907 - y: 344.963309309 - z: -31.3228179542 - - speed: 3.6166665554 - acceleration_s: -0.19631417218 - curvature: 0.000382747802778 - curvature_change_rate: 0 - relative_time: 6.690000057220459 - theta: -1.8353728734 - accumulated_s: 20.68555550334 -} -adc_trajectory_point { - x: -129.696340921 - y: 344.893907899 - z: -31.3219241276 - - speed: 3.6166665554 - acceleration_s: -0.319462048242 - curvature: 0.000382747802778 - curvature_change_rate: 0 - relative_time: 6.7100000381469727 - theta: -1.83542870108 - accumulated_s: 20.72172216894 -} -adc_trajectory_point { - x: -129.705768851 - y: 344.859209441 - z: -31.3214228358 - - speed: 3.6166665554 - acceleration_s: -0.0709556862685 - curvature: 0.000382747802778 - curvature_change_rate: 0 - relative_time: 6.7200000286102295 - theta: -1.83546825617 - accumulated_s: 20.75788883444 -} -adc_trajectory_point { - x: -129.715139657 - y: 344.824542555 - z: -31.3210016955 - - speed: 3.61111116409 - acceleration_s: -0.184650990123 - curvature: 0.000459297432768 - curvature_change_rate: 0.00211983587631 - relative_time: 6.7300000190734863 - theta: -1.83547192106 - accumulated_s: 20.79399994614 -} -adc_trajectory_point { - x: -129.72453811 - y: 344.789848345 - z: -31.3205012884 - - speed: 3.61111116409 - acceleration_s: 0.0243190105165 - curvature: 0.000459297432768 - curvature_change_rate: 0 - relative_time: 6.7400000095367432 - theta: -1.83547946165 - accumulated_s: 20.83011105774 -} -adc_trajectory_point { - x: -129.733909052 - y: 344.755222142 - z: -31.3200632455 - - speed: 3.60833334923 - acceleration_s: 0.0243190105165 - curvature: 0.00053584710648 - curvature_change_rate: 0.00212146900808 - relative_time: 6.75 - theta: -1.8355071408 - accumulated_s: 20.86619439124 -} -adc_trajectory_point { - x: -129.74329153 - y: 344.720570456 - z: -31.3195253564 - - speed: 3.60833334923 - acceleration_s: -0.0802392055238 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 6.7599999904632568 - theta: -1.8355370792 - accumulated_s: 20.90227772474 -} -adc_trajectory_point { - x: -129.752339561 - y: 344.685411672 - z: -31.3193645151 - - speed: 3.60555553436 - acceleration_s: -0.217940655795 - curvature: 0.000612396831201 - curvature_change_rate: 0.00212310485836 - relative_time: 6.7699999809265137 - theta: -1.83540903156 - accumulated_s: 20.93833328004 -} -adc_trajectory_point { - x: -129.761412977 - y: 344.650285541 - z: -31.3188640121 - - speed: 3.60555553436 - acceleration_s: -0.0888897122952 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 6.7799999713897705 - theta: -1.83538202008 - accumulated_s: 20.97438883544 -} -adc_trajectory_point { - x: -129.770502409 - y: 344.615185695 - z: -31.318396044 - - speed: 3.60555553436 - acceleration_s: -0.0970255434221 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 6.7899999618530273 - theta: -1.83541351809 - accumulated_s: 21.01044439074 -} -adc_trajectory_point { - x: -129.779559999 - y: 344.580118708 - z: -31.3179246383 - - speed: 3.6027777195 - acceleration_s: -0.160513943904 - curvature: 0.000727221583477 - curvature_change_rate: 0.00318711730825 - relative_time: 6.7999999523162842 - theta: -1.83541022882 - accumulated_s: 21.04647216794 -} -adc_trajectory_point { - x: -129.788646354 - y: 344.545016546 - z: -31.3174221944 - - speed: 3.59999990463 - acceleration_s: -0.0569414320492 - curvature: 0.000803771467601 - curvature_change_rate: 0.00212638572645 - relative_time: 6.809999942779541 - theta: -1.83545382293 - accumulated_s: 21.08247216704 -} -adc_trajectory_point { - x: -129.797684374 - y: 344.509954644 - z: -31.3169609178 - - speed: 3.59999990463 - acceleration_s: -0.143530273352 - curvature: 0.000803771467601 - curvature_change_rate: 0 - relative_time: 6.8199999332427979 - theta: -1.83542725496 - accumulated_s: 21.11847216604 -} -adc_trajectory_point { - x: -129.797684374 - y: 344.509954644 - z: -31.3169609178 - - speed: 3.59722232819 - acceleration_s: -0.143530273352 - curvature: 0.000918596439528 - curvature_change_rate: 0.00319204545761 - relative_time: 6.8199999332427979 - theta: -1.83542725496 - accumulated_s: 21.15444438934 -} -adc_trajectory_point { - x: -129.815815005 - y: 344.439830258 - z: -31.316028866 - - speed: 3.59722232819 - acceleration_s: -0.0390725718343 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 6.8400001525878906 - theta: -1.83543533505 - accumulated_s: 21.19041661264 -} -adc_trajectory_point { - x: -129.824892932 - y: 344.404782171 - z: -31.3154866332 - - speed: 3.59722232819 - acceleration_s: -0.0654790775035 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 6.8500001430511475 - theta: -1.8354392835 - accumulated_s: 21.22638883594 -} -adc_trajectory_point { - x: -129.833961849 - y: 344.369744159 - z: -31.3150062934 - - speed: 3.59444451332 - acceleration_s: -0.0690526666074 - curvature: 0.0009951465286 - curvature_change_rate: 0.00212967786228 - relative_time: 6.8600001335144043 - theta: -1.83541983186 - accumulated_s: 21.26233328104 -} -adc_trajectory_point { - x: -129.843021746 - y: 344.334719988 - z: -31.3145211916 - - speed: 3.59444451332 - acceleration_s: -0.111774696834 - curvature: 0.00103342160821 - curvature_change_rate: 0.00106483990678 - relative_time: 6.8700001239776611 - theta: -1.83538209833 - accumulated_s: 21.29827772614 -} -adc_trajectory_point { - x: -129.852095711 - y: 344.29971938 - z: -31.3142224336 - - speed: 3.59444451332 - acceleration_s: -0.126812446225 - curvature: 0.00103342160821 - curvature_change_rate: 0 - relative_time: 6.880000114440918 - theta: -1.83537984096 - accumulated_s: 21.33422217134 -} -adc_trajectory_point { - x: -129.861179176 - y: 344.264700586 - z: -31.3137229746 - - speed: 3.59444451332 - acceleration_s: -0.0626922022706 - curvature: 0.0010716967124 - curvature_change_rate: 0.001064840591 - relative_time: 6.8900001049041748 - theta: -1.83536571138 - accumulated_s: 21.37016661644 -} -adc_trajectory_point { - x: -129.861179176 - y: 344.264700586 - z: -31.3137229746 - - speed: 3.59444451332 - acceleration_s: -0.0626922022706 - curvature: 0.0010716967124 - curvature_change_rate: 0 - relative_time: 6.8900001049041748 - theta: -1.83536571138 - accumulated_s: 21.40611106154 -} -adc_trajectory_point { - x: -129.879302997 - y: 344.194676693 - z: -31.3128991006 - - speed: 3.59444451332 - acceleration_s: -0.025684391572 - curvature: 0.0010716967124 - curvature_change_rate: 0 - relative_time: 6.9100000858306885 - theta: -1.8352783275 - accumulated_s: 21.44205550674 -} -adc_trajectory_point { - x: -129.888383387 - y: 344.159682172 - z: -31.3126146821 - - speed: 3.59444451332 - acceleration_s: -0.0452099946246 - curvature: 0.0010716967124 - curvature_change_rate: 0 - relative_time: 6.9200000762939453 - theta: -1.83526642554 - accumulated_s: 21.47799995184 -} -adc_trajectory_point { - x: -129.897496563 - y: 344.124683135 - z: -31.3121939292 - - speed: 3.59444451332 - acceleration_s: -0.031027712531 - curvature: 0.0010716967124 - curvature_change_rate: 0 - relative_time: 6.9300000667572021 - theta: -1.83528810088 - accumulated_s: 21.51394439694 -} -adc_trajectory_point { - x: -129.906549714 - y: 344.089696197 - z: -31.3119860403 - - speed: 3.59444451332 - acceleration_s: -0.0649721158024 - curvature: 0.00110997184211 - curvature_change_rate: 0.00106484130056 - relative_time: 6.940000057220459 - theta: -1.83520864764 - accumulated_s: 21.54988884214 -} -adc_trajectory_point { - x: -129.906549714 - y: 344.089696197 - z: -31.3119860403 - - speed: 3.59444451332 - acceleration_s: -0.0649721158024 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 6.940000057220459 - theta: -1.83520864764 - accumulated_s: 21.58583328724 -} -adc_trajectory_point { - x: -129.924740807 - y: 344.019718613 - z: -31.3114557359 - - speed: 3.59444451332 - acceleration_s: 0.0431314506628 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 6.9600000381469727 - theta: -1.83516088741 - accumulated_s: 21.62177773234 -} -adc_trajectory_point { - x: -129.933843995 - y: 343.984702242 - z: -31.3110922594 - - speed: 3.59444451332 - acceleration_s: 0.0855120684387 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 6.9700000286102295 - theta: -1.83512542731 - accumulated_s: 21.65772217754 -} -adc_trajectory_point { - x: -129.942928386 - y: 343.949727349 - z: -31.3110211371 - - speed: 3.59444451332 - acceleration_s: -0.042027988716 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 6.9800000190734863 - theta: -1.83509154293 - accumulated_s: 21.69366662264 -} -adc_trajectory_point { - x: -129.952030428 - y: 343.914740892 - z: -31.3107325239 - - speed: 3.59444451332 - acceleration_s: -0.0416544132959 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 6.9900000095367432 - theta: -1.83507448019 - accumulated_s: 21.72961106774 -} -adc_trajectory_point { - x: -129.961116486 - y: 343.879776377 - z: -31.3106255215 - - speed: 3.59444451332 - acceleration_s: -0.114881221466 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 7 - theta: -1.83506696304 - accumulated_s: 21.76555551294 -} -adc_trajectory_point { - x: -129.970203904 - y: 343.844785056 - z: -31.3104857299 - - speed: 3.59166669846 - acceleration_s: 0.0376978566876 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 7.0099999904632568 - theta: -1.83506482561 - accumulated_s: 21.80147217994 -} -adc_trajectory_point { - x: -129.979276763 - y: 343.809816167 - z: -31.3103791531 - - speed: 3.59166669846 - acceleration_s: -0.0933464761497 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 7.0199999809265137 - theta: -1.83504723227 - accumulated_s: 21.83738884684 -} -adc_trajectory_point { - x: -129.988342726 - y: 343.774794385 - z: -31.3102112133 - - speed: 3.59166669846 - acceleration_s: 0.171267740385 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 7.0299999713897705 - theta: -1.83501777495 - accumulated_s: 21.87330551384 -} -adc_trajectory_point { - x: -129.997406406 - y: 343.739822131 - z: -31.3101650523 - - speed: 3.59166669846 - acceleration_s: -0.0723029859095 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 7.0399999618530273 - theta: -1.83502498708 - accumulated_s: 21.90922218084 -} -adc_trajectory_point { - x: -130.006485448 - y: 343.704824133 - z: -31.3100451212 - - speed: 3.59444451332 - acceleration_s: 0.077219262431 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 7.0499999523162842 - theta: -1.83504337574 - accumulated_s: 21.94516662594 -} -adc_trajectory_point { - x: -130.015525149 - y: 343.669845799 - z: -31.3099869089 - - speed: 3.59444451332 - acceleration_s: -0.105361000335 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 7.059999942779541 - theta: -1.83503234343 - accumulated_s: 21.98111107114 -} -adc_trajectory_point { - x: -130.024576615 - y: 343.634843107 - z: -31.3099394264 - - speed: 3.59444451332 - acceleration_s: 0.0627868831247 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 7.0699999332427979 - theta: -1.83504259135 - accumulated_s: 22.01705551624 -} -adc_trajectory_point { - x: -130.033620644 - y: 343.599838135 - z: -31.3100141492 - - speed: 3.59444451332 - acceleration_s: 0.0676183245505 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 7.0800001621246338 - theta: -1.83506089019 - accumulated_s: 22.05299996134 -} -adc_trajectory_point { - x: -130.04261413 - y: 343.564807122 - z: -31.3100484544 - - speed: 3.59166669846 - acceleration_s: 0.0676183245505 - curvature: 0.00114824699823 - curvature_change_rate: 0.00106566559017 - relative_time: 7.0900001525878906 - theta: -1.83501748989 - accumulated_s: 22.08891662834 -} -adc_trajectory_point { - x: -130.04261413 - y: 343.564807122 - z: -31.3100484544 - - speed: 3.59166669846 - acceleration_s: 0.0708798665679 - curvature: 0.00114824699823 - curvature_change_rate: 0 - relative_time: 7.0900001525878906 - theta: -1.83501748989 - accumulated_s: 22.12483329534 -} -adc_trajectory_point { - x: -130.060656062 - y: 343.49477692 - z: -31.3101350283 - - speed: 3.58888888359 - acceleration_s: -0.0694072513285 - curvature: 0.00118652218167 - curvature_change_rate: 0.00106649118118 - relative_time: 7.1100001335144043 - theta: -1.83505413531 - accumulated_s: 22.16072218414 -} -adc_trajectory_point { - x: -130.069641818 - y: 343.459738761 - z: -31.3101684554 - - speed: 3.58888888359 - acceleration_s: 0.00296150947042 - curvature: 0.00118652218167 - curvature_change_rate: 0 - relative_time: 7.1200001239776611 - theta: -1.835051506 - accumulated_s: 22.19661107304 -} -adc_trajectory_point { - x: -130.078660473 - y: 343.424728646 - z: -31.3103492931 - - speed: 3.58611106873 - acceleration_s: 0.0119313787973 - curvature: 0.00118652218167 - curvature_change_rate: 0 - relative_time: 7.130000114440918 - theta: -1.83508404737 - accumulated_s: 22.23247218374 -} -adc_trajectory_point { - x: -130.087640918 - y: 343.389669334 - z: -31.3102647075 - - speed: 3.58611106873 - acceleration_s: 0.117254694412 - curvature: 0.00118652218167 - curvature_change_rate: 0 - relative_time: 7.1400001049041748 - theta: -1.83506994516 - accumulated_s: 22.26833329444 -} -adc_trajectory_point { - x: -130.09662663 - y: 343.354619657 - z: -31.3104229178 - - speed: 3.58333325386 - acceleration_s: 0.117254694412 - curvature: 0.00122479739336 - curvature_change_rate: 0.00106814546601 - relative_time: 7.1500000953674316 - theta: -1.83508270945 - accumulated_s: 22.30416662694 -} -adc_trajectory_point { - x: -130.1056281 - y: 343.319552452 - z: -31.3104638765 - - speed: 3.58333325386 - acceleration_s: 0.145958530996 - curvature: 0.00122479739336 - curvature_change_rate: 0 - relative_time: 7.1600000858306885 - theta: -1.83510833489 - accumulated_s: 22.33999995944 -} -adc_trajectory_point { - x: -130.114593512 - y: 343.284493758 - z: -31.3106325427 - - speed: 3.58611106873 - acceleration_s: -0.0127297350305 - curvature: 0.00122479739336 - curvature_change_rate: 0 - relative_time: 7.1700000762939453 - theta: -1.83510208823 - accumulated_s: 22.37586107014 -} -adc_trajectory_point { - x: -130.123569535 - y: 343.249412562 - z: -31.3105624365 - - speed: 3.58611106873 - acceleration_s: 0.0569202468214 - curvature: 0.00122479739336 - curvature_change_rate: 0 - relative_time: 7.1800000667572021 - theta: -1.83508994072 - accumulated_s: 22.41172218084 -} -adc_trajectory_point { - x: -130.132568337 - y: 343.214381013 - z: -31.3106503142 - - speed: 3.58611106873 - acceleration_s: -0.157643290914 - curvature: 0.00126307263419 - curvature_change_rate: 0.0010673188894 - relative_time: 7.190000057220459 - theta: -1.83511761728 - accumulated_s: 22.44758329154 -} -adc_trajectory_point { - x: -130.132568337 - y: 343.214381013 - z: -31.3106503142 - - speed: 3.58611106873 - acceleration_s: -0.157643290914 - curvature: 0.00126307263419 - curvature_change_rate: 0 - relative_time: 7.190000057220459 - theta: -1.83511761728 - accumulated_s: 22.48344440224 -} -adc_trajectory_point { - x: -130.150532675 - y: 343.144269241 - z: -31.3106434494 - - speed: 3.58611106873 - acceleration_s: -0.106311056129 - curvature: 0.00130134790508 - curvature_change_rate: 0.00106731972762 - relative_time: 7.2100000381469727 - theta: -1.83509027941 - accumulated_s: 22.51930551294 -} -adc_trajectory_point { - x: -130.159529213 - y: 343.109191237 - z: -31.3105427884 - - speed: 3.58611106873 - acceleration_s: 0.115221359315 - curvature: 0.00130134790508 - curvature_change_rate: 0 - relative_time: 7.2200000286102295 - theta: -1.83506526736 - accumulated_s: 22.55516662364 -} -adc_trajectory_point { - x: -130.168508102 - y: 343.074132603 - z: -31.310538793 - - speed: 3.58888888359 - acceleration_s: 0.029643046692 - curvature: 0.00130134790508 - curvature_change_rate: 0 - relative_time: 7.2300000190734863 - theta: -1.83505024767 - accumulated_s: 22.59105551244 -} -adc_trajectory_point { - x: -130.177510972 - y: 343.039079463 - z: -31.3103737189 - - speed: 3.58888888359 - acceleration_s: -0.0147885952996 - curvature: 0.00130134790508 - curvature_change_rate: 0 - relative_time: 7.2400000095367432 - theta: -1.83501533914 - accumulated_s: 22.62694440124 -} -adc_trajectory_point { - x: -130.186526955 - y: 343.004019301 - z: -31.3102239668 - - speed: 3.59166669846 - acceleration_s: -0.0147885952996 - curvature: 0.00137789864791 - curvature_change_rate: 0.00213134316893 - relative_time: 7.25 - theta: -1.83499212781 - accumulated_s: 22.66286106824 -} -adc_trajectory_point { - x: -130.19552167 - y: 342.968970379 - z: -31.3100768542 - - speed: 3.59166669846 - acceleration_s: -0.0313511319185 - curvature: 0.00137789864791 - curvature_change_rate: 0 - relative_time: 7.2599999904632568 - theta: -1.83495186355 - accumulated_s: 22.69877773524 -} -adc_trajectory_point { - x: -130.204546417 - y: 342.933922036 - z: -31.3098619198 - - speed: 3.59166669846 - acceleration_s: 0.0902367437011 - curvature: 0.00149272484953 - curvature_change_rate: 0.00319701718626 - relative_time: 7.2699999809265137 - theta: -1.83491460216 - accumulated_s: 22.73469440224 -} -adc_trajectory_point { - x: -130.21358433 - y: 342.898865206 - z: -31.3097897591 - - speed: 3.59166669846 - acceleration_s: 0.028531882737 - curvature: 0.00149272484953 - curvature_change_rate: 0 - relative_time: 7.2799999713897705 - theta: -1.83491524834 - accumulated_s: 22.77061106924 -} -adc_trajectory_point { - x: -130.222597136 - y: 342.863785475 - z: -31.3095163265 - - speed: 3.59166669846 - acceleration_s: 0.0753780355319 - curvature: 0.00164582695329 - curvature_change_rate: 0.00426270354731 - relative_time: 7.2899999618530273 - theta: -1.83485357612 - accumulated_s: 22.80652773614 -} -adc_trajectory_point { - x: -130.231628495 - y: 342.828727264 - z: -31.309449302 - - speed: 3.59166669846 - acceleration_s: 0.0376395358123 - curvature: 0.00164582695329 - curvature_change_rate: 0 - relative_time: 7.2999999523162842 - theta: -1.83482219205 - accumulated_s: 22.84244440314 -} -adc_trajectory_point { - x: -130.240663187 - y: 342.793636264 - z: -31.3091299264 - - speed: 3.59444451332 - acceleration_s: 0.0696315812177 - curvature: 0.00179892968375 - curvature_change_rate: 0.00425942673182 - relative_time: 7.309999942779541 - theta: -1.83478084755 - accumulated_s: 22.87838884834 -} -adc_trajectory_point { - x: -130.249708453 - y: 342.758569037 - z: -31.3090284392 - - speed: 3.59444451332 - acceleration_s: 0.0344800958841 - curvature: 0.00179892968375 - curvature_change_rate: 0 - relative_time: 7.3199999332427979 - theta: -1.83474836288 - accumulated_s: 22.91433329344 -} -adc_trajectory_point { - x: -130.258778295 - y: 342.723481383 - z: -31.3088150099 - - speed: 3.59166669846 - acceleration_s: 0.0944292546466 - curvature: 0.00210513725798 - curvature_change_rate: 0.00852550083098 - relative_time: 7.3300001621246338 - theta: -1.83471420889 - accumulated_s: 22.95024996044 -} -adc_trajectory_point { - x: -130.267817376 - y: 342.68839044 - z: -31.3087048139 - - speed: 3.59166669846 - acceleration_s: 0.0480979808867 - curvature: 0.00210513725798 - curvature_change_rate: 0 - relative_time: 7.3400001525878906 - theta: -1.83464913536 - accumulated_s: 22.98616662744 -} -adc_trajectory_point { - x: -130.276886507 - y: 342.653292831 - z: -31.3084988119 - - speed: 3.59166669846 - acceleration_s: 0.0993478851233 - curvature: 0.00229651859052 - curvature_change_rate: 0.00532848252946 - relative_time: 7.3500001430511475 - theta: -1.83461414728 - accumulated_s: 23.02208329444 -} -adc_trajectory_point { - x: -130.285928296 - y: 342.618174026 - z: -31.3084008833 - - speed: 3.59166669846 - acceleration_s: 0.1004974117 - curvature: 0.00229651859052 - curvature_change_rate: 0 - relative_time: 7.3600001335144043 - theta: -1.83453535113 - accumulated_s: 23.05799996134 -} -adc_trajectory_point { - x: -130.294970121 - y: 342.583056148 - z: -31.3082660045 - - speed: 3.59166669846 - acceleration_s: 0.0633690466968 - curvature: 0.00244962463489 - curvature_change_rate: 0.00426281326249 - relative_time: 7.3700001239776611 - theta: -1.83448217622 - accumulated_s: 23.09391662834 -} -adc_trajectory_point { - x: -130.304013811 - y: 342.5479244 - z: -31.3081754399 - - speed: 3.59166669846 - acceleration_s: 0.0765517437431 - curvature: 0.00244962463489 - curvature_change_rate: 0 - relative_time: 7.380000114440918 - theta: -1.83441362412 - accumulated_s: 23.12983329534 -} -adc_trajectory_point { - x: -130.313059421 - y: 342.512776467 - z: -31.3081546687 - - speed: 3.59166669846 - acceleration_s: 0.16486283758 - curvature: 0.00256445477712 - curvature_change_rate: 0.00319712690159 - relative_time: 7.3900001049041748 - theta: -1.83434890854 - accumulated_s: 23.16574996234 -} -adc_trajectory_point { - x: -130.322121672 - y: 342.477620614 - z: -31.3080039769 - - speed: 3.59166669846 - acceleration_s: 0.16486283758 - curvature: 0.00256445477712 - curvature_change_rate: 0 - relative_time: 7.4000000953674316 - theta: -1.83429750296 - accumulated_s: 23.20166662934 -} -adc_trajectory_point { - x: -130.331166428 - y: 342.442466323 - z: -31.3079969566 - - speed: 3.59166669846 - acceleration_s: 0.0820721228419 - curvature: 0.00267928546864 - curvature_change_rate: 0.00319714219518 - relative_time: 7.4100000858306885 - theta: -1.83420113683 - accumulated_s: 23.23758329634 -} -adc_trajectory_point { - x: -130.34020588 - y: 342.407298586 - z: -31.3079012437 - - speed: 3.59166669846 - acceleration_s: 0.0814759711025 - curvature: 0.00267928546864 - curvature_change_rate: 0 - relative_time: 7.4200000762939453 - theta: -1.8341303526 - accumulated_s: 23.27349996324 -} -adc_trajectory_point { - x: -130.349274754 - y: 342.372133407 - z: -31.3079076596 - - speed: 3.59166669846 - acceleration_s: 0.0196518608533 - curvature: 0.00275583979477 - curvature_change_rate: 0.00213144293583 - relative_time: 7.4300000667572021 - theta: -1.83405418753 - accumulated_s: 23.30941663024 -} -adc_trajectory_point { - x: -130.358377993 - y: 342.336947744 - z: -31.3077859282 - - speed: 3.59166669846 - acceleration_s: 0.129350664373 - curvature: 0.00275583979477 - curvature_change_rate: 0 - relative_time: 7.440000057220459 - theta: -1.83399703206 - accumulated_s: 23.34533329724 -} -adc_trajectory_point { - x: -130.358377993 - y: 342.336947744 - z: -31.3077859282 - - speed: 3.59444451332 - acceleration_s: 0.129350664373 - curvature: 0.00275583979477 - curvature_change_rate: 0 - relative_time: 7.440000057220459 - theta: -1.83399703206 - accumulated_s: 23.38127774234 -} -adc_trajectory_point { - x: -130.376616435 - y: 342.266592228 - z: -31.3076887252 - - speed: 3.59444451332 - acceleration_s: 0.146340192669 - curvature: 0.00275583979477 - curvature_change_rate: 0 - relative_time: 7.4600000381469727 - theta: -1.8338779961 - accumulated_s: 23.41722218754 -} -adc_trajectory_point { - x: -130.376616435 - y: 342.266592228 - z: -31.3076887252 - - speed: 3.59444451332 - acceleration_s: 0.146340192669 - curvature: 0.00275583979477 - curvature_change_rate: 0 - relative_time: 7.4600000381469727 - theta: -1.8338779961 - accumulated_s: 23.45316663264 -} -adc_trajectory_point { - x: -130.394901045 - y: 342.196204353 - z: -31.3076158371 - - speed: 3.59722232819 - acceleration_s: 0.117064397227 - curvature: 0.00275583979477 - curvature_change_rate: 0 - relative_time: 7.4800000190734863 - theta: -1.83373853351 - accumulated_s: 23.48913885594 -} -adc_trajectory_point { - x: -130.404053375 - y: 342.161012492 - z: -31.3075456787 - - speed: 3.59999990463 - acceleration_s: 0.0284211737936 - curvature: 0.0027175627066 - curvature_change_rate: -0.00106325247733 - relative_time: 7.4900000095367432 - theta: -1.8336616883 - accumulated_s: 23.52513885494 -} -adc_trajectory_point { - x: -130.413197227 - y: 342.125807433 - z: -31.3074800158 - - speed: 3.59999990463 - acceleration_s: 0.0284211737936 - curvature: 0.0027175627066 - curvature_change_rate: 0 - relative_time: 7.5 - theta: -1.83357778194 - accumulated_s: 23.56113885404 -} -adc_trajectory_point { - x: -130.422384725 - y: 342.090611337 - z: -31.3074125173 - - speed: 3.6027777195 - acceleration_s: 0.0633574613684 - curvature: 0.00264100850892 - curvature_change_rate: -0.00212486596842 - relative_time: 7.5099999904632568 - theta: -1.83353886354 - accumulated_s: 23.59716663124 -} -adc_trajectory_point { - x: -130.431553773 - y: 342.055391385 - z: -31.3074186957 - - speed: 3.6027777195 - acceleration_s: 0.121753161698 - curvature: 0.00264100850892 - curvature_change_rate: 0 - relative_time: 7.5199999809265137 - theta: -1.83348873593 - accumulated_s: 23.63319440844 -} -adc_trajectory_point { - x: -130.440697187 - y: 342.020139134 - z: -31.3072792934 - - speed: 3.60555553436 - acceleration_s: 0.149883871992 - curvature: 0.00256445477712 - curvature_change_rate: -0.0021232159946 - relative_time: 7.5299999713897705 - theta: -1.83340978088 - accumulated_s: 23.66924996374 -} -adc_trajectory_point { - x: -130.449842853 - y: 341.984902127 - z: -31.3073009551 - - speed: 3.60555553436 - acceleration_s: 0.0972756561058 - curvature: 0.00256445477712 - curvature_change_rate: 0 - relative_time: 7.5399999618530273 - theta: -1.83334414549 - accumulated_s: 23.70530551914 -} -adc_trajectory_point { - x: -130.458988646 - y: 341.949633606 - z: -31.3071024986 - - speed: 3.60833334923 - acceleration_s: 0.0972756561058 - curvature: 0.00244962463489 - curvature_change_rate: -0.00318235958594 - relative_time: 7.5499999523162842 - theta: -1.83330046649 - accumulated_s: 23.74138885264 -} -adc_trajectory_point { - x: -130.46811181 - y: 341.914366125 - z: -31.3071321752 - - speed: 3.60833334923 - acceleration_s: 0.0974151609056 - curvature: 0.00244962463489 - curvature_change_rate: 0 - relative_time: 7.559999942779541 - theta: -1.83326266322 - accumulated_s: 23.77747218614 -} -adc_trajectory_point { - x: -130.477227617 - y: 341.879063801 - z: -31.3068647711 - - speed: 3.61111116409 - acceleration_s: 0.109978512877 - curvature: 0.00237307149975 - curvature_change_rate: -0.00211993294195 - relative_time: 7.5699999332427979 - theta: -1.83321713076 - accumulated_s: 23.81358329774 -} -adc_trajectory_point { - x: -130.486315045 - y: 341.84378041 - z: -31.3068743879 - - speed: 3.61111116409 - acceleration_s: 0.00567902186277 - curvature: 0.00237307149975 - curvature_change_rate: 0 - relative_time: 7.5800001621246338 - theta: -1.83319815852 - accumulated_s: 23.84969440934 -} -adc_trajectory_point { - x: -130.495376099 - y: 341.808448496 - z: -31.3067256249 - - speed: 3.6166665554 - acceleration_s: 0.152469261191 - curvature: 0.00225824221834 - curvature_change_rate: -0.00317500327013 - relative_time: 7.5900001525878906 - theta: -1.83315549593 - accumulated_s: 23.88586107494 -} -adc_trajectory_point { - x: -130.504386577 - y: 341.773133968 - z: -31.3067099955 - - speed: 3.6166665554 - acceleration_s: 0.152469261191 - curvature: 0.00225824221834 - curvature_change_rate: 0 - relative_time: 7.6000001430511475 - theta: -1.83309316732 - accumulated_s: 23.92202774044 -} -adc_trajectory_point { - x: -130.513453083 - y: 341.737777539 - z: -31.3065015916 - - speed: 3.61111116409 - acceleration_s: 0.179880549344 - curvature: 0.00214341342064 - curvature_change_rate: -0.0031798743513 - relative_time: 7.6100001335144043 - theta: -1.83312058844 - accumulated_s: 23.95813885214 -} -adc_trajectory_point { - x: -130.522445901 - y: 341.702419138 - z: -31.306389872 - - speed: 3.61111116409 - acceleration_s: 0.106177237866 - curvature: 0.00214341342064 - curvature_change_rate: 0 - relative_time: 7.6200001239776611 - theta: -1.83309768605 - accumulated_s: 23.99424996374 -} -adc_trajectory_point { - x: -130.531461869 - y: 341.667048605 - z: -31.3062682543 - - speed: 3.61111116409 - acceleration_s: 0.127126930021 - curvature: 0.00202858508204 - curvature_change_rate: -0.00317986163771 - relative_time: 7.630000114440918 - theta: -1.83310159988 - accumulated_s: 24.03036107544 -} -adc_trajectory_point { - x: -130.540412175 - y: 341.631632082 - z: -31.3060056586 - - speed: 3.61111116409 - acceleration_s: 0.165897218174 - curvature: 0.00202858508204 - curvature_change_rate: 0 - relative_time: 7.6400001049041748 - theta: -1.83303996439 - accumulated_s: 24.06647218704 -} -adc_trajectory_point { - x: -130.549373796 - y: 341.59624719 - z: -31.3059436176 - - speed: 3.61388897896 - acceleration_s: 0.0274753954421 - curvature: 0.00195203309921 - curvature_change_rate: -0.00211827157033 - relative_time: 7.6500000953674316 - theta: -1.83305600875 - accumulated_s: 24.10261107684 -} -adc_trajectory_point { - x: -130.558305939 - y: 341.560791409 - z: -31.3057266828 - - speed: 3.61388897896 - acceleration_s: 0.219597653305 - curvature: 0.00195203309921 - curvature_change_rate: 0 - relative_time: 7.6600000858306885 - theta: -1.8330286297 - accumulated_s: 24.13874996664 -} -adc_trajectory_point { - x: -130.567250945 - y: 341.525391517 - z: -31.3056051079 - - speed: 3.61388897896 - acceleration_s: -0.04968520856 - curvature: 0.00191375717794 - curvature_change_rate: -0.00105913384432 - relative_time: 7.6700000762939453 - theta: -1.83306049982 - accumulated_s: 24.17488885644 -} -adc_trajectory_point { - x: -130.576155849 - y: 341.489935814 - z: -31.305308939 - - speed: 3.61388897896 - acceleration_s: 0.0754218193221 - curvature: 0.00191375717794 - curvature_change_rate: 0 - relative_time: 7.6800000667572021 - theta: -1.83303113849 - accumulated_s: 24.21102774624 -} -adc_trajectory_point { - x: -130.585087762 - y: 341.454496958 - z: -31.3051161263 - - speed: 3.61388897896 - acceleration_s: 0.0459569842948 - curvature: 0.00183720547112 - curvature_change_rate: -0.00211826393298 - relative_time: 7.690000057220459 - theta: -1.83303396846 - accumulated_s: 24.24716663604 -} -adc_trajectory_point { - x: -130.585087762 - y: 341.454496958 - z: -31.3051161263 - - speed: 3.61388897896 - acceleration_s: 0.0459569842948 - curvature: 0.00183720547112 - curvature_change_rate: 0 - relative_time: 7.690000057220459 - theta: -1.83303396846 - accumulated_s: 24.28330552574 -} -adc_trajectory_point { - x: -130.602911121 - y: 341.383562012 - z: -31.3047279408 - - speed: 3.61111116409 - acceleration_s: 0.144849583266 - curvature: 0.00183720547112 - curvature_change_rate: 0 - relative_time: 7.7100000381469727 - theta: -1.83293445716 - accumulated_s: 24.31941663744 -} -adc_trajectory_point { - x: -130.611852783 - y: 341.348106938 - z: -31.3045846215 - - speed: 3.61111116409 - acceleration_s: 0.0448845221166 - curvature: 0.00183720547112 - curvature_change_rate: 0 - relative_time: 7.7200000286102295 - theta: -1.83294424528 - accumulated_s: 24.35552774904 -} -adc_trajectory_point { - x: -130.620780796 - y: 341.312606475 - z: -31.3042427422 - - speed: 3.61111116409 - acceleration_s: 0.160385700989 - curvature: 0.00179892968375 - curvature_change_rate: -0.00105994486544 - relative_time: 7.7300000190734863 - theta: -1.83289843935 - accumulated_s: 24.39163886074 -} -adc_trajectory_point { - x: -130.629714032 - y: 341.277145663 - z: -31.3041904727 - - speed: 3.61111116409 - acceleration_s: 0.0446487559159 - curvature: 0.00179892968375 - curvature_change_rate: 0 - relative_time: 7.7400000095367432 - theta: -1.83288996666 - accumulated_s: 24.42774997234 -} -adc_trajectory_point { - x: -130.638674159 - y: 341.24160425 - z: -31.3038888006 - - speed: 3.61388897896 - acceleration_s: 0.2240524262 - curvature: 0.00179892968375 - curvature_change_rate: 0 - relative_time: 7.75 - theta: -1.83288226161 - accumulated_s: 24.46388886214 -} -adc_trajectory_point { - x: -130.647626384 - y: 341.206107513 - z: -31.3037703065 - - speed: 3.61388897896 - acceleration_s: 0.0394091362678 - curvature: 0.00179892968375 - curvature_change_rate: 0 - relative_time: 7.7599999904632568 - theta: -1.83285930312 - accumulated_s: 24.50002775194 -} -adc_trajectory_point { - x: -130.647626384 - y: 341.206107513 - z: -31.3037703065 - - speed: 3.6166665554 - acceleration_s: 0.0394091362678 - curvature: 0.0017606539392 - curvature_change_rate: -0.00105831555025 - relative_time: 7.7599999904632568 - theta: -1.83285930312 - accumulated_s: 24.53619441744 -} -adc_trajectory_point { - x: -130.666043407 - y: 341.135419188 - z: -31.3035298269 - - speed: 3.6166665554 - acceleration_s: 0.0398697614652 - curvature: 0.0017606539392 - curvature_change_rate: 0 - relative_time: 7.7799999713897705 - theta: -1.83282695049 - accumulated_s: 24.57236108304 -} -adc_trajectory_point { - x: -130.666043407 - y: 341.135419188 - z: -31.3035298269 - - speed: 3.61944437027 - acceleration_s: 0.0398697614652 - curvature: 0.00168410257488 - curvature_change_rate: -0.00211500320182 - relative_time: 7.7799999713897705 - theta: -1.83282695049 - accumulated_s: 24.60855552674 -} -adc_trajectory_point { - x: -130.675528532 - y: 341.099629458 - z: -31.3032928389 - - speed: 3.61944437027 - acceleration_s: 0.1292120301 - curvature: 0.00168410257488 - curvature_change_rate: 0 - relative_time: 7.7899999618530273 - theta: -1.83279553698 - accumulated_s: 24.64474997044 -} -adc_trajectory_point { - x: -130.69440843 - y: 341.028045342 - z: -31.3030609163 - - speed: 3.625 - acceleration_s: 0.0501726322437 - curvature: 0.00156927582672 - curvature_change_rate: -0.00316763443199 - relative_time: 7.809999942779541 - theta: -1.83274545472 - accumulated_s: 24.68099997044 -} -adc_trajectory_point { - x: -130.703852373 - y: 340.992214082 - z: -31.3028028309 - - speed: 3.625 - acceleration_s: 0.124113583731 - curvature: 0.00156927582672 - curvature_change_rate: 0 - relative_time: 7.8199999332427979 - theta: -1.83272471706 - accumulated_s: 24.71724997044 -} -adc_trajectory_point { - x: -130.713271736 - y: 340.956389943 - z: -31.3027244527 - - speed: 3.625 - acceleration_s: 0.0844670987936 - curvature: 0.00149272484953 - curvature_change_rate: -0.00211175109484 - relative_time: 7.8300001621246338 - theta: -1.83270542199 - accumulated_s: 24.75349997044 -} -adc_trajectory_point { - x: -130.722703543 - y: 340.920539753 - z: -31.3024780815 - - speed: 3.625 - acceleration_s: 0.148104053322 - curvature: 0.00149272484953 - curvature_change_rate: 0 - relative_time: 7.8400001525878906 - theta: -1.83271988044 - accumulated_s: 24.78974997044 -} -adc_trajectory_point { - x: -130.732108872 - y: 340.884678737 - z: -31.3023909777 - - speed: 3.63055562973 - acceleration_s: 0.148104053322 - curvature: 0.00137789864791 - curvature_change_rate: -0.00316277213004 - relative_time: 7.8500001430511475 - theta: -1.83270299502 - accumulated_s: 24.82605552674 -} -adc_trajectory_point { - x: -130.741504345 - y: 340.848781349 - z: -31.3021927224 - - speed: 3.63055562973 - acceleration_s: 0.179385781992 - curvature: 0.00137789864791 - curvature_change_rate: 0 - relative_time: 7.8600001335144043 - theta: -1.83268369838 - accumulated_s: 24.86236108304 -} -adc_trajectory_point { - x: -130.750903537 - y: 340.812895603 - z: -31.3020933596 - - speed: 3.63611102104 - acceleration_s: 0.0930404922489 - curvature: 0.00130134790508 - curvature_change_rate: -0.00210529168074 - relative_time: 7.8700001239776611 - theta: -1.83265571511 - accumulated_s: 24.89872219324 -} -adc_trajectory_point { - x: -130.760292861 - y: 340.776977129 - z: -31.3019938609 - - speed: 3.63611102104 - acceleration_s: 0.152979877708 - curvature: 0.00130134790508 - curvature_change_rate: 0 - relative_time: 7.880000114440918 - theta: -1.83263881198 - accumulated_s: 24.93508330344 -} -adc_trajectory_point { - x: -130.76967928 - y: 340.741082499 - z: -31.301855946 - - speed: 3.64166665077 - acceleration_s: 0.0231350709845 - curvature: 0.00118652218167 - curvature_change_rate: -0.00315310912329 - relative_time: 7.8900001049041748 - theta: -1.8326313572 - accumulated_s: 24.97149996994 -} -adc_trajectory_point { - x: -130.779138295 - y: 340.705167118 - z: -31.3017047923 - - speed: 3.64166665077 - acceleration_s: 0.0231350709845 - curvature: 0.00118652218167 - curvature_change_rate: 0 - relative_time: 7.9000000953674316 - theta: -1.83266872915 - accumulated_s: 25.00791663644 -} -adc_trajectory_point { - x: -130.788551733 - y: 340.669244905 - z: -31.3015434276 - - speed: 3.64166665077 - acceleration_s: 0.0728129344467 - curvature: 0.00110997184211 - curvature_change_rate: -0.00210206883018 - relative_time: 7.9100000858306885 - theta: -1.83261671623 - accumulated_s: 25.04433330294 -} -adc_trajectory_point { - x: -130.798021393 - y: 340.633331995 - z: -31.301507744 - - speed: 3.64166665077 - acceleration_s: 0.0896483382723 - curvature: 0.00110997184211 - curvature_change_rate: 0 - relative_time: 7.9200000762939453 - theta: -1.83263678319 - accumulated_s: 25.08074996944 -} -adc_trajectory_point { - x: -130.807484599 - y: 340.597393821 - z: -31.3013093742 - - speed: 3.64166665077 - acceleration_s: 0.135289308023 - curvature: 0.00103342160821 - curvature_change_rate: -0.00210206592869 - relative_time: 7.9300000667572021 - theta: -1.83258672514 - accumulated_s: 25.11716663604 -} -adc_trajectory_point { - x: -130.816937774 - y: 340.561463679 - z: -31.3011940848 - - speed: 3.64166665077 - acceleration_s: 0.0628889723761 - curvature: 0.00103342160821 - curvature_change_rate: 0 - relative_time: 7.940000057220459 - theta: -1.83255082443 - accumulated_s: 25.15358330254 -} -adc_trajectory_point { - x: -130.816937774 - y: 340.561463679 - z: -31.3011940848 - - speed: 3.64444446564 - acceleration_s: 0.0628889723761 - curvature: 0.000918596439528 - curvature_change_rate: -0.00315069058562 - relative_time: 7.940000057220459 - theta: -1.83255082443 - accumulated_s: 25.19002774714 -} -adc_trajectory_point { - x: -130.83593004 - y: 340.489596202 - z: -31.3008860145 - - speed: 3.64444446564 - acceleration_s: -0.0163727158504 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 7.9600000381469727 - theta: -1.83255423802 - accumulated_s: 25.22647219184 -} -adc_trajectory_point { - x: -130.845418368 - y: 340.45365412 - z: -31.3007718567 - - speed: 3.6472222805 - acceleration_s: 0.0501716132282 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 7.9700000286102295 - theta: -1.83253588269 - accumulated_s: 25.26294441464 -} -adc_trajectory_point { - x: -130.854934592 - y: 340.417716539 - z: -31.3005748028 - - speed: 3.6472222805 - acceleration_s: 0.0350966479665 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 7.9800000190734863 - theta: -1.83251789237 - accumulated_s: 25.29941663744 -} -adc_trajectory_point { - x: -130.864450823 - y: 340.381778494 - z: -31.3004705673 - - speed: 3.6472222805 - acceleration_s: 0.0538111666898 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 7.9900000095367432 - theta: -1.83250343616 - accumulated_s: 25.33588886024 -} -adc_trajectory_point { - x: -130.873993682 - y: 340.345841256 - z: -31.3002635697 - - speed: 3.6472222805 - acceleration_s: 0.0231137538721 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8 - theta: -1.83250007398 - accumulated_s: 25.37236108304 -} -adc_trajectory_point { - x: -130.883525638 - y: 340.309894166 - z: -31.3001907943 - - speed: 3.6472222805 - acceleration_s: 0.0817352685085 - curvature: 0.000880321428239 - curvature_change_rate: -0.00104942908179 - relative_time: 8.0099999904632568 - theta: -1.83245126535 - accumulated_s: 25.408833305839998 -} -adc_trajectory_point { - x: -130.893060411 - y: 340.273944983 - z: -31.3000618229 - - speed: 3.6472222805 - acceleration_s: 0.0817352685085 - curvature: 0.000880321428239 - curvature_change_rate: 0 - relative_time: 8.0199999809265137 - theta: -1.83241241184 - accumulated_s: 25.44530552864 -} -adc_trajectory_point { - x: -130.902637598 - y: 340.238000204 - z: -31.2999389796 - - speed: 3.6472222805 - acceleration_s: 0.048851556906 - curvature: 0.000880321428239 - curvature_change_rate: 0 - relative_time: 8.02999997138977 - theta: -1.83240779429 - accumulated_s: 25.48177775144 -} -adc_trajectory_point { - x: -130.912176404 - y: 340.20202961 - z: -31.2998038605 - - speed: 3.65000009537 - acceleration_s: 0.0897047452737 - curvature: 0.000880321428239 - curvature_change_rate: 0 - relative_time: 8.0399999618530273 - theta: -1.83235125691 - accumulated_s: 25.51827775244 -} -adc_trajectory_point { - x: -130.921783432 - y: 340.166072734 - z: -31.2996864039 - - speed: 3.65277767181 - acceleration_s: 0.0897047452737 - curvature: 0.000918596439528 - curvature_change_rate: 0.00104783303907 - relative_time: 8.0499999523162842 - theta: -1.83233337587 - accumulated_s: 25.55480552914 -} -adc_trajectory_point { - x: -130.9313818 - y: 340.130114091 - z: -31.299647077 - - speed: 3.65277767181 - acceleration_s: 0.0624346032785 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.059999942779541 - theta: -1.8323109334 - accumulated_s: 25.59133330584 -} -adc_trajectory_point { - x: -130.941007048 - y: 340.09412651 - z: -31.2994796736 - - speed: 3.65277767181 - acceleration_s: 0.142720077487 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.0699999332427979 - theta: -1.83228829884 - accumulated_s: 25.62786108254 -} -adc_trajectory_point { - x: -130.950640579 - y: 340.058177255 - z: -31.2994999234 - - speed: 3.65555548668 - acceleration_s: 0.000615801137302 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.0800001621246338 - theta: -1.83228444302 - accumulated_s: 25.66441663744 -} -adc_trajectory_point { - x: -130.960315636 - y: 340.022180065 - z: -31.2993414029 - - speed: 3.65555548668 - acceleration_s: 0.15280930018 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.09000015258789 - theta: -1.83226636784 - accumulated_s: 25.70097219234 -} -adc_trajectory_point { - x: -130.969995453 - y: 339.986192931 - z: -31.299452601 - - speed: 3.65833330154 - acceleration_s: 0.15280930018 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.1000001430511475 - theta: -1.83225447424 - accumulated_s: 25.73755552534 -} -adc_trajectory_point { - x: -130.979682334 - y: 339.950163942 - z: -31.2993475264 - - speed: 3.66111111641 - acceleration_s: 0.198806584695 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.1100001335144043 - theta: -1.83222854493 - accumulated_s: 25.77416663644 -} -adc_trajectory_point { - x: -130.989392073 - y: 339.91415531 - z: -31.2994117336 - - speed: 3.66111111641 - acceleration_s: 0.134532857608 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.1200001239776611 - theta: -1.83223108593 - accumulated_s: 25.81077774764 -} -adc_trajectory_point { - x: -130.999126681 - y: 339.878125284 - z: -31.2993557891 - - speed: 3.66666674614 - acceleration_s: 0.112522315953 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.130000114440918 - theta: -1.83221197181 - accumulated_s: 25.84744441514 -} -adc_trajectory_point { - x: -131.008844928 - y: 339.842102638 - z: -31.2993960408 - - speed: 3.66666674614 - acceleration_s: 0.0224882151414 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.1400001049041748 - theta: -1.83216295343 - accumulated_s: 25.88411108254 -} -adc_trajectory_point { - x: -131.018578714 - y: 339.806075759 - z: -31.2995150331 - - speed: 3.669444561 - acceleration_s: 0.0572459340474 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.1500000953674316 - theta: -1.83212542772 - accumulated_s: 25.92080552814 -} -adc_trajectory_point { - x: -131.028347707 - y: 339.770029 - z: -31.2995252535 - - speed: 3.669444561 - acceleration_s: 0.153243487934 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.1600000858306885 - theta: -1.8321122234 - accumulated_s: 25.95749997374 -} -adc_trajectory_point { - x: -131.038073745 - y: 339.73398671 - z: -31.2996486742 - - speed: 3.669444561 - acceleration_s: 0.00412568286448 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.1700000762939453 - theta: -1.83206449221 - accumulated_s: 25.99419441934 -} -adc_trajectory_point { - x: -131.047846748 - y: 339.697903145 - z: -31.2996453242 - - speed: 3.66388893127 - acceleration_s: 0.213592708517 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.1800000667572021 - theta: -1.8320369349 - accumulated_s: 26.03083330874 -} -adc_trajectory_point { - x: -131.057601704 - y: 339.661848463 - z: -31.2998498427 - - speed: 3.66388893127 - acceleration_s: 0.0729537930512 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.190000057220459 - theta: -1.8320153096 - accumulated_s: 26.06747219804 -} -adc_trajectory_point { - x: -131.057601704 - y: 339.661848463 - z: -31.2998498427 - - speed: 3.66666674614 - acceleration_s: 0.0729537930512 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.190000057220459 - theta: -1.8320153096 - accumulated_s: 26.10413886544 -} -adc_trajectory_point { - x: -131.077140665 - y: 339.589661023 - z: -31.3000360513 - - speed: 3.66666674614 - acceleration_s: 0.0613900097566 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.2100000381469727 - theta: -1.83190855949 - accumulated_s: 26.14080553294 -} -adc_trajectory_point { - x: -131.08696897 - y: 339.55356477 - z: -31.3001523307 - - speed: 3.66666674614 - acceleration_s: 0.0456917770021 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.22000002861023 - theta: -1.83192682468 - accumulated_s: 26.17747220044 -} -adc_trajectory_point { - x: -131.096779297 - y: 339.517449887 - z: -31.3002983937 - - speed: 3.669444561 - acceleration_s: 0.157094234461 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.2300000190734863 - theta: -1.83187575872 - accumulated_s: 26.21416664604 -} -adc_trajectory_point { - x: -131.106589695 - y: 339.481355823 - z: -31.3004826577 - - speed: 3.669444561 - acceleration_s: 0.0138360880559 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.2400000095367432 - theta: -1.83183937453 - accumulated_s: 26.25086109164 -} -adc_trajectory_point { - x: -131.116441605 - y: 339.445233672 - z: -31.3005322805 - - speed: 3.669444561 - acceleration_s: 0.110514537161 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.25 - theta: -1.83180888744 - accumulated_s: 26.28755553724 -} -adc_trajectory_point { - x: -131.126272548 - y: 339.409125322 - z: -31.3005999485 - - speed: 3.669444561 - acceleration_s: 0.0216516731092 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.2599999904632568 - theta: -1.83175332343 - accumulated_s: 26.32424998284 -} -adc_trajectory_point { - x: -131.136115777 - y: 339.373016152 - z: -31.3006376708 - - speed: 3.669444561 - acceleration_s: 0.0208072840911 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.2699999809265137 - theta: -1.83167516464 - accumulated_s: 26.36094442844 -} -adc_trajectory_point { - x: -131.145988643 - y: 339.33690518 - z: -31.3007889176 - - speed: 3.669444561 - acceleration_s: 0.0778664068072 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.27999997138977 - theta: -1.83166581714 - accumulated_s: 26.39763887404 -} -adc_trajectory_point { - x: -131.155856212 - y: 339.300765569 - z: -31.3008449012 - - speed: 3.669444561 - acceleration_s: 0.149877177892 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.2899999618530273 - theta: -1.83163130848 - accumulated_s: 26.43433331964 -} -adc_trajectory_point { - x: -131.165734938 - y: 339.264620127 - z: -31.3008489804 - - speed: 3.67222213745 - acceleration_s: 0.16331538138 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.2999999523162842 - theta: -1.831635156 - accumulated_s: 26.47105554104 -} -adc_trajectory_point { - x: -131.175566316 - y: 339.228455267 - z: -31.3009608481 - - speed: 3.67222213745 - acceleration_s: 0.135593390645 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.309999942779541 - theta: -1.83159067492 - accumulated_s: 26.50777776244 -} -adc_trajectory_point { - x: -131.185440819 - y: 339.192279291 - z: -31.3009583792 - - speed: 3.67222213745 - acceleration_s: 0.151254464873 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.3199999332427979 - theta: -1.83159968181 - accumulated_s: 26.54449998384 -} -adc_trajectory_point { - x: -131.195248563 - y: 339.156106709 - z: -31.3010963807 - - speed: 3.67222213745 - acceleration_s: 0.0250942985311 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.3300001621246338 - theta: -1.83156516734 - accumulated_s: 26.58122220514 -} -adc_trajectory_point { - x: -131.205084922 - y: 339.119887824 - z: -31.3011043938 - - speed: 3.67499995232 - acceleration_s: 0.167788912539 - curvature: 0.000918596439528 - curvature_change_rate: 0 - relative_time: 8.34000015258789 - theta: -1.83157327091 - accumulated_s: 26.61797220464 -} -adc_trajectory_point { - x: -131.214858687 - y: 339.083669224 - z: -31.3012608467 - - speed: 3.67499995232 - acceleration_s: 0.167788912539 - curvature: 0.000880321428239 - curvature_change_rate: -0.00104149691933 - relative_time: 8.3500001430511475 - theta: -1.83155865376 - accumulated_s: 26.65472220424 -} -adc_trajectory_point { - x: -131.224615283 - y: 339.04742901 - z: -31.3012495674 - - speed: 3.67499995232 - acceleration_s: 0.0822227314289 - curvature: 0.000880321428239 - curvature_change_rate: 0 - relative_time: 8.3600001335144043 - theta: -1.83153343829 - accumulated_s: 26.69147220374 -} -adc_trajectory_point { - x: -131.234406776 - y: 339.011172706 - z: -31.3013456613 - - speed: 3.67777776718 - acceleration_s: 0.113819625336 - curvature: 0.000803771467601 - curvature_change_rate: -0.00208141887531 - relative_time: 8.3700001239776611 - theta: -1.8315918382 - accumulated_s: 26.72824998144 -} -adc_trajectory_point { - x: -131.244131202 - y: 338.974905711 - z: -31.301438354 - - speed: 3.67777776718 - acceleration_s: 0.0554700617746 - curvature: 0.000803771467601 - curvature_change_rate: 0 - relative_time: 8.380000114440918 - theta: -1.83162134349 - accumulated_s: 26.76502775904 -} -adc_trajectory_point { - x: -131.25384955 - y: 338.938616238 - z: -31.3015423361 - - speed: 3.68055558205 - acceleration_s: 0.152532449879 - curvature: 0.00076549651643 - curvature_change_rate: -0.00103992319414 - relative_time: 8.3900001049041748 - theta: -1.83165084373 - accumulated_s: 26.80183331494 -} -adc_trajectory_point { - x: -131.25384955 - y: 338.938616238 - z: -31.3015423361 - - speed: 3.68055558205 - acceleration_s: 0.152532449879 - curvature: 0.00076549651643 - curvature_change_rate: 0 - relative_time: 8.3900001049041748 - theta: -1.83165084373 - accumulated_s: 26.83863887074 -} -adc_trajectory_point { - x: -131.273254626 - y: 338.86600178 - z: -31.301791084 - - speed: 3.68055558205 - acceleration_s: 0.154423085802 - curvature: 0.00076549651643 - curvature_change_rate: 0 - relative_time: 8.4100000858306885 - theta: -1.83177836445 - accumulated_s: 26.87544442654 -} -adc_trajectory_point { - x: -131.282905752 - y: 338.829664789 - z: -31.3019227739 - - speed: 3.68333339691 - acceleration_s: 0.10791718453 - curvature: 0.000727221583477 - curvature_change_rate: -0.00103913843329 - relative_time: 8.4200000762939453 - theta: -1.83179098684 - accumulated_s: 26.91227776054 -} -adc_trajectory_point { - x: -131.292559769 - y: 338.793302242 - z: -31.3020108668 - - speed: 3.68333339691 - acceleration_s: 0.180575814529 - curvature: 0.000727221583477 - curvature_change_rate: 0 - relative_time: 8.4300000667572021 - theta: -1.83185252348 - accumulated_s: 26.94911109444 -} -adc_trajectory_point { - x: -131.302179486 - y: 338.756936416 - z: -31.302163193 - - speed: 3.68611121178 - acceleration_s: 0.105572172671 - curvature: 0.000650671714967 - curvature_change_rate: -0.00207671076947 - relative_time: 8.440000057220459 - theta: -1.83189221851 - accumulated_s: 26.98597220664 -} -adc_trajectory_point { - x: -131.302179486 - y: 338.756936416 - z: -31.302163193 - - speed: 3.68888878822 - acceleration_s: 0.105572172671 - curvature: 0.000612396831201 - curvature_change_rate: -0.0010375721786 - relative_time: 8.440000057220459 - theta: -1.83189221851 - accumulated_s: 27.02286109444 -} -adc_trajectory_point { - x: -131.321386084 - y: 338.684148733 - z: -31.3023956306 - - speed: 3.68888878822 - acceleration_s: 0.0708134451255 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 8.4600000381469727 - theta: -1.83197773929 - accumulated_s: 27.05974998234 -} -adc_trajectory_point { - x: -131.330996058 - y: 338.647753089 - z: -31.3024842339 - - speed: 3.68888878822 - acceleration_s: 0.0391873945295 - curvature: 0.000612396831201 - curvature_change_rate: 0 - relative_time: 8.47000002861023 - theta: -1.83205288131 - accumulated_s: 27.09663887024 -} -adc_trajectory_point { - x: -131.340587888 - y: 338.611329648 - z: -31.3024761761 - - speed: 3.69166660309 - acceleration_s: 0.107011650936 - curvature: 0.000574121962009 - curvature_change_rate: -0.00103679105692 - relative_time: 8.4800000190734863 - theta: -1.83209904554 - accumulated_s: 27.13355553624 -} -adc_trajectory_point { - x: -131.350157567 - y: 338.574925673 - z: -31.3025584891 - - speed: 3.69166660309 - acceleration_s: -0.034284269404 - curvature: 0.000574121962009 - curvature_change_rate: 0 - relative_time: 8.4900000095367432 - theta: -1.83216386153 - accumulated_s: 27.17047220234 -} -adc_trajectory_point { - x: -131.359719855 - y: 338.538482962 - z: -31.3025128227 - - speed: 3.69444441795 - acceleration_s: 0.118293462844 - curvature: 0.000574121962009 - curvature_change_rate: 0 - relative_time: 8.5 - theta: -1.83218950412 - accumulated_s: 27.20741664644 -} -adc_trajectory_point { - x: -131.369269317 - y: 338.502063949 - z: -31.3025091486 - - speed: 3.69444441795 - acceleration_s: 0.0124151792347 - curvature: 0.000574121962009 - curvature_change_rate: 0 - relative_time: 8.5099999904632568 - theta: -1.83223507413 - accumulated_s: 27.24436109064 -} -adc_trajectory_point { - x: -131.378789178 - y: 338.465620489 - z: -31.302387909 - - speed: 3.69722223282 - acceleration_s: 0.029718293086 - curvature: 0.00053584710648 - curvature_change_rate: -0.00103523275364 - relative_time: 8.5199999809265137 - theta: -1.83225507449 - accumulated_s: 27.28133331304 -} -adc_trajectory_point { - x: -131.388316753 - y: 338.429162972 - z: -31.3022825252 - - speed: 3.69722223282 - acceleration_s: 0.12692532821 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.52999997138977 - theta: -1.8322771072 - accumulated_s: 27.31830553534 -} -adc_trajectory_point { - x: -131.397823933 - y: 338.392724876 - z: -31.3021739516 - - speed: 3.69722223282 - acceleration_s: -0.00662109430063 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.5399999618530273 - theta: -1.832332708 - accumulated_s: 27.35527775764 -} -adc_trajectory_point { - x: -131.407388895 - y: 338.356264182 - z: -31.3019151967 - - speed: 3.69722223282 - acceleration_s: -0.00662109430063 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.5499999523162842 - theta: -1.83237843888 - accumulated_s: 27.39224997994 -} -adc_trajectory_point { - x: -131.416904285 - y: 338.31981783 - z: -31.3017598446 - - speed: 3.69722223282 - acceleration_s: -0.00236487887047 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.559999942779541 - theta: -1.83241540315 - accumulated_s: 27.42922220234 -} -adc_trajectory_point { - x: -131.426426575 - y: 338.283351957 - z: -31.3013430377 - - speed: 3.70000004768 - acceleration_s: 0.028371706438 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.5699999332427979 - theta: -1.83241878261 - accumulated_s: 27.46622220274 -} -adc_trajectory_point { - x: -131.43595991 - y: 338.246907871 - z: -31.3009619135 - - speed: 3.70000004768 - acceleration_s: -0.0127730491426 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.5800001621246338 - theta: -1.83243947028 - accumulated_s: 27.50322220324 -} -adc_trajectory_point { - x: -131.445479111 - y: 338.210474133 - z: -31.3006140888 - - speed: 3.70000004768 - acceleration_s: -0.070433993924 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.59000015258789 - theta: -1.8324544003 - accumulated_s: 27.54022220374 -} -adc_trajectory_point { - x: -131.45503387 - y: 338.17403338 - z: -31.3001018483 - - speed: 3.70000004768 - acceleration_s: -0.070433993924 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.6000001430511475 - theta: -1.83249050491 - accumulated_s: 27.57722220424 -} -adc_trajectory_point { - x: -131.464535186 - y: 338.137613357 - z: -31.2997517921 - - speed: 3.70000004768 - acceleration_s: -0.0880824898025 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.6100001335144043 - theta: -1.8324624664 - accumulated_s: 27.61422220464 -} -adc_trajectory_point { - x: -131.474127088 - y: 338.101154263 - z: -31.2990875654 - - speed: 3.70000004768 - acceleration_s: 0.149555047142 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.6200001239776611 - theta: -1.83250666476 - accumulated_s: 27.65122220514 -} -adc_trajectory_point { - x: -131.483683473 - y: 338.064741751 - z: -31.2987857442 - - speed: 3.70000004768 - acceleration_s: 0.011688433096 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.630000114440918 - theta: -1.83251654948 - accumulated_s: 27.68822220564 -} -adc_trajectory_point { - x: -131.493265877 - y: 338.028255166 - z: -31.2981409179 - - speed: 3.70000004768 - acceleration_s: 0.239190739268 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.6400001049041748 - theta: -1.83249716564 - accumulated_s: 27.72522220614 -} -adc_trajectory_point { - x: -131.502857738 - y: 337.991810233 - z: -31.2977487864 - - speed: 3.70000004768 - acceleration_s: 0.0734298613112 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.6500000953674316 - theta: -1.83251383764 - accumulated_s: 27.76222220664 -} -adc_trajectory_point { - x: -131.512487687 - y: 337.955330837 - z: -31.2971710358 - - speed: 3.70277786255 - acceleration_s: 0.140154603522 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.6600000858306885 - theta: -1.8325214378 - accumulated_s: 27.79924998524 -} -adc_trajectory_point { - x: -131.522087455 - y: 337.918846195 - z: -31.2967666406 - - speed: 3.70277786255 - acceleration_s: 0.127838432431 - curvature: 0.000574121962009 - curvature_change_rate: 0.0010336794955 - relative_time: 8.6700000762939453 - theta: -1.83249570734 - accumulated_s: 27.83627776384 -} -adc_trajectory_point { - x: -131.531708209 - y: 337.882377424 - z: -31.2963586831 - - speed: 3.70277786255 - acceleration_s: 0.0684593042975 - curvature: 0.000574121962009 - curvature_change_rate: 0 - relative_time: 8.6800000667572021 - theta: -1.83247814077 - accumulated_s: 27.87330554244 -} -adc_trajectory_point { - x: -131.541360228 - y: 337.845861763 - z: -31.2958159689 - - speed: 3.70277786255 - acceleration_s: 0.156014190983 - curvature: 0.00053584710648 - curvature_change_rate: -0.0010336794955 - relative_time: 8.690000057220459 - theta: -1.8324976108 - accumulated_s: 27.91033332114 -} -adc_trajectory_point { - x: -131.541360228 - y: 337.845861763 - z: -31.2958159689 - - speed: 3.70277786255 - acceleration_s: 0.156014190983 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.690000057220459 - theta: -1.8324976108 - accumulated_s: 27.94736109974 -} -adc_trajectory_point { - x: -131.560649886 - y: 337.772871413 - z: -31.2949329298 - - speed: 3.70277786255 - acceleration_s: 0.109487997078 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.7100000381469727 - theta: -1.83254384308 - accumulated_s: 27.98438887834 -} -adc_trajectory_point { - x: -131.57027568 - y: 337.736368343 - z: -31.294543298 - - speed: 3.70277786255 - acceleration_s: 0.000564899935024 - curvature: 0.000574121962009 - curvature_change_rate: 0.0010336794955 - relative_time: 8.72000002861023 - theta: -1.83256203208 - accumulated_s: 28.02141665694 -} -adc_trajectory_point { - x: -131.579923332 - y: 337.699868223 - z: -31.2941764966 - - speed: 3.70277786255 - acceleration_s: -0.0411097084191 - curvature: 0.000574121962009 - curvature_change_rate: 0 - relative_time: 8.7300000190734863 - theta: -1.83255273706 - accumulated_s: 28.05844443564 -} -adc_trajectory_point { - x: -131.589561521 - y: 337.663334655 - z: -31.2937997337 - - speed: 3.70277786255 - acceleration_s: 0.123581769938 - curvature: 0.00053584710648 - curvature_change_rate: -0.0010336794955 - relative_time: 8.7400000095367432 - theta: -1.83257555353 - accumulated_s: 28.09547221424 -} -adc_trajectory_point { - x: -131.599202071 - y: 337.626824712 - z: -31.2934148507 - - speed: 3.70277786255 - acceleration_s: -0.0121917363633 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.75 - theta: -1.83259350435 - accumulated_s: 28.13249999284 -} -adc_trajectory_point { - x: -131.599202071 - y: 337.626824712 - z: -31.2934148507 - - speed: 3.70833325386 - acceleration_s: -0.0121917363633 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.75 - theta: -1.83259350435 - accumulated_s: 28.16958332534 -} -adc_trajectory_point { - x: -131.618780157 - y: 337.553650134 - z: -31.2927733092 - - speed: 3.70833325386 - acceleration_s: -0.0725997921008 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.7699999809265137 - theta: -1.83274640646 - accumulated_s: 28.20666665794 -} -adc_trajectory_point { - x: -131.628765907 - y: 337.517272111 - z: -31.2922379617 - - speed: 3.705555439 - acceleration_s: 0.075737330826 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.77999997138977 - theta: -1.83272447243 - accumulated_s: 28.24372221234 -} -adc_trajectory_point { - x: -131.638740986 - y: 337.480956091 - z: -31.2919738125 - - speed: 3.705555439 - acceleration_s: -0.0937081855589 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.7899999618530273 - theta: -1.83276958518 - accumulated_s: 28.28077776674 -} -adc_trajectory_point { - x: -131.648704064 - y: 337.444586733 - z: -31.2914515454 - - speed: 3.70277786255 - acceleration_s: -0.0937081855589 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.7999999523162842 - theta: -1.83275636361 - accumulated_s: 28.31780554534 -} -adc_trajectory_point { - x: -131.658705585 - y: 337.408247923 - z: -31.2911516726 - - speed: 3.70277786255 - acceleration_s: 0.0681437019346 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.809999942779541 - theta: -1.83281612598 - accumulated_s: 28.35483332394 -} -adc_trajectory_point { - x: -131.668661222 - y: 337.371907279 - z: -31.2907408178 - - speed: 3.70277786255 - acceleration_s: -0.099527039029 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.8199999332427979 - theta: -1.83281894125 - accumulated_s: 28.39186110254 -} -adc_trajectory_point { - x: -131.678659342 - y: 337.335557915 - z: -31.2902631406 - - speed: 3.70277786255 - acceleration_s: 0.0890027687472 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.8300001621246338 - theta: -1.83288298567 - accumulated_s: 28.42888888124 -} -adc_trajectory_point { - x: -131.688624377 - y: 337.299222625 - z: -31.2899421751 - - speed: 3.70000004768 - acceleration_s: -0.137580611445 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.84000015258789 - theta: -1.83291704751 - accumulated_s: 28.46588888164 -} -adc_trajectory_point { - x: -131.688624377 - y: 337.299222625 - z: -31.2899421751 - - speed: 3.70000004768 - acceleration_s: -0.137580611445 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.84000015258789 - theta: -1.83291704751 - accumulated_s: 28.50288888214 -} -adc_trajectory_point { - x: -131.708531599 - y: 337.226494257 - z: -31.2892645588 - - speed: 3.70000004768 - acceleration_s: 0.0396054650685 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.8600001335144043 - theta: -1.83296999317 - accumulated_s: 28.53988888264 -} -adc_trajectory_point { - x: -131.718479872 - y: 337.190087374 - z: -31.2888366133 - - speed: 3.70000004768 - acceleration_s: 0.180401379397 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.8700001239776611 - theta: -1.83298946318 - accumulated_s: 28.57688888314 -} -adc_trajectory_point { - x: -131.72839872 - y: 337.153695671 - z: -31.2885086285 - - speed: 3.70000004768 - acceleration_s: 0.0836099026704 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.880000114440918 - theta: -1.8330274929 - accumulated_s: 28.61388888364 -} -adc_trajectory_point { - x: -131.738315366 - y: 337.117265071 - z: -31.2881116476 - - speed: 3.70000004768 - acceleration_s: 0.135979254009 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.8900001049041748 - theta: -1.83304124774 - accumulated_s: 28.65088888404 -} -adc_trajectory_point { - x: -131.748245639 - y: 337.080881606 - z: -31.2878572233 - - speed: 3.70277786255 - acceleration_s: 0.135979254009 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.9000000953674316 - theta: -1.83309087791 - accumulated_s: 28.68791666274 -} -adc_trajectory_point { - x: -131.758150354 - y: 337.044486814 - z: -31.2875475967 - - speed: 3.70277786255 - acceleration_s: -0.0505321742459 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.9100000858306885 - theta: -1.83310802566 - accumulated_s: 28.72494444134 -} -adc_trajectory_point { - x: -131.768059188 - y: 337.008108499 - z: -31.2871869998 - - speed: 3.70277786255 - acceleration_s: -0.131845749929 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.9200000762939453 - theta: -1.833123165 - accumulated_s: 28.76197221994 -} -adc_trajectory_point { - x: -131.777970007 - y: 336.971717349 - z: -31.286901297 - - speed: 3.70277786255 - acceleration_s: -0.0451045930258 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.9300000667572021 - theta: -1.83313277831 - accumulated_s: 28.79899999854 -} -adc_trajectory_point { - x: -131.787917428 - y: 336.935312594 - z: -31.2865524534 - - speed: 3.70000004768 - acceleration_s: 0.127624506135 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.940000057220459 - theta: -1.83316101704 - accumulated_s: 28.83599999904 -} -adc_trajectory_point { - x: -131.787917428 - y: 336.935312594 - z: -31.2865524534 - - speed: 3.70000004768 - acceleration_s: 0.127624506135 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.940000057220459 - theta: -1.83316101704 - accumulated_s: 28.87299999954 -} -adc_trajectory_point { - x: -131.807778545 - y: 336.862541381 - z: -31.2859327458 - - speed: 3.70277786255 - acceleration_s: 0.0238426907985 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.9600000381469727 - theta: -1.83316117339 - accumulated_s: 28.91002777814 -} -adc_trajectory_point { - x: -131.81775047 - y: 336.826192022 - z: -31.285672551 - - speed: 3.70277786255 - acceleration_s: -0.0975240029295 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.97000002861023 - theta: -1.83319875823 - accumulated_s: 28.94705555674 -} -adc_trajectory_point { - x: -131.827726885 - y: 336.789829578 - z: -31.2853520252 - - speed: 3.70277786255 - acceleration_s: -0.0257528220648 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.9800000190734863 - theta: -1.83318785812 - accumulated_s: 28.98408333544 -} -adc_trajectory_point { - x: -131.837727948 - y: 336.753476516 - z: -31.2850953396 - - speed: 3.70277786255 - acceleration_s: -0.0293263028318 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.9900000095367432 - theta: -1.83316666831 - accumulated_s: 29.02111111404 -} -adc_trajectory_point { - x: -131.837727948 - y: 336.753476516 - z: -31.2850953396 - - speed: 3.70277786255 - acceleration_s: -0.0293263028318 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 8.9900000095367432 - theta: -1.83316666831 - accumulated_s: 29.05813889264 -} -adc_trajectory_point { - x: -131.857789913 - y: 336.680795797 - z: -31.2844986888 - - speed: 3.70277786255 - acceleration_s: -0.0859159215394 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 9.0099999904632568 - theta: -1.8331442283 - accumulated_s: 29.09516667124 -} -adc_trajectory_point { - x: -131.867858279 - y: 336.644447226 - z: -31.2842541337 - - speed: 3.70000004768 - acceleration_s: 0.0688763261144 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 9.0199999809265137 - theta: -1.83314503834 - accumulated_s: 29.13216667174 -} -adc_trajectory_point { - x: -131.877926522 - y: 336.608126829 - z: -31.2838689461 - - speed: 3.70000004768 - acceleration_s: -0.0674539453227 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 9.02999997138977 - theta: -1.83312264266 - accumulated_s: 29.16916667224 -} -adc_trajectory_point { - x: -131.888045007 - y: 336.571811491 - z: -31.2836882854 - - speed: 3.70000004768 - acceleration_s: 0.0021468945572 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 9.0399999618530273 - theta: -1.83312505396 - accumulated_s: 29.20616667274 -} -adc_trajectory_point { - x: -131.898139316 - y: 336.53546611 - z: -31.2834078707 - - speed: 3.70000004768 - acceleration_s: 0.0893199435897 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 9.0499999523162842 - theta: -1.83311317301 - accumulated_s: 29.24316667314 -} -adc_trajectory_point { - x: -131.908238826 - y: 336.499157166 - z: -31.2832412831 - - speed: 3.70277786255 - acceleration_s: -0.0335673719355 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 9.059999942779541 - theta: -1.83313955653 - accumulated_s: 29.28019445184 -} -adc_trajectory_point { - x: -131.918309583 - y: 336.462810372 - z: -31.282883063 - - speed: 3.70277786255 - acceleration_s: -0.0254764834384 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 9.0699999332427979 - theta: -1.83309929172 - accumulated_s: 29.31722223044 -} -adc_trajectory_point { - x: -131.928360849 - y: 336.426486092 - z: -31.2826836845 - - speed: 3.70277786255 - acceleration_s: -0.0254764834384 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 9.0800001621246338 - theta: -1.83311098593 - accumulated_s: 29.35425000904 -} -adc_trajectory_point { - x: -131.938423434 - y: 336.390161578 - z: -31.2824502764 - - speed: 3.70277786255 - acceleration_s: -0.0668495592853 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 9.09000015258789 - theta: -1.83314376077 - accumulated_s: 29.39127778764 -} -adc_trajectory_point { - x: -131.938423434 - y: 336.390161578 - z: -31.2824502764 - - speed: 3.70000004768 - acceleration_s: -0.0668495592853 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 9.09000015258789 - theta: -1.83314376077 - accumulated_s: 29.42827778814 -} -adc_trajectory_point { - x: -131.958419922 - y: 336.317464015 - z: -31.2820673492 - - speed: 3.70000004768 - acceleration_s: 0.0778040294489 - curvature: 0.00053584710648 - curvature_change_rate: 0 - relative_time: 9.1100001335144043 - theta: -1.83315452385 - accumulated_s: 29.46527778864 -} -adc_trajectory_point { - x: -131.968373492 - y: 336.28110898 - z: -31.2818031767 - - speed: 3.69722223282 - acceleration_s: 0.00340458911614 - curvature: 0.000497572263703 - curvature_change_rate: -0.00103523240872 - relative_time: 9.1200001239776611 - theta: -1.83314264465 - accumulated_s: 29.50225001094 -} -adc_trajectory_point { - x: -131.978316981 - y: 336.244732181 - z: -31.2816065559 - - speed: 3.69722223282 - acceleration_s: 0.0857427683471 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.130000114440918 - theta: -1.83313270365 - accumulated_s: 29.53922223334 -} -adc_trajectory_point { - x: -131.988291681 - y: 336.208387714 - z: -31.2813490098 - - speed: 3.69722223282 - acceleration_s: -0.0700423239248 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.1400001049041748 - theta: -1.83319844934 - accumulated_s: 29.57619445564 -} -adc_trajectory_point { - x: -131.998212134 - y: 336.17206633 - z: -31.2812162284 - - speed: 3.69722223282 - acceleration_s: -0.0700423239248 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.1500000953674316 - theta: -1.83323643575 - accumulated_s: 29.61316667794 -} -adc_trajectory_point { - x: -132.008181273 - y: 336.135707756 - z: -31.2809310397 - - speed: 3.70000004768 - acceleration_s: -0.0460476408749 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.1600000858306885 - theta: -1.83327856135 - accumulated_s: 29.65016667844 -} -adc_trajectory_point { - x: -132.018130384 - y: 336.099390106 - z: -31.2807655167 - - speed: 3.70000004768 - acceleration_s: -0.115812291568 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.1700000762939453 - theta: -1.83331377557 - accumulated_s: 29.68716667894 -} -adc_trajectory_point { - x: -132.028097214 - y: 336.063064907 - z: -31.2804642152 - - speed: 3.70000004768 - acceleration_s: -0.0634537214815 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.1800000667572021 - theta: -1.83333034688 - accumulated_s: 29.72416667934 -} -adc_trajectory_point { - x: -132.038067381 - y: 336.026769643 - z: -31.2803229606 - - speed: 3.70000004768 - acceleration_s: -0.118376814908 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.190000057220459 - theta: -1.83337965058 - accumulated_s: 29.76116667984 -} -adc_trajectory_point { - x: -132.038067381 - y: 336.026769643 - z: -31.2803229606 - - speed: 3.70000004768 - acceleration_s: -0.118376814908 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.190000057220459 - theta: -1.83337965058 - accumulated_s: 29.79816668034 -} -adc_trajectory_point { - x: -132.057996965 - y: 335.954147235 - z: -31.2798358034 - - speed: 3.70000004768 - acceleration_s: -0.0808539505321 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.2100000381469727 - theta: -1.83335918303 - accumulated_s: 29.83516668084 -} -adc_trajectory_point { - x: -132.068021459 - y: 335.917832418 - z: -31.2795281885 - - speed: 3.70277786255 - acceleration_s: 0.112236915771 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.22000002861023 - theta: -1.83338053939 - accumulated_s: 29.87219445944 -} -adc_trajectory_point { - x: -132.077989439 - y: 335.881557276 - z: -31.2793505248 - - speed: 3.70277786255 - acceleration_s: -0.133367470484 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.2300000190734863 - theta: -1.83338886045 - accumulated_s: 29.90922223804 -} -adc_trajectory_point { - x: -132.077989439 - y: 335.881557276 - z: -31.2793505248 - - speed: 3.705555439 - acceleration_s: -0.133367470484 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.2300000190734863 - theta: -1.83338886045 - accumulated_s: 29.94627779244 -} -adc_trajectory_point { - x: -132.097946774 - y: 335.808984003 - z: -31.2788987225 - - speed: 3.705555439 - acceleration_s: -0.0128794777785 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.25 - theta: -1.83344914213 - accumulated_s: 29.98333334684 -} -adc_trajectory_point { - x: -132.107904573 - y: 335.772678861 - z: -31.2787367748 - - speed: 3.70833325386 - acceleration_s: 0.0281507078451 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.2599999904632568 - theta: -1.83344925793 - accumulated_s: 30.02041667934 -} -adc_trajectory_point { - x: -132.117859476 - y: 335.736392537 - z: -31.2785454029 - - speed: 3.70833325386 - acceleration_s: -0.0324692451399 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.2699999809265137 - theta: -1.83346644884 - accumulated_s: 30.05750001194 -} -adc_trajectory_point { - x: -132.127804151 - y: 335.700106117 - z: -31.2784009278 - - speed: 3.705555439 - acceleration_s: -0.0499122077425 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.27999997138977 - theta: -1.83347854463 - accumulated_s: 30.09455556634 -} -adc_trajectory_point { - x: -132.13774501 - y: 335.663806691 - z: -31.2781876344 - - speed: 3.705555439 - acceleration_s: -0.0204625835762 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.2899999618530273 - theta: -1.83349770563 - accumulated_s: 30.13161112074 -} -adc_trajectory_point { - x: -132.147647431 - y: 335.627528584 - z: -31.2781113992 - - speed: 3.70277786255 - acceleration_s: -0.0204625835762 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.2999999523162842 - theta: -1.83347794346 - accumulated_s: 30.16863889934 -} -adc_trajectory_point { - x: -132.157598613 - y: 335.591221714 - z: -31.2779482659 - - speed: 3.70277786255 - acceleration_s: 0.0148677812372 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.309999942779541 - theta: -1.83353368127 - accumulated_s: 30.20566667794 -} -adc_trajectory_point { - x: -132.167486542 - y: 335.554938476 - z: -31.2779333852 - - speed: 3.70833325386 - acceleration_s: -0.0861770774704 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.3199999332427979 - theta: -1.83352248502 - accumulated_s: 30.24275001054 -} -adc_trajectory_point { - x: -132.177389065 - y: 335.518639297 - z: -31.2777470071 - - speed: 3.70833325386 - acceleration_s: -0.0108284926706 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.3300001621246338 - theta: -1.83352944732 - accumulated_s: 30.27983334304 -} -adc_trajectory_point { - x: -132.187282044 - y: 335.482382948 - z: -31.277702542 - - speed: 3.705555439 - acceleration_s: -0.170504335112 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.34000015258789 - theta: -1.8335351443 - accumulated_s: 30.31688889744 -} -adc_trajectory_point { - x: -132.197146705 - y: 335.446071787 - z: -31.2775664376 - - speed: 3.705555439 - acceleration_s: 0.064874406577 - curvature: 0.000497572263703 - curvature_change_rate: 0 - relative_time: 9.3500001430511475 - theta: -1.83348356256 - accumulated_s: 30.35394445184 -} -adc_trajectory_point { - x: -132.2070435 - y: 335.409805434 - z: -31.2775769858 - - speed: 3.70277786255 - acceleration_s: 0.064874406577 - curvature: 0.000459297432768 - curvature_change_rate: -0.0010336788313 - relative_time: 9.3600001335144043 - theta: -1.8335215536 - accumulated_s: 30.39097223044 -} -adc_trajectory_point { - x: -132.216949518 - y: 335.373541721 - z: -31.2774795797 - - speed: 3.70277786255 - acceleration_s: -0.0377638359669 - curvature: 0.000459297432768 - curvature_change_rate: 0 - relative_time: 9.3700001239776611 - theta: -1.83352852181 - accumulated_s: 30.42800000904 -} -adc_trajectory_point { - x: -132.226823516 - y: 335.337259561 - z: -31.2774208793 - - speed: 3.70000004768 - acceleration_s: -0.019376836181 - curvature: 0.000421022612763 - curvature_change_rate: -0.00103445458139 - relative_time: 9.380000114440918 - theta: -1.83350958508 - accumulated_s: 30.46500000954 -} -adc_trajectory_point { - x: -132.236712689 - y: 335.301008906 - z: -31.2773537524 - - speed: 3.70000004768 - acceleration_s: -0.0714875758623 - curvature: 0.000421022612763 - curvature_change_rate: 0 - relative_time: 9.3900001049041748 - theta: -1.83349703975 - accumulated_s: 30.50200001004 -} -adc_trajectory_point { - x: -132.236712689 - y: 335.301008906 - z: -31.2773537524 - - speed: 3.69722223282 - acceleration_s: -0.0714875758623 - curvature: 0.000382747802778 - curvature_change_rate: -0.0010352315218 - relative_time: 9.3900001049041748 - theta: -1.83349703975 - accumulated_s: 30.53897223234 -} -adc_trajectory_point { - x: -132.256508384 - y: 335.228520503 - z: -31.2773318859 - - speed: 3.69722223282 - acceleration_s: -0.0320372389986 - curvature: 0.000382747802778 - curvature_change_rate: 0 - relative_time: 9.4100000858306885 - theta: -1.83347645423 - accumulated_s: 30.575944454640002 -} -adc_trajectory_point { - x: -132.266447045 - y: 335.19228644 - z: -31.2772535691 - - speed: 3.69166660309 - acceleration_s: -0.0277083486613 - curvature: 0.000382747802778 - curvature_change_rate: 0 - relative_time: 9.4200000762939453 - theta: -1.83349382294 - accumulated_s: 30.61286112074 -} -adc_trajectory_point { - x: -132.276349856 - y: 335.156047197 - z: -31.2773276428 - - speed: 3.69166660309 - acceleration_s: 0.0097882489765 - curvature: 0.000382747802778 - curvature_change_rate: 0 - relative_time: 9.4300000667572021 - theta: -1.83346983411 - accumulated_s: 30.649777786740003 -} -adc_trajectory_point { - x: -132.28627245 - y: 335.119809234 - z: -31.2772213072 - - speed: 3.69166660309 - acceleration_s: -0.0203050805543 - curvature: 0.000306198182417 - curvature_change_rate: -0.00207357891682 - relative_time: 9.440000057220459 - theta: -1.83346225214 - accumulated_s: 30.68669445274 -} -adc_trajectory_point { - x: -132.28627245 - y: 335.119809234 - z: -31.2772213072 - - speed: 3.69166660309 - acceleration_s: -0.0203050805543 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 9.440000057220459 - theta: -1.83346225214 - accumulated_s: 30.723611118839997 -} -adc_trajectory_point { - x: -132.306121853 - y: 335.04740141 - z: -31.2771796137 - - speed: 3.68888878822 - acceleration_s: -0.113497308062 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 9.4600000381469727 - theta: -1.83348980646 - accumulated_s: 30.76050000664 -} -adc_trajectory_point { - x: -132.316022213 - y: 335.011197764 - z: -31.2771620173 - - speed: 3.68888878822 - acceleration_s: -0.10800009485 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 9.47000002861023 - theta: -1.83346983723 - accumulated_s: 30.79738889454 -} -adc_trajectory_point { - x: -132.325942061 - y: 334.974998993 - z: -31.2771311263 - - speed: 3.68611121178 - acceleration_s: -0.10800009485 - curvature: 0.000267923397025 - curvature_change_rate: -0.00103835134625 - relative_time: 9.4800000190734863 - theta: -1.83348745956 - accumulated_s: 30.834250006639998 -} -adc_trajectory_point { - x: -132.335866566 - y: 334.938789824 - z: -31.2771076933 - - speed: 3.68611121178 - acceleration_s: 0.00340698607689 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.4900000095367432 - theta: -1.83351794815 - accumulated_s: 30.87111111884 -} -adc_trajectory_point { - x: -132.34579007 - y: 334.902605896 - z: -31.2770189103 - - speed: 3.68611121178 - acceleration_s: 0.00340698607689 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.5 - theta: -1.83356104399 - accumulated_s: 30.907972230939997 -} -adc_trajectory_point { - x: -132.34579007 - y: 334.902605896 - z: -31.2770189103 - - speed: 3.68611121178 - acceleration_s: -0.0598562763837 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.5 - theta: -1.83356104399 - accumulated_s: 30.944833343040003 -} -adc_trajectory_point { - x: -132.365628196 - y: 334.830263087 - z: -31.2768508997 - - speed: 3.68611121178 - acceleration_s: -0.0852656314668 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.5199999809265137 - theta: -1.83361914369 - accumulated_s: 30.98169445514 -} -adc_trajectory_point { - x: -132.375541309 - y: 334.794117251 - z: -31.2767734025 - - speed: 3.68611121178 - acceleration_s: -0.119545102887 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.52999997138977 - theta: -1.83362740513 - accumulated_s: 31.01855556724 -} -adc_trajectory_point { - x: -132.385502938 - y: 334.757982983 - z: -31.2767456351 - - speed: 3.68611121178 - acceleration_s: -0.0521183684964 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.5399999618530273 - theta: -1.83369129463 - accumulated_s: 31.05541667934 -} -adc_trajectory_point { - x: -132.395440882 - y: 334.721841131 - z: -31.2765656896 - - speed: 3.68611121178 - acceleration_s: -0.0521183684964 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.5499999523162842 - theta: -1.8337147282 - accumulated_s: 31.09227779154 -} -adc_trajectory_point { - x: -132.405356414 - y: 334.685726786 - z: -31.2765603065 - - speed: 3.68611121178 - acceleration_s: -0.10309123563 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.559999942779541 - theta: -1.83373368173 - accumulated_s: 31.129138903639998 -} -adc_trajectory_point { - x: -132.415285953 - y: 334.649572979 - z: -31.27638816 - - speed: 3.68611121178 - acceleration_s: 0.0632254496802 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.5699999332427979 - theta: -1.83377606174 - accumulated_s: 31.166000015740003 -} -adc_trajectory_point { - x: -132.425176129 - y: 334.613471669 - z: -31.276399726 - - speed: 3.68611121178 - acceleration_s: -0.16557725373 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.5800001621246338 - theta: -1.83382686471 - accumulated_s: 31.202861127840002 -} -adc_trajectory_point { - x: -132.435087263 - y: 334.577329929 - z: -31.2761858553 - - speed: 3.68611121178 - acceleration_s: 0.0030236410683 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.59000015258789 - theta: -1.83388921224 - accumulated_s: 31.23972223994 -} -adc_trajectory_point { - x: -132.444935072 - y: 334.541233548 - z: -31.2762448108 - - speed: 3.68611121178 - acceleration_s: 0.0030236410683 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.6000001430511475 - theta: -1.83393036295 - accumulated_s: 31.27658335214 -} -adc_trajectory_point { - x: -132.454787152 - y: 334.505092022 - z: -31.2761642355 - - speed: 3.68611121178 - acceleration_s: -0.194202137923 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.6100001335144043 - theta: -1.83397956297 - accumulated_s: 31.31344446424 -} -adc_trajectory_point { - x: -132.464602605 - y: 334.468987353 - z: -31.2762580309 - - speed: 3.68333339691 - acceleration_s: -0.0921553495998 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.6200001239776611 - theta: -1.83400638466 - accumulated_s: 31.35027779814 -} -adc_trajectory_point { - x: -132.474450074 - y: 334.432839964 - z: -31.2761457358 - - speed: 3.68333339691 - acceleration_s: -0.0189713502264 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.630000114440918 - theta: -1.8340811556 - accumulated_s: 31.38711113214 -} -adc_trajectory_point { - x: -132.484249792 - y: 334.396733716 - z: -31.2762143593 - - speed: 3.68055558205 - acceleration_s: -0.113972390304 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.6400001049041748 - theta: -1.83411691341 - accumulated_s: 31.42391668794 -} -adc_trajectory_point { - x: -132.484249792 - y: 334.396733716 - z: -31.2762143593 - - speed: 3.68055558205 - acceleration_s: -0.113972390304 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.6400001049041748 - theta: -1.83411691341 - accumulated_s: 31.46072224374 -} -adc_trajectory_point { - x: -132.503793178 - y: 334.324478932 - z: -31.2763494886 - - speed: 3.67777776718 - acceleration_s: -0.00754373244004 - curvature: 0.00022964861801 - curvature_change_rate: -0.00104070396415 - relative_time: 9.6600000858306885 - theta: -1.83414336428 - accumulated_s: 31.497500021439997 -} -adc_trajectory_point { - x: -132.513547372 - y: 334.288355637 - z: -31.2764242683 - - speed: 3.67777776718 - acceleration_s: -0.0429540512884 - curvature: 0.00022964861801 - curvature_change_rate: 0 - relative_time: 9.6700000762939453 - theta: -1.8341249813 - accumulated_s: 31.53427779914 -} -adc_trajectory_point { - x: -132.523340475 - y: 334.25224665 - z: -31.2765155546 - - speed: 3.67499995232 - acceleration_s: -0.0641137927879 - curvature: 0.00022964861801 - curvature_change_rate: 0 - relative_time: 9.6800000667572021 - theta: -1.83413665565 - accumulated_s: 31.571027798640003 -} -adc_trajectory_point { - x: -132.533120517 - y: 334.216149147 - z: -31.2766190059 - - speed: 3.67499995232 - acceleration_s: -0.0601449302991 - curvature: 0.00022964861801 - curvature_change_rate: 0 - relative_time: 9.690000057220459 - theta: -1.83412861727 - accumulated_s: 31.60777779814 -} -adc_trajectory_point { - x: -132.533120517 - y: 334.216149147 - z: -31.2766190059 - - speed: 3.67777776718 - acceleration_s: -0.0601449302991 - curvature: 0.00022964861801 - curvature_change_rate: 0 - relative_time: 9.690000057220459 - theta: -1.83412861727 - accumulated_s: 31.644555575840002 -} -adc_trajectory_point { - x: -132.55274699 - y: 334.143993175 - z: -31.2769757332 - - speed: 3.67777776718 - acceleration_s: -0.0473853953028 - curvature: 0.00022964861801 - curvature_change_rate: 0 - relative_time: 9.7100000381469727 - theta: -1.83411576045 - accumulated_s: 31.681333353539998 -} -adc_trajectory_point { - x: -132.562626884 - y: 334.107918546 - z: -31.2770130374 - - speed: 3.67777776718 - acceleration_s: 0.00380957724767 - curvature: 0.00022964861801 - curvature_change_rate: 0 - relative_time: 9.72000002861023 - theta: -1.83410191979 - accumulated_s: 31.71811113124 -} -adc_trajectory_point { - x: -132.572521441 - y: 334.071895683 - z: -31.2772678779 - - speed: 3.67777776718 - acceleration_s: -0.148643972092 - curvature: 0.00022964861801 - curvature_change_rate: 0 - relative_time: 9.7300000190734863 - theta: -1.83408614397 - accumulated_s: 31.75488890884 -} -adc_trajectory_point { - x: -132.582445074 - y: 334.035855242 - z: -31.2773258034 - - speed: 3.67777776718 - acceleration_s: -0.0647918424753 - curvature: 0.00022964861801 - curvature_change_rate: 0 - relative_time: 9.7400000095367432 - theta: -1.83404132243 - accumulated_s: 31.791666686539997 -} -adc_trajectory_point { - x: -132.592399241 - y: 333.999878115 - z: -31.2775527621 - - speed: 3.67777776718 - acceleration_s: -0.0647918424753 - curvature: 0.00022964861801 - curvature_change_rate: 0 - relative_time: 9.75 - theta: -1.83403700259 - accumulated_s: 31.82844446424 -} -adc_trajectory_point { - x: -132.602362924 - y: 333.963870573 - z: -31.277556641 - - speed: 3.68055558205 - acceleration_s: -0.0280492656679 - curvature: 0.00022964861801 - curvature_change_rate: 0 - relative_time: 9.7599999904632568 - theta: -1.83400798623 - accumulated_s: 31.86525002004 -} -adc_trajectory_point { - x: -132.612571826 - y: 333.927896006 - z: -31.2778558498 - - speed: 3.68055558205 - acceleration_s: -0.248044298396 - curvature: 0.00022964861801 - curvature_change_rate: 0 - relative_time: 9.7699999809265137 - theta: -1.8340272878 - accumulated_s: 31.902055575840002 -} -adc_trajectory_point { - x: -132.622765624 - y: 333.892007101 - z: -31.2777975388 - - speed: 3.68055558205 - acceleration_s: -0.0666630968565 - curvature: 0.00022964861801 - curvature_change_rate: 0 - relative_time: 9.77999997138977 - theta: -1.83403050578 - accumulated_s: 31.938861131640003 -} -adc_trajectory_point { - x: -132.632923405 - y: 333.856177461 - z: -31.2781809671 - - speed: 3.68055558205 - acceleration_s: -0.142098543328 - curvature: 0.00022964861801 - curvature_change_rate: 0 - relative_time: 9.7899999618530273 - theta: -1.83401242033 - accumulated_s: 31.97566668754 -} -adc_trajectory_point { - x: -132.643105006 - y: 333.820311515 - z: -31.2781149456 - - speed: 3.68055558205 - acceleration_s: -0.142098543328 - curvature: 0.000267923397025 - curvature_change_rate: 0.00103991851671 - relative_time: 9.7999999523162842 - theta: -1.83404376709 - accumulated_s: 32.01247224334 -} -adc_trajectory_point { - x: -132.653242664 - y: 333.784452432 - z: -31.2782685002 - - speed: 3.68055558205 - acceleration_s: -0.00840818446238 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.809999942779541 - theta: -1.83400732259 - accumulated_s: 32.04927779914 -} -adc_trajectory_point { - x: -132.66338165 - y: 333.748605675 - z: -31.2782534566 - - speed: 3.67777776718 - acceleration_s: -0.0634310379344 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.8199999332427979 - theta: -1.83405144873 - accumulated_s: 32.08605557684 -} -adc_trajectory_point { - x: -132.67344709 - y: 333.712761016 - z: -31.2785384571 - - speed: 3.67777776718 - acceleration_s: -0.112519250137 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.8300001621246338 - theta: -1.83405031778 - accumulated_s: 32.12283335444 -} -adc_trajectory_point { - x: -132.683508975 - y: 333.676922344 - z: -31.2785902759 - - speed: 3.67777776718 - acceleration_s: -0.110672510261 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.84000015258789 - theta: -1.83408744353 - accumulated_s: 32.15961113214 -} -adc_trajectory_point { - x: -132.683508975 - y: 333.676922344 - z: -31.2785902759 - - speed: 3.67777776718 - acceleration_s: -0.110672510261 - curvature: 0.000267923397025 - curvature_change_rate: 0 - relative_time: 9.84000015258789 - theta: -1.83408744353 - accumulated_s: 32.19638890984 -} -adc_trajectory_point { - x: -132.70359128 - y: 333.605290692 - z: -31.2786425408 - - speed: 3.67777776718 - acceleration_s: -0.0845600592295 - curvature: 0.000306198182417 - curvature_change_rate: 0.00104070413751 - relative_time: 9.8600001335144043 - theta: -1.83417351223 - accumulated_s: 32.23316668754 -} -adc_trajectory_point { - x: -132.713602221 - y: 333.569474338 - z: -31.2788601648 - - speed: 3.67777776718 - acceleration_s: -0.0420496219288 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 9.8700001239776611 - theta: -1.83421945913 - accumulated_s: 32.26994446514 -} -adc_trajectory_point { - x: -132.723598214 - y: 333.533659103 - z: -31.2789625516 - - speed: 3.669444561 - acceleration_s: -0.0282229879329 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 9.880000114440918 - theta: -1.83426703222 - accumulated_s: 32.30663891074 -} -adc_trajectory_point { - x: -132.733623096 - y: 333.497845819 - z: -31.2790034963 - - speed: 3.669444561 - acceleration_s: -0.0417450219111 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 9.8900001049041748 - theta: -1.83432680577 - accumulated_s: 32.34333335634 -} -adc_trajectory_point { - x: -132.733623096 - y: 333.497845819 - z: -31.2790034963 - - speed: 3.669444561 - acceleration_s: -0.0417450219111 - curvature: 0.000306198182417 - curvature_change_rate: 0 - relative_time: 9.8900001049041748 - theta: -1.83432680577 - accumulated_s: 32.38002780204 -} -estop { - is_estop: false -} -gear: GEAR_DRIVE diff --git a/modules/tools/planning/plot_trajectory/example_data/BUILD b/modules/tools/planning/plot_trajectory/example_data/BUILD deleted file mode 100644 index 173dfa24854..00000000000 --- a/modules/tools/planning/plot_trajectory/example_data/BUILD +++ /dev/null @@ -1,6 +0,0 @@ -package(default_visibility = ["//visibility:public"]) - -filegroup( - name = "example_data", - srcs = glob(["*.txt"]), -) diff --git a/modules/tools/planning/plot_trajectory/main.py b/modules/tools/planning/plot_trajectory/main.py deleted file mode 100644 index 0d4ed0b695a..00000000000 --- a/modules/tools/planning/plot_trajectory/main.py +++ /dev/null @@ -1,143 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import sys - -import matplotlib.pyplot as plt - -import modules.tools.common.proto_utils as proto_utils -from modules.tools.planning.plot_trajectory import mkz_polygon -from modules.common_msgs.planning_msgs.planning_pb2 import ADCTrajectory -from modules.common_msgs.localization_msgs.localization_pb2 import LocalizationEstimate - - -def plot_trajectory(planning_pb, ax): - points_x = [] - points_y = [] - points_t = [] - base_time_sec = planning_pb.header.timestamp_sec - for trajectory_point in planning_pb.adc_trajectory_point: - points_x.append(trajectory_point.x) - points_y.append(trajectory_point.y) - points_t.append(base_time_sec + trajectory_point.relative_time) - ax.plot(points_x, points_y, "r.") - - -def find_closest_t(points_t, current_t): - if len(points_t) == 0: - return -1 - if len(points_t) == 1: - return points_t[0] - if len(points_t) == 2: - if abs(points_t[0] - current_t) < abs(points_t[1] - current_t): - return points_t[0] - else: - return points_t[1] - if points_t[len(points_t) // 2] > current_t: - return find_closest_t(points_t[0:len(points_t) // 2], current_t) - elif points_t[len(points_t) // 2] < current_t: - return find_closest_t(points_t[len(points_t) // 2 + 1:], current_t) - else: - return current_t - - -def find_closest_traj_point(planning_pb, current_t): - points_x = [] - points_y = [] - points_t = [] - base_time_sec = planning_pb.header.timestamp_sec - for trajectory_point in planning_pb.adc_trajectory_point: - points_x.append(trajectory_point.x) - points_y.append(trajectory_point.y) - points_t.append(base_time_sec + trajectory_point.relative_time) - - matched_t = find_closest_t(points_t, current_t) - idx = points_t.index(matched_t) - return planning_pb.adc_trajectory_point[idx] - - -def plot_traj_point(planning_pb, traj_point, ax): - matched_t = planning_pb.header.timestamp_sec \ - + traj_point.relative_time - ax.plot([traj_point.x], [traj_point.y], "bs") - content = "t = " + str(matched_t) + "\n" - content += "speed = " + str(traj_point.speed) + "\n" - content += "acc = " + str(traj_point.acceleration_s) - lxy = [-80, -80] - ax.annotate( - content, - xy=(traj_point.x, traj_point.y), - xytext=lxy, - textcoords='offset points', - ha='right', - va='top', - bbox=dict(boxstyle='round,pad=0.5', fc='yellow', alpha=0.3), - arrowprops=dict(arrowstyle='->', connectionstyle='arc3,rad=0'), - alpha=0.8) - - -def plot_vehicle(localization_pb, ax): - loc_x = [localization_pb.pose.position.x] - loc_y = [localization_pb.pose.position.y] - current_t = localization_pb.header.timestamp_sec - ax.plot(loc_x, loc_y, "bo") - position = [] - position.append(localization_pb.pose.position.x) - position.append(localization_pb.pose.position.y) - position.append(localization_pb.pose.position.z) - - mkz_polygon.plot(position, localization_pb.pose.heading, ax) - content = "t = " + str(current_t) + "\n" - content += "speed @y = " + \ - str(localization_pb.pose.linear_velocity.y) + "\n" - content += "acc @y = " + \ - str(localization_pb.pose.linear_acceleration_vrf.y) - lxy = [-80, 80] - ax.annotate( - content, - xy=(loc_x[0], loc_y[0]), - xytext=lxy, - textcoords='offset points', - ha='left', - va='top', - bbox=dict(boxstyle='round,pad=0.5', fc='yellow', alpha=0.3), - arrowprops=dict(arrowstyle='->', connectionstyle='arc3,rad=0'), - alpha=0.8) - - -if __name__ == "__main__": - if len(sys.argv) < 2: - print("usage: %s " % sys.argv[0]) - sys.exit(0) - - planning_pb_file = sys.argv[1] - localization_pb_file = sys.argv[2] - planning_pb = proto_utils.get_pb_from_text_file( - planning_pb_file, ADCTrajectory()) - localization_pb = proto_utils.get_pb_from_text_file( - localization_pb_file, LocalizationEstimate()) - - plot_trajectory(planning_pb, plt) - plot_vehicle(localization_pb, plt) - - current_t = localization_pb.header.timestamp_sec - trajectory_point = find_closest_traj_point(planning_pb, current_t) - plot_traj_point(planning_pb, trajectory_point, plt) - - plt.axis('equal') - plt.show() diff --git a/modules/tools/planning/plot_trajectory/mkz_polygon.py b/modules/tools/planning/plot_trajectory/mkz_polygon.py deleted file mode 100644 index 41789b0cd54..00000000000 --- a/modules/tools/planning/plot_trajectory/mkz_polygon.py +++ /dev/null @@ -1,64 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import math - - -def get(position, heading): - - front_edge_to_center = 3.89 - back_edge_to_center = 1.043 - left_edge_to_center = 1.055 - right_edge_to_center = 1.055 - - cos_h = math.cos(heading) - sin_h = math.sin(heading) - # (p3) -------- (p0) - # | o | - # (p2) -------- (p1) - p0_x, p0_y = front_edge_to_center, left_edge_to_center - p1_x, p1_y = front_edge_to_center, -right_edge_to_center - p2_x, p2_y = -back_edge_to_center, -left_edge_to_center - p3_x, p3_y = -back_edge_to_center, right_edge_to_center - - p0_x, p0_y = p0_x * cos_h - p0_y * sin_h, p0_x * sin_h + p0_y * cos_h - p1_x, p1_y = p1_x * cos_h - p1_y * sin_h, p1_x * sin_h + p1_y * cos_h - p2_x, p2_y = p2_x * cos_h - p2_y * sin_h, p2_x * sin_h + p2_y * cos_h - p3_x, p3_y = p3_x * cos_h - p3_y * sin_h, p3_x * sin_h + p3_y * cos_h - - [x, y, z] = position - polygon = [] - polygon.append([p0_x + x, p0_y + y, 0]) - polygon.append([p1_x + x, p1_y + y, 0]) - polygon.append([p2_x + x, p2_y + y, 0]) - polygon.append([p3_x + x, p3_y + y, 0]) - return polygon - - -def plot(position, quaternion, ax): - polygon = get(position, quaternion) - px = [] - py = [] - for point in polygon: - px.append(point[0]) - py.append(point[1]) - point = polygon[0] - px.append(point[0]) - py.append(point[1]) - ax.plot(px, py, "g-") - ax.plot([position[0]], [position[1]], 'go') diff --git a/modules/tools/planning/plot_trajectory/run.sh b/modules/tools/planning/plot_trajectory/run.sh deleted file mode 100755 index dad53e04de2..00000000000 --- a/modules/tools/planning/plot_trajectory/run.sh +++ /dev/null @@ -1,31 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - - -if [ $# -lt 2 ] -then - echo Usage: ./run.sh planning.pb.txt localization.pb.txt - exit -fi - -TOP_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")/../../.." && pwd -P)" -source "${TOP_DIR}/scripts/apollo_base.sh" - -cd "$(dirname "${BASH_SOURCE[0]}")" - -eval "${TOP_DIR}/bazel-bin/modules/tools/planning/plot_trajectory/main $1 $2" diff --git a/modules/tools/plot_control/BUILD b/modules/tools/plot_control/BUILD deleted file mode 100644 index bdaaa702677..00000000000 --- a/modules/tools/plot_control/BUILD +++ /dev/null @@ -1,32 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -py_binary( - name = "plot_control", - srcs = ["plot_control.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//modules/common_msgs/control_msgs:control_cmd_py_pb2", - ], -) - -py_binary( - name = "realtime_test", - srcs = ["realtime_test.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - ], -) - -install( - name = "install", - py_dest = "tools/plot_control", - targets = [ - ":plot_control", - ":realtime_test" - ] -) \ No newline at end of file diff --git a/modules/tools/plot_control/plot_control.py b/modules/tools/plot_control/plot_control.py deleted file mode 100644 index f6bbcdef087..00000000000 --- a/modules/tools/plot_control/plot_control.py +++ /dev/null @@ -1,102 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import sys -import gflags -from cyber.python.cyber_py3 import cyber -import matplotlib.pyplot as plt -import matplotlib.animation as animation -from modules.common_msgs.control_msgs import control_cmd_pb2 -BRAKE_LINE_DATA = [] -TROTTLE_LINE_DATA = [] -STEERING_LINE_DATA = [] - -FLAGS = gflags.FLAGS -gflags.DEFINE_integer("data_length", 500, "Control plot data length") - - -def callback(control_cmd_pb): - global STEERING_LINE_DATA - global TROTTLE_LINE_DATA, BRAKE_LINE_DATA - - STEERING_LINE_DATA.append(control_cmd_pb.steering_target) - if len(STEERING_LINE_DATA) > FLAGS.data_length: - STEERING_LINE_DATA = STEERING_LINE_DATA[-FLAGS.data_length:] - - BRAKE_LINE_DATA.append(control_cmd_pb.brake) - if len(BRAKE_LINE_DATA) > FLAGS.data_length: - BRAKE_LINE_DATA = BRAKE_LINE_DATA[-FLAGS.data_length:] - - TROTTLE_LINE_DATA.append(control_cmd_pb.throttle) - if len(TROTTLE_LINE_DATA) > FLAGS.data_length: - TROTTLE_LINE_DATA = TROTTLE_LINE_DATA[-FLAGS.data_length:] - - -def listener(): - cyber.init() - test_node = cyber.Node("control_listener") - test_node.create_reader("/apollo/control", - control_cmd_pb2.ControlCommand, callback) - test_node.spin() - cyber.shutdown() - - -def compensate(data_list): - comp_data = [0] * FLAGS.data_length - comp_data.extend(data_list) - if len(comp_data) > FLAGS.data_length: - comp_data = comp_data[-FLAGS.data_length:] - return comp_data - - -def update(frame_number): - brake_data = compensate(BRAKE_LINE_DATA) - brake_line.set_ydata(brake_data) - - throttle_data = compensate(TROTTLE_LINE_DATA) - throttle_line.set_ydata(throttle_data) - - steering_data = compensate(STEERING_LINE_DATA) - steering_line.set_ydata(steering_data) - - brake_text.set_text('brake = %.1f' % brake_data[-1]) - throttle_text.set_text('throttle = %.1f' % throttle_data[-1]) - steering_text.set_text('steering = %.1f' % steering_data[-1]) - - -if __name__ == '__main__': - argv = FLAGS(sys.argv) - listener() - fig, ax = plt.subplots() - X = range(FLAGS.data_length) - Xs = [i * -1 for i in X] - Xs.sort() - steering_line, = ax.plot( - Xs, [0] * FLAGS.data_length, 'b', lw=3, alpha=0.5, label='steering') - throttle_line, = ax.plot( - Xs, [0] * FLAGS.data_length, 'g', lw=3, alpha=0.5, label='throttle') - brake_line, = ax.plot( - Xs, [0] * FLAGS.data_length, 'r', lw=3, alpha=0.5, label='brake') - brake_text = ax.text(0.75, 0.85, '', transform=ax.transAxes) - throttle_text = ax.text(0.75, 0.90, '', transform=ax.transAxes) - steering_text = ax.text(0.75, 0.95, '', transform=ax.transAxes) - ani = animation.FuncAnimation(fig, update, interval=100) - ax.set_ylim(-100, 120) - ax.set_xlim(-1 * FLAGS.data_length, 10) - ax.legend(loc="upper left") - plt.show() diff --git a/modules/tools/plot_control/realtime_test.py b/modules/tools/plot_control/realtime_test.py deleted file mode 100644 index 162b460a927..00000000000 --- a/modules/tools/plot_control/realtime_test.py +++ /dev/null @@ -1,95 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -"""Real Time ACC Calculate Test Tool Based on Speed""" - -import argparse -import datetime -import os -import sys - -from cyber.python.cyber_py3 import cyber -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.localization_msgs import localization_pb2 - - -SmoothParam = 9 - - -class RealTimeTest(object): - - def __init__(self): - self.last_t = None - self.last_speed = None - self.last_acc = None - self.acc = None - self.accs = [] - self.buff = [] - self.count = 0 - self.acclimit = 0 - - def chassis_callback(self, chassis_pb2): - """Calculate ACC from Chassis Speed""" - speedmps = chassis_pb2.speed_mps - t = chassis_pb2.header.timestamp_sec - #speedkmh = speedmps * 3.6 - - self.buff.append(speedmps) - if len(self.buff) < SmoothParam: - return - if self.last_t is not None: - self.count += 1 - deltt = t - self.last_t - deltv = sum(self.buff) / len(self.buff) - self.last_speed - if deltt <= 1e-10: - deltt = 0.000000000001 - print("delt=0 ", t, ",", self.last_t) - self.acc = deltv / deltt - - self.accs.append(self.acc) - if abs(self.acc) > self.acclimit: - print(t, "\t", (sum(self.buff) / len(self.buff)) * 3.6, "\t", - self.acc, "\t", self.count, "\t", self.acclimit) - self.last_acc = self.acc - self.last_t = t - self.last_speed = sum(self.buff) / len(self.buff) - self.buff = [] - - -if __name__ == '__main__': - """Main function""" - parser = argparse.ArgumentParser( - description="Test car realtime status.", - prog="RealTimeTest.py", - usage="python realtime_test.py") - parser.add_argument( - "--acc", - type=int, - required=False, - default=2, - help="Acc limit default must > 0") - args = parser.parse_args() - if args.acc < 0: - print("acc must larger than 0") - cyber.init() - rttest = RealTimeTest() - rttest.acclimit = args.acc - cyber_node = cyber.Node("RealTimeTest") - cyber_node.create_reader("/apollo/canbus/chassis", - chassis_pb2.Chassis, rttest.chassis_callback) - cyber_node.spin() - cyber.shutdown() diff --git a/modules/tools/plot_control/run.sh b/modules/tools/plot_control/run.sh deleted file mode 100755 index c6faf970432..00000000000 --- a/modules/tools/plot_control/run.sh +++ /dev/null @@ -1,22 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -TOP_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")/../../.." && pwd -P)" -source "${TOP_DIR}/scripts/apollo_base.sh" - -eval "${TOP_DIR}/bazel-bin/modules/tools/plot_control/plot_control $1" diff --git a/modules/tools/plot_planning/BUILD b/modules/tools/plot_planning/BUILD deleted file mode 100644 index 78ae637f1bd..00000000000 --- a/modules/tools/plot_planning/BUILD +++ /dev/null @@ -1,171 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -py_binary( - name = "chassis_speed", - srcs = ["chassis_speed.py"], - deps = [ - ":record_reader", - ], -) - -py_binary( - name = "imu_acc", - srcs = ["imu_acc.py"], - deps = [ - ":record_reader", - ], -) - -py_binary( - name = "imu_angular_velocity", - srcs = ["imu_angular_velocity.py"], - deps = [ - ":record_reader", - ], -) - -py_binary( - name = "imu_av_curvature", - srcs = ["imu_av_curvature.py"], - deps = [ - ":imu_angular_velocity", - ":imu_speed", - ":record_reader", - ], -) - -py_binary( - name = "imu_speed", - srcs = ["imu_speed.py"], - deps = [ - ":record_reader", - ], -) - -py_binary( - name = "imu_speed_acc", - srcs = ["imu_speed_acc.py"], - deps = [ - ":imu_speed", - ":record_reader", - ], -) - -py_binary( - name = "imu_speed_jerk", - srcs = ["imu_speed_jerk.py"], - deps = [ - ":imu_speed_acc", - ":record_reader", - ], -) - -py_binary( - name = "planning_speed", - srcs = ["planning_speed.py"], -) - -py_binary( - name = "plot_acc_jerk", - srcs = ["plot_acc_jerk.py"], - deps = [ - ":imu_speed_acc", - ":imu_speed_jerk", - ":record_reader", - ], -) - -py_binary( - name = "plot_chassis_acc", - srcs = ["plot_chassis_acc.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/control_msgs:control_cmd_py_pb2", - ], -) - -py_binary( - name = "plot_planning_acc", - srcs = ["plot_planning_acc.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/control_msgs:control_cmd_py_pb2", - ], -) - -py_binary( - name = "plot_planning_speed", - srcs = ["plot_planning_speed.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/control_msgs:control_cmd_py_pb2", - ], -) - -py_binary( - name = "plot_speed_jerk", - srcs = ["plot_speed_jerk.py"], - deps = [ - ":imu_speed", - ":imu_speed_jerk", - ":record_reader", - ], -) - -py_binary( - name = "plot_speed_steering", - srcs = ["plot_speed_steering.py"], - deps = [ - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/planning_msgs:planning_py_pb2", - ], -) - -py_library( - name = "record_reader", - srcs = ["record_reader.py"], - deps = [ - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - "//modules/common_msgs/planning_msgs:planning_py_pb2", - ], -) - -py_binary( - name = "speed_dsteering_data", - srcs = ["speed_dsteering_data.py"], - deps = [ - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - ], -) - -install( - name = "install", - py_dest = "tools/plot_planning", - targets = [ - ":speed_dsteering_data", - ":plot_speed_steering", - ":plot_speed_jerk", - ":plot_planning_speed", - ":plot_planning_acc", - ":plot_chassis_acc", - ":plot_acc_jerk", - ":planning_speed", - ":imu_speed_jerk", - ":imu_speed_acc", - ":imu_speed", - ":imu_av_curvature", - ":imu_angular_velocity", - ":imu_acc", - ":chassis_speed", - ] -) \ No newline at end of file diff --git a/modules/tools/plot_planning/chassis_speed.py b/modules/tools/plot_planning/chassis_speed.py deleted file mode 100644 index 956f4119da1..00000000000 --- a/modules/tools/plot_planning/chassis_speed.py +++ /dev/null @@ -1,87 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math -from modules.tools.plot_planning.record_reader import RecordItemReader - - -class ChassisSpeed: - - def __init__(self): - self.timestamp_list = [] - self.speed_list = [] - - def add(self, chassis): - timestamp_sec = chassis.header.timestamp_sec - speed_mps = chassis.speed_mps - - self.timestamp_list.append(timestamp_sec) - self.speed_list.append(speed_mps) - - def get_speed_list(self): - return self.speed_list - - def get_timestamp_list(self): - return self.timestamp_list - - def get_lastest_speed(self): - if len(self.speed_list) > 0: - return self.speed_list[-1] - else: - return None - - def get_lastest_timestamp(self): - if len(self.timestamp_list) > 0: - return self.timestamp_list[-1] - else: - return None - - -if __name__ == "__main__": - import sys - import matplotlib.pyplot as plt - from os import listdir - from os.path import isfile, join - - folders = sys.argv[1:] - fig, ax = plt.subplots() - colors = ["g", "b", "r", "m", "y"] - markers = ["o", "o", "o", "o"] - for i in range(len(folders)): - folder = folders[i] - color = colors[i % len(colors)] - marker = markers[i % len(markers)] - fns = [f for f in listdir(folder) if isfile(join(folder, f))] - for fn in fns: - reader = RecordItemReader(folder+"/"+fn) - processor = ChassisSpeed() - last_chassis_data = None - topics = ["/apollo/canbus/chassis"] - for data in reader.read(topics): - if "chassis" in data: - last_chassis_data = data["chassis"] - processor.add(last_chassis_data) - last_pose_data = None - last_chassis_data = None - - data_x = processor.get_timestamp_list() - data_y = processor.get_speed_list() - - ax.scatter(data_x, data_y, c=color, marker=marker, alpha=0.4) - - plt.show() diff --git a/modules/tools/plot_planning/imu_acc.py b/modules/tools/plot_planning/imu_acc.py deleted file mode 100644 index 93e49027663..00000000000 --- a/modules/tools/plot_planning/imu_acc.py +++ /dev/null @@ -1,124 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math -from modules.tools.plot_planning.record_reader import RecordItemReader - - -class ImuAcc: - - def __init__(self): - self.timestamp_list = [] - self.corrected_acc_list = [] - self.acc_list = [] - - self.last_corrected_acc = None - self.last_timestamp = None - - def add(self, location_est): - timestamp = location_est.measurement_time - acc = location_est.pose.linear_acceleration.x * \ - math.cos(location_est.pose.heading) + \ - location_est.pose.linear_acceleration.y * \ - math.sin(location_est.pose.heading) - - if self.last_corrected_acc is not None: - corrected_acc = self._correct_acc(acc, self.last_corrected_acc) - else: - corrected_acc = acc - - self.acc_list.append(acc) - self.corrected_acc_list.append(corrected_acc) - self.timestamp_list.append(timestamp) - - self.last_timestamp = timestamp - self.last_corrected_acc = corrected_acc - - def get_acc_list(self): - return self.acc_list - - def get_corrected_acc_list(self): - return self.corrected_acc_list - - def get_timestamp_list(self): - return self.timestamp_list - - def get_lastest_corrected_acc(self): - if len(self.corrected_acc_list) > 0: - return self.corrected_acc_list[-1] - else: - return None - - def get_lastest_acc(self): - if len(self.acc_list) > 0: - return self.acc_list[-1] - else: - return None - - def get_lastest_timestamp(self): - if len(self.timestamp_list) > 0: - return self.timestamp_list[-1] - else: - return None - - def _correct_acc(self, acc, last_acc): - if last_acc is None: - return last_acc - delta = abs(acc - last_acc) / abs(last_acc) - if delta > 0.4: - corrected = acc / 2.0 - return corrected - else: - return acc - - -if __name__ == "__main__": - import sys - import matplotlib.pyplot as plt - from os import listdir - from os.path import isfile, join - - folders = sys.argv[1:] - fig, ax = plt.subplots() - colors = ["g", "b", "r", "m", "y"] - markers = ["o", "o", "o", "o"] - for i in range(len(folders)): - folder = folders[i] - color = colors[i % len(colors)] - marker = markers[i % len(markers)] - fns = [f for f in listdir(folder) if isfile(join(folder, f))] - for fn in fns: - reader = RecordItemReader(folder+"/"+fn) - processor = ImuAcc() - last_pose_data = None - last_chassis_data = None - topics = ["/apollo/localization/pose"] - for data in reader.read(topics): - if "pose" in data: - last_pose_data = data["pose"] - processor.add(last_pose_data) - last_pose_data = None - last_chassis_data = None - - data_x = processor.get_timestamp_list() - data_y = processor.get_corrected_acc_list() - ax.scatter(data_x, data_y, c=color, marker=marker, alpha=0.4) - data_y = processor.get_acc_list() - ax.scatter(data_x, data_y, c="k", marker="+", alpha=0.4) - - plt.show() diff --git a/modules/tools/plot_planning/imu_angular_velocity.py b/modules/tools/plot_planning/imu_angular_velocity.py deleted file mode 100644 index 11089a8603c..00000000000 --- a/modules/tools/plot_planning/imu_angular_velocity.py +++ /dev/null @@ -1,118 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math -from modules.tools.plot_planning.record_reader import RecordItemReader - - -class ImuAngularVelocity: - def __init__(self): - self.timestamp_list = [] - self.angular_velocity_list = [] - self.corrected_angular_velocity_list = [] - - self.last_corrected_angular_velocity = None - self.last_timestamp = None - - def add(self, location_est): - timestamp_sec = location_est.header.timestamp_sec - angular_velocity = location_est.pose.angular_velocity.z - - if self.last_corrected_angular_velocity is not None: - corrected = self.correct_angular_velocity( - angular_velocity, timestamp_sec) - else: - corrected = angular_velocity - - self.timestamp_list.append(timestamp_sec) - self.angular_velocity_list.append(angular_velocity) - self.corrected_angular_velocity_list.append(corrected) - - self.last_corrected_angular_velocity = corrected - self.last_timestamp = timestamp_sec - - def correct_angular_velocity(self, angular_velocity, timestamp_sec): - if self.last_corrected_angular_velocity is None: - return angular_velocity - delta = abs(angular_velocity - self.last_corrected_angular_velocity)\ - / abs(self.last_corrected_angular_velocity) - - if delta > 0.25: - corrected = angular_velocity / 2.0 - return corrected - else: - return angular_velocity - - def get_anglular_velocity_list(self): - return self.angular_velocity_list - - def get_corrected_anglular_velocity_list(self): - return self.corrected_angular_velocity_list - - def get_timestamp_list(self): - return self.timestamp_list - - def get_latest_angular_velocity(self): - if len(self.angular_velocity_list) == 0: - return None - else: - return self.angular_velocity_list[-1] - - def get_latest_corrected_angular_velocity(self): - if len(self.corrected_angular_velocity_list) == 0: - return None - else: - return self.corrected_angular_velocity_list[-1] - - def get_latest_timestamp(self): - if len(self.timestamp_list) == 0: - return None - else: - return self.timestamp_list[-1] - - -if __name__ == "__main__": - import sys - import matplotlib.pyplot as plt - from os import listdir - from os.path import isfile, join - - folders = sys.argv[1:] - fig, ax = plt.subplots() - colors = ["g", "b", "r", "m", "y"] - markers = ["o", "o", "o", "o"] - for i in range(len(folders)): - folder = folders[i] - color = colors[i % len(colors)] - marker = markers[i % len(markers)] - fns = [f for f in listdir(folder) if isfile(join(folder, f))] - fns.sort() - for fn in fns: - reader = RecordItemReader(folder+"/"+fn) - processor = ImuAngularVelocity() - for data in reader.read(["/apollo/localization/pose"]): - processor.add(data["pose"]) - - data_x = processor.get_timestamp_list() - data_y = processor.get_corrected_anglular_velocity_list() - ax.scatter(data_x, data_y, c=color, marker=marker, alpha=0.4) - - data_y = processor.get_anglular_velocity_list() - ax.scatter(data_x, data_y, c='k', marker="+", alpha=0.8) - - plt.show() diff --git a/modules/tools/plot_planning/imu_av_curvature.py b/modules/tools/plot_planning/imu_av_curvature.py deleted file mode 100644 index 5d9518e11bc..00000000000 --- a/modules/tools/plot_planning/imu_av_curvature.py +++ /dev/null @@ -1,114 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math -from modules.tools.plot_planning.record_reader import RecordItemReader -from modules.tools.plot_planning.imu_angular_velocity import ImuAngularVelocity -from modules.tools.plot_planning.imu_speed import ImuSpeed - - -class ImuAvCurvature: - def __init__(self): - self.timestamp_list = [] - self.curvature_list = [] - - self.last_angular_velocity_z = None - - self.imu_angular_velocity = ImuAngularVelocity() - self.imu_speed = ImuSpeed() - - def add(self, location_est): - timestamp_sec = location_est.header.timestamp_sec - - self.imu_angular_velocity.add(location_est) - self.imu_speed.add(location_est) - - angular_velocity_z \ - = self.imu_angular_velocity.get_latest_corrected_angular_velocity() - speed_mps = self.imu_speed.get_lastest_speed() - if speed_mps > 0.03: - kappa = angular_velocity_z / speed_mps - else: - kappa = 0 - - self.timestamp_list.append(timestamp_sec) - self.curvature_list.append(kappa) - - self.last_angular_velocity_z = angular_velocity_z - - def get_timestamp_list(self): - return self.timestamp_list - - def get_curvature_list(self): - return self.curvature_list - - def get_last_timestamp(self): - if len(self.timestamp_list) > 0: - return self.timestamp_list[-1] - return None - - def get_last_curvature(self): - if len(self.curvature_list) > 0: - return self.curvature_list[-1] - return None - - -if __name__ == "__main__": - import sys - import matplotlib.pyplot as plt - from os import listdir - from os.path import isfile, join - - folders = sys.argv[1:] - fig, ax = plt.subplots() - colors = ["g", "b", "r", "m", "y"] - markers = ["o", "o", "o", "o"] - for i in range(len(folders)): - folder = folders[i] - color = colors[i % len(colors)] - marker = markers[i % len(markers)] - fns = [f for f in listdir(folder) if isfile(join(folder, f))] - fns.sort() - for fn in fns: - print(fn) - reader = RecordItemReader(folder+"/"+fn) - curvature_processor = ImuAvCurvature() - speed_processor = ImuSpeed() - av_processor = ImuAngularVelocity() - last_pose_data = None - last_chassis_data = None - for data in reader.read(["/apollo/localization/pose"]): - if "pose" in data: - last_pose_data = data["pose"] - curvature_processor.add(last_pose_data) - speed_processor.add(last_pose_data) - av_processor.add(last_pose_data) - - data_x = curvature_processor.get_timestamp_list() - data_y = curvature_processor.get_curvature_list() - ax.scatter(data_x, data_y, c=color, marker=marker, alpha=0.4) - - data_x = speed_processor.get_timestamp_list() - data_y = speed_processor.get_speed_list() - ax.scatter(data_x, data_y, c='r', marker=marker, alpha=0.4) - - data_x = av_processor.get_timestamp_list() - data_y = av_processor.get_corrected_anglular_velocity_list() - ax.scatter(data_x, data_y, c='b', marker=marker, alpha=0.4) - - plt.show() diff --git a/modules/tools/plot_planning/imu_speed.py b/modules/tools/plot_planning/imu_speed.py deleted file mode 100644 index 3364bf37b86..00000000000 --- a/modules/tools/plot_planning/imu_speed.py +++ /dev/null @@ -1,110 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math -from modules.tools.plot_planning.record_reader import RecordItemReader - - -class ImuSpeed: - - def __init__(self, is_lateral=False): - self.timestamp_list = [] - self.speed_list = [] - - self.last_speed_mps = None - self.last_imu_speed = None - - self.is_lateral = is_lateral - - def add(self, location_est): - timestamp_sec = location_est.measurement_time - self.timestamp_list.append(timestamp_sec) - if self.is_lateral: - speed = -1 * location_est.pose.linear_velocity.x \ - * math.sin(location_est.pose.heading) + \ - location_est.pose.linear_velocity.y * \ - math.cos(location_est.pose.heading) - else: - speed = location_est.pose.linear_velocity.x \ - * math.cos(location_est.pose.heading) + \ - location_est.pose.linear_velocity.y * \ - math.sin(location_est.pose.heading) - self.speed_list.append(speed) - - def get_speed_list(self): - return self.speed_list - - def get_timestamp_list(self): - return self.timestamp_list - - def get_lastest_speed(self): - if len(self.speed_list) > 0: - return self.speed_list[-1] - else: - return None - - def get_lastest_timestamp(self): - if len(self.timestamp_list) > 0: - return self.timestamp_list[-1] - else: - return None - - -if __name__ == "__main__": - import sys - import matplotlib.pyplot as plt - from os import listdir - from os.path import isfile, join - - folders = sys.argv[1:] - fig, ax = plt.subplots(2, 1) - colors = ["g", "b", "r", "m", "y"] - markers = ["o", "o", "o", "o"] - for i in range(len(folders)): - folder = folders[i] - color = colors[i % len(colors)] - marker = markers[i % len(markers)] - fns = [f for f in listdir(folder) if isfile(join(folder, f))] - for fn in fns: - reader = RecordItemReader(folder+"/"+fn) - lat_speed_processor = ImuSpeed(True) - lon_speed_processor = ImuSpeed(False) - - last_pose_data = None - last_chassis_data = None - topics = ["/apollo/localization/pose"] - for data in reader.read(topics): - if "pose" in data: - last_pose_data = data["pose"] - lat_speed_processor.add(last_pose_data) - lon_speed_processor.add(last_pose_data) - - data_x = lon_speed_processor.get_timestamp_list() - data_y = lon_speed_processor.get_speed_list() - ax[0].scatter(data_x, data_y, c=color, marker=marker, alpha=0.4) - - data_x = lat_speed_processor.get_timestamp_list() - data_y = lat_speed_processor.get_speed_list() - ax[1].scatter(data_x, data_y, c=color, marker=marker, alpha=0.4) - - ax[0].set_xlabel('Timestamp') - ax[0].set_ylabel('Lon Acc') - ax[1].set_xlabel('Timestamp') - ax[1].set_ylabel('Lat Acc') - - plt.show() diff --git a/modules/tools/plot_planning/imu_speed_acc.py b/modules/tools/plot_planning/imu_speed_acc.py deleted file mode 100644 index 505d44d0af5..00000000000 --- a/modules/tools/plot_planning/imu_speed_acc.py +++ /dev/null @@ -1,145 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math - -from modules.tools.plot_planning.imu_speed import ImuSpeed -from modules.tools.plot_planning.record_reader import RecordItemReader - - -class ImuSpeedAcc: - - def __init__(self, is_lateral=False): - self.timestamp_list = [] - self.acc_list = [] - self.imu_speed = ImuSpeed(is_lateral) - - def add(self, location_est): - self.imu_speed.add(location_est) - speed_timestamp_list = self.imu_speed.get_timestamp_list() - - index_50ms = len(speed_timestamp_list) - 1 - found_index_50ms = False - last_timestamp = speed_timestamp_list[-1] - while index_50ms >= 0: - current_timestamp = speed_timestamp_list[index_50ms] - if (last_timestamp - current_timestamp) >= 0.05: - found_index_50ms = True - break - index_50ms -= 1 - - if found_index_50ms: - speed_list = self.imu_speed.get_speed_list() - acc = (speed_list[-1] - speed_list[index_50ms]) / \ - (speed_timestamp_list[-1] - speed_timestamp_list[index_50ms]) - self.acc_list.append(acc) - self.timestamp_list.append(speed_timestamp_list[-1]) - - def get_acc_list(self): - return self.acc_list - - def get_timestamp_list(self): - return self.timestamp_list - - def get_lastest_acc(self): - if len(self.acc_list) > 0: - return self.acc_list[-1] - else: - return None - - def get_lastest_timestamp(self): - if len(self.timestamp_list) > 0: - return self.timestamp_list[-1] - else: - return None - - -if __name__ == "__main__": - import sys - import matplotlib.pyplot as plt - import numpy as np - from os import listdir - from os.path import isfile, join - - def plot_freq(x, y, ax, color): - Fs = len(y) / float(x[-1] - x[0]) - n = len(y) - k = np.arange(n) - T = n / Fs - frq = k / T - frq = frq[range(n // 2)] - - Y = np.fft.fft(y) / n - Y = Y[range(n // 2)] - ax.plot(frq, abs(Y), c=color) - - folders = sys.argv[1:] - fig, ax = plt.subplots(2, 2) - colors = ["g", "b", "r", "m", "y"] - markers = ["o", "o", "o", "o"] - for i in range(len(folders)): - lat_time = [] - lat_acc = [] - lon_time = [] - lon_acc = [] - - folder = folders[i] - color = colors[i % len(colors)] - marker = markers[i % len(markers)] - fns = [f for f in listdir(folder) if isfile(join(folder, f))] - fns.sort() - for fn in fns: - reader = RecordItemReader(folder + "/" + fn) - lat_acc_processor = ImuSpeedAcc(is_lateral=True) - lon_acc_processor = ImuSpeedAcc(is_lateral=False) - - last_pose_data = None - last_chassis_data = None - topics = ["/apollo/localization/pose"] - for data in reader.read(topics): - if "pose" in data: - last_pose_data = data["pose"] - lat_acc_processor.add(last_pose_data) - lon_acc_processor.add(last_pose_data) - - data_x = lat_acc_processor.get_timestamp_list() - data_y = lat_acc_processor.get_acc_list() - - lat_time.extend(data_x) - lat_acc.extend(data_y) - - data_x = lon_acc_processor.get_timestamp_list() - data_y = lon_acc_processor.get_acc_list() - - lon_time.extend(data_x) - lon_acc.extend(data_y) - - if len(lat_time) == 0: - continue - - ax[0][0].plot(lon_time, lon_acc, c=color, alpha=0.4) - - ax[0][1].plot(lat_time, lat_acc, c=color, alpha=0.4) - - ax[1][0].plot(lat_acc, lon_acc, '.', c=color, alpha=0.4) - ax[0][0].set_xlabel('Timestamp') - ax[0][0].set_ylabel('Lon Acc') - ax[0][1].set_xlabel('Timestamp') - ax[0][1].set_ylabel('Lat Acc') - - plt.show() diff --git a/modules/tools/plot_planning/imu_speed_jerk.py b/modules/tools/plot_planning/imu_speed_jerk.py deleted file mode 100644 index b2ba33eb50f..00000000000 --- a/modules/tools/plot_planning/imu_speed_jerk.py +++ /dev/null @@ -1,117 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math -from modules.tools.plot_planning.record_reader import RecordItemReader -from modules.tools.plot_planning.imu_speed_acc import ImuSpeedAcc - - -class ImuSpeedJerk: - - def __init__(self, is_lateral=False): - self.timestamp_list = [] - self.jerk_list = [] - self.imu_speed_acc = ImuSpeedAcc(is_lateral) - - def add(self, location_est): - self.imu_speed_acc.add(location_est) - acc_timestamp_list = self.imu_speed_acc.get_timestamp_list() - if len(acc_timestamp_list) <= 0: - return - - index_500ms = len(acc_timestamp_list) - 1 - found_index_500ms = False - last_timestamp = acc_timestamp_list[-1] - while index_500ms >= 0: - current_timestamp = acc_timestamp_list[index_500ms] - if (last_timestamp - current_timestamp) >= 0.5: - found_index_500ms = True - break - index_500ms -= 1 - - if found_index_500ms: - acc_list = self.imu_speed_acc.get_acc_list() - jerk = (acc_list[-1] - acc_list[index_500ms]) / \ - (acc_timestamp_list[-1] - acc_timestamp_list[index_500ms]) - self.jerk_list.append(jerk) - self.timestamp_list.append(acc_timestamp_list[-1]) - - def get_jerk_list(self): - return self.jerk_list - - def get_timestamp_list(self): - return self.timestamp_list - - def get_lastest_jerk(self): - if len(self.jerk_list) > 0: - return self.jerk_list[-1] - else: - return None - - def get_lastest_timestamp(self): - if len(self.timestamp_list) > 0: - return self.timestamp_list[-1] - else: - return None - - -if __name__ == "__main__": - import sys - import matplotlib.pyplot as plt - import numpy as np - from os import listdir - from os.path import isfile, join - - folders = sys.argv[1:] - fig, ax = plt.subplots(1, 1) - colors = ["g", "b", "r", "m", "y"] - markers = ["o", "o", "o", "o"] - for i in range(len(folders)): - x = [] - y = [] - folder = folders[i] - color = colors[i % len(colors)] - marker = markers[i % len(markers)] - fns = [f for f in listdir(folder) if isfile(join(folder, f))] - fns.sort() - for fn in fns: - reader = RecordItemReader(folder+"/"+fn) - processor = ImuSpeedJerk(True) - last_pose_data = None - last_chassis_data = None - topics = ["/apollo/localization/pose"] - for data in reader.read(topics): - if "pose" in data: - last_pose_data = data["pose"] - processor.add(last_pose_data) - - data_x = processor.get_timestamp_list() - data_y = processor.get_jerk_list() - - x.extend(data_x) - y.extend(data_y) - - if len(x) <= 0: - continue - ax.scatter(x, y, c=color, marker=marker, alpha=0.4) - #ax.plot(x, y, c=color, alpha=0.4) - - ax.set_xlabel('Timestamp') - ax.set_ylabel('Jerk') - - plt.show() diff --git a/modules/tools/plot_planning/planning_speed.py b/modules/tools/plot_planning/planning_speed.py deleted file mode 100644 index aa1c96186c3..00000000000 --- a/modules/tools/plot_planning/planning_speed.py +++ /dev/null @@ -1,89 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - - -class PlanningSpeed: - - def __init__(self): - self.timestamp_list = [] - self.speed_list = [] - - self.last_speed_mps = None - self.last_imu_speed = None - - def add(self, planning_pb): - timestamp_sec = planning_pb.header.timestamp_sec - relative_time = planning_pb.debug.planning_data.init_point.relative_time - self.timestamp_list.append(timestamp_sec + relative_time) - - speed = planning_pb.debug.planning_data.init_point.v - self.speed_list.append(speed) - - def get_speed_list(self): - return self.speed_list - - def get_timestamp_list(self): - return self.timestamp_list - - def get_lastest_speed(self): - if len(self.speed_list) > 0: - return self.speed_list[-1] - else: - return None - - def get_lastest_timestamp(self): - if len(self.timestamp_list) > 0: - return self.timestamp_list[-1] - else: - return None - - -if __name__ == "__main__": - import sys - import math - import matplotlib.pyplot as plt - from os import listdir - from os.path import isfile, join - from record_reader import RecordItemReader - - folders = sys.argv[1:] - fig, ax = plt.subplots() - colors = ["g", "b", "r", "m", "y"] - markers = ["o", "o", "o", "o"] - - for i in range(len(folders)): - folder = folders[i] - color = colors[i % len(colors)] - marker = markers[i % len(markers)] - fns = [f for f in listdir(folder) if isfile(join(folder, f))] - for fn in fns: - reader = RecordItemReader(folder+"/"+fn) - processor = PlanningSpeed() - last_pose_data = None - last_chassis_data = None - topics = ["/apollo/planning"] - for data in reader.read(topics): - if "planning" in data: - planning_pb = data["planning"] - processor.add(planning_pb) - - data_x = processor.get_timestamp_list() - data_y = processor.get_speed_list() - ax.scatter(data_x, data_y, c=color, marker=marker, alpha=0.4) - - plt.show() diff --git a/modules/tools/plot_planning/plot_acc_jerk.py b/modules/tools/plot_planning/plot_acc_jerk.py deleted file mode 100644 index f95beb496b7..00000000000 --- a/modules/tools/plot_planning/plot_acc_jerk.py +++ /dev/null @@ -1,77 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math -import sys -import matplotlib.pyplot as plt -import numpy as np -from os import listdir -from os.path import isfile, join - -from modules.tools.plot_planning.record_reader import RecordItemReader -from modules.tools.plot_planning.imu_speed_jerk import ImuSpeedJerk -from modules.tools.plot_planning.imu_speed_acc import ImuSpeedAcc - - -def grid(data_list, shift): - data_grid = [] - for data in data_list: - data_grid.append(round(data) + shift/10.0) - return data_grid - - -if __name__ == "__main__": - folders = sys.argv[1:] - fig, ax = plt.subplots(1, 1) - colors = ["g", "b", "r", "m", "y"] - markers = [".", ".", ".", "."] - for i in range(len(folders)): - x = [] - y = [] - folder = folders[i] - color = colors[i % len(colors)] - marker = markers[i % len(markers)] - fns = [f for f in listdir(folder) if isfile(join(folder, f))] - fns.sort() - for fn in fns: - reader = RecordItemReader(folder+"/"+fn) - jerk_processor = ImuSpeedJerk() - acc_processor = ImuSpeedAcc() - - topics = ["/apollo/localization/pose"] - for data in reader.read(topics): - if "pose" in data: - pose_data = data["pose"] - acc_processor.add(pose_data) - jerk_processor.add(pose_data) - - data_x = grid(acc_processor.get_acc_list(), i + 1) - data_y = grid(jerk_processor.get_jerk_list(), i + 1) - data_x = data_x[-1 * len(data_y):] - x.extend(data_x) - y.extend(data_y) - - if len(x) <= 0: - continue - ax.scatter(x, y, c=color, marker=marker, alpha=0.4) - #ax.plot(x, y, c=color, alpha=0.4) - - ax.set_xlabel('Acc') - ax.set_ylabel('Jerk') - - plt.show() diff --git a/modules/tools/plot_planning/plot_chassis_acc.py b/modules/tools/plot_planning/plot_chassis_acc.py deleted file mode 100644 index 3af269e0b12..00000000000 --- a/modules/tools/plot_planning/plot_chassis_acc.py +++ /dev/null @@ -1,120 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import sys -import threading - -import gflags -import matplotlib.animation as animation -import matplotlib.pyplot as plt - -from cyber.python.cyber_py3 import cyber -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.control_msgs import control_cmd_pb2 - - -INIT_ACC_DATA = [] -INIT_T_DATA = [] - -begin_t = None -last_t = None -last_v = None -lock = threading.Lock() - -FLAGS = gflags.FLAGS -gflags.DEFINE_integer("data_length", 500, "Planning plot data length") - - -def callback(chassis_pb): - global INIT_ACC_DATA, INIT_T_DATA - global begin_t, last_t, last_v - - if begin_t is None: - begin_t = chassis_pb.header.timestamp_sec - last_t = begin_t - current_t = chassis_pb.header.timestamp_sec - current_v = chassis_pb.speed_mps - - print(current_v) - if abs(current_t - last_t) < 0.015: - return - - lock.acquire() - if last_t is not None and abs(current_t - last_t) > 1: - begin_t = chassis_pb.header.timestamp_sec - - INIT_ACC_DATA = [] - INIT_T_DATA = [] - - last_t = None - last_v = None - - if last_t is not None and last_v is not None and current_t > last_t: - INIT_T_DATA.append(current_t - begin_t) - INIT_ACC_DATA.append((current_v - last_v) / (current_t - last_t)) - - lock.release() - - last_t = current_t - last_v = current_v - - -def listener(): - cyber.init() - test_node = cyber.Node("chassis_acc_listener") - test_node.create_reader("/apollo/canbus/chassis", - chassis_pb2.Chassis, callback) - - -def compensate(data_list): - comp_data = [0] * FLAGS.data_length - comp_data.extend(data_list) - if len(comp_data) > FLAGS.data_length: - comp_data = comp_data[-FLAGS.data_length:] - return comp_data - - -def update(frame_number): - lock.acquire() - init_data_line.set_xdata(INIT_T_DATA) - init_data_line.set_ydata(INIT_ACC_DATA) - lock.release() - #brake_text.set_text('brake = %.1f' % brake_data[-1]) - #throttle_text.set_text('throttle = %.1f' % throttle_data[-1]) - if len(INIT_ACC_DATA) > 0: - init_data_text.set_text('chassis acc = %.1f' % INIT_ACC_DATA[-1]) - - -if __name__ == '__main__': - argv = FLAGS(sys.argv) - listener() - fig, ax = plt.subplots() - X = range(FLAGS.data_length) - Xs = [i * -1 for i in X] - Xs.sort() - init_data_line, = ax.plot( - INIT_T_DATA, INIT_ACC_DATA, 'b', lw=2, alpha=0.7, label='chassis acc') - - #brake_text = ax.text(0.75, 0.85, '', transform=ax.transAxes) - #throttle_text = ax.text(0.75, 0.90, '', transform=ax.transAxes) - init_data_text = ax.text(0.75, 0.95, '', transform=ax.transAxes) - ani = animation.FuncAnimation(fig, update, interval=100) - ax.set_ylim(-6, 3) - ax.set_xlim(-1, 60) - ax.legend(loc="upper left") - plt.show() diff --git a/modules/tools/plot_planning/plot_planning_acc.py b/modules/tools/plot_planning/plot_planning_acc.py deleted file mode 100644 index 4c96c698f72..00000000000 --- a/modules/tools/plot_planning/plot_planning_acc.py +++ /dev/null @@ -1,160 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import sys -import threading - -import gflags -import matplotlib.animation as animation -import matplotlib.pyplot as plt - -from cyber.python.cyber_py3 import cyber -from modules.common_msgs.control_msgs import control_cmd_pb2 -from modules.common_msgs.planning_msgs import planning_pb2 - - -LAST_TRAJ_DATA = [] -LAST_TRAJ_T_DATA = [] -CURRENT_TRAJ_DATA = [] -CURRENT_TRAJ_T_DATA = [] -INIT_V_DATA = [] -INIT_T_DATA = [] - -begin_t = None -last_t = None -last_v = None -lock = threading.Lock() - -FLAGS = gflags.FLAGS -gflags.DEFINE_integer("data_length", 500, "Planning plot data length") - - -def callback(planning_pb): - global INIT_V_DATA, INIT_T_DATA - global CURRENT_TRAJ_DATA, LAST_TRAJ_DATA - global CURRENT_TRAJ_T_DATA, LAST_TRAJ_T_DATA - global begin_t, last_t, last_v - - lock.acquire() - - if begin_t is None: - begin_t = planning_pb.header.timestamp_sec - current_t = planning_pb.header.timestamp_sec - current_v = planning_pb.debug.planning_data.init_point.v - - if last_t is not None and abs(current_t - last_t) > 1: - begin_t = planning_pb.header.timestamp_sec - LAST_TRAJ_DATA = [] - LAST_TRAJ_T_DATA = [] - - CURRENT_TRAJ_DATA = [] - CURRENT_TRAJ_T_DATA = [] - - INIT_V_DATA = [] - INIT_T_DATA = [] - - last_t = None - last_v = None - - if last_t is not None and last_v is not None and current_t > last_t: - INIT_T_DATA.append(current_t - begin_t) - INIT_V_DATA.append((current_v - last_v) / (current_t - last_t)) - - LAST_TRAJ_DATA = [] - for v in CURRENT_TRAJ_DATA: - LAST_TRAJ_DATA.append(v) - - LAST_TRAJ_T_DATA = [] - for t in CURRENT_TRAJ_T_DATA: - LAST_TRAJ_T_DATA.append(t) - - CURRENT_TRAJ_DATA = [] - CURRENT_TRAJ_T_DATA = [] - traj_point_last_v = None - traj_point_last_t = None - for traj_point in planning_pb.trajectory_point: - if traj_point_last_v is None: - CURRENT_TRAJ_DATA.append(traj_point.a) - else: - # CURRENT_TRAJ_DATA.append(traj_point.a) - cal_a = (traj_point.v - traj_point_last_v) / \ - (traj_point.relative_time - traj_point_last_t) - CURRENT_TRAJ_DATA.append(cal_a) - CURRENT_TRAJ_T_DATA.append(current_t - begin_t + traj_point.relative_time) - traj_point_last_t = traj_point.relative_time - traj_point_last_v = traj_point.v - lock.release() - - last_t = current_t - last_v = current_v - - -def listener(): - cyber.init() - test_node = cyber.Node("planning_acc_listener") - test_node.create_reader("/apollo/planning", - planning_pb2.ADCTrajectory, callback) - - -def compensate(data_list): - comp_data = [0] * FLAGS.data_length - comp_data.extend(data_list) - if len(comp_data) > FLAGS.data_length: - comp_data = comp_data[-FLAGS.data_length:] - return comp_data - - -def update(frame_number): - lock.acquire() - last_traj.set_xdata(LAST_TRAJ_T_DATA) - last_traj.set_ydata(LAST_TRAJ_DATA) - - current_traj.set_xdata(CURRENT_TRAJ_T_DATA) - current_traj.set_ydata(CURRENT_TRAJ_DATA) - - init_data_line.set_xdata(INIT_T_DATA) - init_data_line.set_ydata(INIT_V_DATA) - lock.release() - #brake_text.set_text('brake = %.1f' % brake_data[-1]) - #throttle_text.set_text('throttle = %.1f' % throttle_data[-1]) - if len(INIT_V_DATA) > 0: - init_data_text.set_text('init point a = %.1f' % INIT_V_DATA[-1]) - - -if __name__ == '__main__': - argv = FLAGS(sys.argv) - listener() - fig, ax = plt.subplots() - X = range(FLAGS.data_length) - Xs = [i * -1 for i in X] - Xs.sort() - init_data_line, = ax.plot( - INIT_T_DATA, INIT_V_DATA, 'b', lw=2, alpha=0.7, label='init_point_a') - current_traj, = ax.plot( - CURRENT_TRAJ_T_DATA, CURRENT_TRAJ_DATA, 'r', lw=1, alpha=0.5, label='current_traj') - last_traj, = ax.plot( - LAST_TRAJ_T_DATA, LAST_TRAJ_DATA, 'g', lw=1, alpha=0.5, label='last_traj') - - #brake_text = ax.text(0.75, 0.85, '', transform=ax.transAxes) - #throttle_text = ax.text(0.75, 0.90, '', transform=ax.transAxes) - init_data_text = ax.text(0.75, 0.95, '', transform=ax.transAxes) - ani = animation.FuncAnimation(fig, update, interval=100) - ax.set_ylim(-6, 3) - ax.set_xlim(-1, 60) - ax.legend(loc="upper left") - plt.show() diff --git a/modules/tools/plot_planning/plot_planning_speed.py b/modules/tools/plot_planning/plot_planning_speed.py deleted file mode 100644 index fda847924aa..00000000000 --- a/modules/tools/plot_planning/plot_planning_speed.py +++ /dev/null @@ -1,143 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import sys -import threading - -import gflags -import matplotlib.animation as animation -import matplotlib.pyplot as plt - -from cyber.python.cyber_py3 import cyber -from modules.common_msgs.control_msgs import control_cmd_pb2 -from modules.common_msgs.planning_msgs import planning_pb2 - - -LAST_TRAJ_DATA = [] -LAST_TRAJ_T_DATA = [] -CURRENT_TRAJ_DATA = [] -CURRENT_TRAJ_T_DATA = [] -INIT_V_DATA = [] -INIT_T_DATA = [] - -begin_t = None -last_t = None -lock = threading.Lock() - -FLAGS = gflags.FLAGS -gflags.DEFINE_integer("data_length", 500, "Planning plot data length") - - -def callback(planning_pb): - global INIT_V_DATA, INIT_T_DATA - global CURRENT_TRAJ_DATA, LAST_TRAJ_DATA - global CURRENT_TRAJ_T_DATA, LAST_TRAJ_T_DATA - global begin_t, last_t - - lock.acquire() - - if begin_t is None: - begin_t = planning_pb.header.timestamp_sec - current_t = planning_pb.header.timestamp_sec - if last_t is not None and abs(current_t - last_t) > 1: - begin_t = planning_pb.header.timestamp_sec - LAST_TRAJ_DATA = [] - LAST_TRAJ_T_DATA = [] - - CURRENT_TRAJ_DATA = [] - CURRENT_TRAJ_T_DATA = [] - - INIT_V_DATA = [] - INIT_T_DATA = [] - - INIT_T_DATA.append(current_t - begin_t) - INIT_V_DATA.append(planning_pb.debug.planning_data.init_point.v) - - LAST_TRAJ_DATA = [] - for v in CURRENT_TRAJ_DATA: - LAST_TRAJ_DATA.append(v) - - LAST_TRAJ_T_DATA = [] - for t in CURRENT_TRAJ_T_DATA: - LAST_TRAJ_T_DATA.append(t) - - CURRENT_TRAJ_DATA = [] - CURRENT_TRAJ_T_DATA = [] - for traj_point in planning_pb.trajectory_point: - CURRENT_TRAJ_DATA.append(traj_point.v) - CURRENT_TRAJ_T_DATA.append(current_t - begin_t + traj_point.relative_time) - - lock.release() - - last_t = current_t - - -def listener(): - cyber.init() - test_node = cyber.Node("planning_listener") - test_node.create_reader("/apollo/planning", - planning_pb2.ADCTrajectory, callback) - - -def compensate(data_list): - comp_data = [0] * FLAGS.data_length - comp_data.extend(data_list) - if len(comp_data) > FLAGS.data_length: - comp_data = comp_data[-FLAGS.data_length:] - return comp_data - - -def update(frame_number): - lock.acquire() - last_traj.set_xdata(LAST_TRAJ_T_DATA) - last_traj.set_ydata(LAST_TRAJ_DATA) - - current_traj.set_xdata(CURRENT_TRAJ_T_DATA) - current_traj.set_ydata(CURRENT_TRAJ_DATA) - - init_data_line.set_xdata(INIT_T_DATA) - init_data_line.set_ydata(INIT_V_DATA) - lock.release() - #brake_text.set_text('brake = %.1f' % brake_data[-1]) - #throttle_text.set_text('throttle = %.1f' % throttle_data[-1]) - if len(INIT_V_DATA) > 0: - init_data_text.set_text('init point v = %.1f' % INIT_V_DATA[-1]) - - -if __name__ == '__main__': - argv = FLAGS(sys.argv) - listener() - fig, ax = plt.subplots() - X = range(FLAGS.data_length) - Xs = [i * -1 for i in X] - Xs.sort() - init_data_line, = ax.plot( - INIT_T_DATA, INIT_V_DATA, 'b', lw=2, alpha=0.7, label='init_point_v') - current_traj, = ax.plot( - CURRENT_TRAJ_T_DATA, CURRENT_TRAJ_DATA, 'r', lw=1, alpha=0.5, label='current_traj') - last_traj, = ax.plot( - LAST_TRAJ_T_DATA, LAST_TRAJ_DATA, 'g', lw=1, alpha=0.5, label='last_traj') - - #brake_text = ax.text(0.75, 0.85, '', transform=ax.transAxes) - #throttle_text = ax.text(0.75, 0.90, '', transform=ax.transAxes) - init_data_text = ax.text(0.75, 0.95, '', transform=ax.transAxes) - ani = animation.FuncAnimation(fig, update, interval=100) - ax.set_ylim(-1, 30) - ax.set_xlim(-1, 60) - ax.legend(loc="upper left") - plt.show() diff --git a/modules/tools/plot_planning/plot_speed_jerk.py b/modules/tools/plot_planning/plot_speed_jerk.py deleted file mode 100644 index 577aee39393..00000000000 --- a/modules/tools/plot_planning/plot_speed_jerk.py +++ /dev/null @@ -1,94 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -from os import listdir -from os.path import isfile, join -import math -import sys - -import matplotlib.pyplot as plt -import numpy as np - -from modules.tools.plot_planning.imu_speed import ImuSpeed -from modules.tools.plot_planning.imu_speed_jerk import ImuSpeedJerk -from modules.tools.plot_planning.record_reader import RecordItemReader - - -def grid(data_list, shift): - data_grid = [] - for data in data_list: - data_grid.append(round(data) + shift / 10.0) - return data_grid - - -def generate_speed_jerk_dict(speed_jerk_dict, speed_list, jerk_list): - for i in range(len(speed_list)): - speed = int(speed_list[i]) - jerk = int(jerk_list[i]) - if speed in speed_jerk_dict: - if jerk not in speed_jerk_dict[speed]: - speed_jerk_dict[speed].append(jerk) - else: - speed_jerk_dict[speed] = [jerk] - return speed_jerk_dict - - -if __name__ == "__main__": - - folders = sys.argv[1:] - fig, ax = plt.subplots(1, 1) - colors = ["g", "b", "r", "m", "y"] - markers = [".", ".", ".", "."] - speed_jerk_dict = {} - - for i in range(len(folders)): - x = [] - y = [] - folder = folders[i] - color = colors[i % len(colors)] - marker = markers[i % len(markers)] - fns = [f for f in listdir(folder) if isfile(join(folder, f))] - fns.sort() - for fn in fns: - reader = RecordItemReader(folder+"/"+fn) - jerk_processor = ImuSpeedJerk(True) - speed_processor = ImuSpeed(True) - - topics = ["/apollo/localization/pose"] - for data in reader.read(topics): - if "pose" in data: - pose_data = data["pose"] - speed_processor.add(pose_data) - jerk_processor.add(pose_data) - - data_x = grid(speed_processor.get_speed_list(), i + 1) - data_y = grid(jerk_processor.get_jerk_list(), i + 1) - data_x = data_x[-1 * len(data_y):] - x.extend(data_x) - y.extend(data_y) - speed_jerk_dict = generate_speed_jerk_dict(speed_jerk_dict, x, y) - - if len(x) <= 0: - continue - ax.scatter(x, y, c=color, marker=marker, alpha=0.4) - #ax.plot(x, y, c=color, alpha=0.4) - - ax.set_xlabel('Speed') - ax.set_ylabel('Jerk') - print(speed_jerk_dict) - plt.show() diff --git a/modules/tools/plot_planning/plot_speed_steering.py b/modules/tools/plot_planning/plot_speed_steering.py deleted file mode 100644 index 3e5c6d8f3f0..00000000000 --- a/modules/tools/plot_planning/plot_speed_steering.py +++ /dev/null @@ -1,79 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - - -import sys - -import matplotlib.pyplot as plt - -from cyber.python.cyber_py3.record import RecordReader -from modules.common_msgs.chassis_msgs import chassis_pb2 - - -def process(reader): - last_steering_percentage = None - last_speed_mps = None - last_timestamp_sec = None - speed_data = [] - d_steering_data = [] - - for msg in reader.read_messages(): - if msg.topic == "/apollo/canbus/chassis": - chassis = chassis_pb2.Chassis() - chassis.ParseFromString(msg.message) - - steering_percentage = chassis.steering_percentage - speed_mps = chassis.speed_mps - timestamp_sec = chassis.header.timestamp_sec - - if chassis.driving_mode != chassis_pb2.Chassis.COMPLETE_AUTO_DRIVE: - last_steering_percentage = steering_percentage - last_speed_mps = speed_mps - last_timestamp_sec = timestamp_sec - continue - - if last_timestamp_sec is None: - last_steering_percentage = steering_percentage - last_speed_mps = speed_mps - last_timestamp_sec = timestamp_sec - continue - - if (timestamp_sec - last_timestamp_sec) > 0.02: - d_steering = (steering_percentage - last_steering_percentage) \ - / (timestamp_sec - last_timestamp_sec) - speed_data.append(speed_mps) - d_steering_data.append(d_steering) - - last_steering_percentage = steering_percentage - last_speed_mps = speed_mps - last_timestamp_sec = timestamp_sec - - return speed_data, d_steering_data - - -if __name__ == "__main__": - fns = sys.argv[1:] - fig, ax = plt.subplots() - - for fn in fns: - reader = RecordReader(fn) - speed_data, d_steering_data = process(reader) - ax.scatter(speed_data, d_steering_data) - ax.set_xlim(-5, 40) - ax.set_ylim(-300, 300) - plt.show() diff --git a/modules/tools/plot_planning/record_reader.py b/modules/tools/plot_planning/record_reader.py deleted file mode 100644 index ad5403b851c..00000000000 --- a/modules/tools/plot_planning/record_reader.py +++ /dev/null @@ -1,50 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -from cyber.python.cyber_py3.record import RecordReader -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.localization_msgs import localization_pb2 -from modules.common_msgs.planning_msgs import planning_pb2 - - -class RecordItemReader: - def __init__(self, record_file): - self.record_file = record_file - - def read(self, topics): - reader = RecordReader(self.record_file) - for msg in reader.read_messages(): - if msg.topic not in topics: - continue - if msg.topic == "/apollo/canbus/chassis": - chassis = chassis_pb2.Chassis() - chassis.ParseFromString(msg.message) - data = {"chassis": chassis} - yield data - - if msg.topic == "/apollo/localization/pose": - location_est = localization_pb2.LocalizationEstimate() - location_est.ParseFromString(msg.message) - data = {"pose": location_est} - yield data - - if msg.topic == "/apollo/planning": - planning = planning_pb2.ADCTrajectory() - planning.ParseFromString(msg.message) - data = {"planning": planning} - yield data diff --git a/modules/tools/plot_planning/speed_dsteering_data.py b/modules/tools/plot_planning/speed_dsteering_data.py deleted file mode 100644 index 7c75ece4b5a..00000000000 --- a/modules/tools/plot_planning/speed_dsteering_data.py +++ /dev/null @@ -1,91 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import sys -from modules.tools.plot_planning.record_reader import RecordItemReader -import matplotlib.pyplot as plt -from cyber.python.cyber_py3.record import RecordReader -from modules.common_msgs.chassis_msgs import chassis_pb2 - - -class SpeedDsteeringData: - def __init__(self): - self.last_steering_percentage = None - self.last_speed_mps = None - self.last_timestamp_sec = None - self.speed_data = [] - self.d_steering_data = [] - - def add(self, chassis): - steering_percentage = chassis.steering_percentage - speed_mps = chassis.speed_mps - timestamp_sec = chassis.header.timestamp_sec - - if self.last_timestamp_sec is None: - self.last_steering_percentage = steering_percentage - self.last_speed_mps = speed_mps - self.last_timestamp_sec = timestamp_sec - return - - if (timestamp_sec - self.last_timestamp_sec) > 0.02: - d_steering = (steering_percentage - self.last_steering_percentage) \ - / (timestamp_sec - self.last_timestamp_sec) - self.speed_data.append(speed_mps) - self.d_steering_data.append(d_steering) - - self.last_steering_percentage = steering_percentage - self.last_speed_mps = speed_mps - self.last_timestamp_sec = timestamp_sec - - def get_speed_dsteering(self): - return self.speed_data, self.d_steering_data - - -if __name__ == "__main__": - import sys - import matplotlib.pyplot as plt - from os import listdir - from os.path import isfile, join - - folders = sys.argv[1:] - fig, ax = plt.subplots() - colors = ["g", "b", "r", "m", "y"] - markers = ["o", "o", "o", "o"] - for i in range(len(folders)): - folder = folders[i] - color = colors[i % len(colors)] - marker = markers[i % len(markers)] - fns = [f for f in listdir(folder) if isfile(join(folder, f))] - for fn in fns: - reader = RecordItemReader(folder+"/"+fn) - processor = SpeedDsteeringData() - last_pose_data = None - last_chassis_data = None - topics = ["/apollo/localization/pose", "/apollo/canbus/chassis"] - for data in reader.read(topics): - if "chassis" in data: - last_chassis_data = data["chassis"] - if last_chassis_data is not None: - processor.add(last_chassis_data) - #last_pose_data = None - #last_chassis_data = None - - data_x, data_y = processor.get_speed_dsteering() - ax.scatter(data_x, data_y, c=color, marker=marker, alpha=0.2) - - plt.show() diff --git a/modules/tools/plot_planning/time_curvature_data.py b/modules/tools/plot_planning/time_curvature_data.py deleted file mode 100644 index 57cd2e248b9..00000000000 --- a/modules/tools/plot_planning/time_curvature_data.py +++ /dev/null @@ -1,110 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -from modules.tools.plot_planning.record_reader import RecordItemReader -from modules.tools.plot_planning.time_angular_velocity_data import TimeAngularVelocityData -from modules.tools.plot_planning.time_speed_data import TimeSpeedData -import math - - -class TimeCurvatureData: - def __init__(self): - self.timestamp_list = [] - self.curvature_list = [] - self.speed_list = [] - - self.corrected_timestamp_list = [] - self.corrected_velocity_list = [] - - self.last_angular_velocity_z = None - - self.angular_velocity_data = TimeAngularVelocityData() - self.speed_data = TimeSpeedData() - - def add(self, location_est, chassis): - timestamp_sec = location_est.header.timestamp_sec - - self.angular_velocity_data.add_location_estimation(location_est) - self.speed_data.add(location_est, chassis) - - angular_velocity_z = self.angular_velocity_data.get_latest() - speed_mps = self.speed_data.get_imu_based_lastest_speed() - - if speed_mps > 0.5: - kappa = angular_velocity_z / speed_mps - if kappa > 0.05: - self.timestamp_list.append(timestamp_sec) - self.curvature_list.append(kappa) - self.speed_list.append(speed_mps) - - self.last_angular_velocity_z = angular_velocity_z - - def get_time_curvature(self): - return self.timestamp_list, self.curvature_list - - def get_speed_curvature(self): - return self.speed_list, self.curvature_list - - def get_fixed_ca_speed_curvature(self): - speed_list = list(range(1, 31)) - curvature_list = [] - for speed in speed_list: - curvature = 2.0 / (speed * speed) - curvature_list.append(curvature) - return speed_list, curvature_list - - -if __name__ == "__main__": - import sys - import matplotlib.pyplot as plt - from os import listdir - from os.path import isfile, join - - folders = sys.argv[1:] - fig, ax = plt.subplots() - colors = ["g", "b", "r", "m", "y"] - markers = ["o", "o", "o", "o"] - for i in range(len(folders)): - folder = folders[i] - color = colors[i % len(colors)] - marker = markers[i % len(markers)] - fns = [f for f in listdir(folder) if isfile(join(folder, f))] - for fn in fns: - print(fn) - reader = RecordItemReader(folder+"/"+fn) - processor = TimeCurvatureData() - last_pose_data = None - last_chassis_data = None - for data in reader.read(["/apollo/localization/pose", - "/apollo/canbus/chassis"]): - if "pose" in data: - last_pose_data = data["pose"] - if "chassis" in data: - last_chassis_data = data["chassis"] - if last_chassis_data is not None and last_pose_data is not None: - processor.add(last_pose_data, last_chassis_data) - - data_x, data_y = processor.get_speed_curvature() - data_y = [abs(i) for i in data_y] - ax.scatter(data_x, data_y, c=color, marker=marker, alpha=0.4) - #data_x, data_y = processor.speed_data.get_time_speed() - #ax.scatter(data_x, data_y, c=color, marker="+", alpha=0.4) - processor = TimeCurvatureData() - x, y = processor.get_fixed_ca_speed_curvature() - ax.plot(x, y) - plt.show() diff --git a/modules/tools/plot_trace/BUILD b/modules/tools/plot_trace/BUILD deleted file mode 100644 index bb321a433aa..00000000000 --- a/modules/tools/plot_trace/BUILD +++ /dev/null @@ -1,34 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -py_binary( - name = "plot_planning_result", - srcs = ["plot_planning_result.py"], - deps = [ - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - "//modules/common_msgs/planning_msgs:planning_py_pb2", - ], -) - -py_binary( - name = "plot_trace", - srcs = ["plot_trace.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - ], -) - - -install( - name = "install", - py_dest = "tools/plot_trace", - targets = [ - ":plot_trace", - ":plot_planning_result", - ] -) \ No newline at end of file diff --git a/modules/tools/plot_trace/plot_planning_result.py b/modules/tools/plot_trace/plot_planning_result.py deleted file mode 100755 index ebcfa6735ca..00000000000 --- a/modules/tools/plot_trace/plot_planning_result.py +++ /dev/null @@ -1,123 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -from subprocess import call -import sys - -from google.protobuf import text_format -from mpl_toolkits.mplot3d import Axes3D -import matplotlib -import matplotlib.animation as animation -import matplotlib.pyplot as plt -import numpy as np - -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.localization_msgs import localization_pb2 -from modules.common_msgs.planning_msgs import planning_pb2 - - -g_args = None - - -def get_3d_trajectory(planning_pb): - x = [p.path_point.x for p in planning_pb.trajectory_point] - y = [p.path_point.y for p in planning_pb.trajectory_point] - z = [p.v for p in planning_pb.trajectory_point] - return (x, y, z) - - -def get_debug_paths(planning_pb): - if not planning_pb.HasField("debug"): - return None - if not planning_pb.debug.HasField("planning_data"): - return None - results = [] - for path in planning_pb.debug.planning_data.path: - x = [p.x for p in path.path_point] - y = [p.y for p in path.path_point] - results.append((path.name, (x, y))) - return results - - -def plot_planning(ax, planning_file): - with open(planning_file, 'r') as fp: - planning_pb = planning_pb2.ADCTrajectory() - text_format.Merge(fp.read(), planning_pb) - trajectory = get_3d_trajectory(planning_pb) - ax.plot(trajectory[0], trajectory[1], trajectory[2], - label="Trajectory:%s" % planning_file) - paths = get_debug_paths(planning_pb) - if paths: - for name, path in paths: - ax.plot(path[0], path[1], label="%s:%s" % (name, planning_file)) - ax.legend() - - -def press_key(event): - if event.key == 'c': - files = g_args.planning_files - if len(files) != 2: - print('Need more than two files.') - return - command = ["cp"] - for f in files: - command.append(f) - if call(command) == 0: - print('command success: %s' % " ".join(command)) - sys.exit(0) - else: - print('Failed to run command: %s ' % " ".join(command)) - sys.exit(1) - - -if __name__ == '__main__': - import argparse - parser = argparse.ArgumentParser( - description="""A visualization tool that can plot one or multiple planning " - results, so that we can compare the differences. - Example: plot_planning_result.py result_file1.pb.txt result_file2.pb.txt""" - ) - parser.add_argument( - "planning_files", - action='store', - nargs="+", - help="The planning results") - parser.add_argument( - "--figure", - action='store', - type=str, - help="Save the planning results to picture, if not set, show on screen" - ) - g_args = parser.parse_args() - - matplotlib.rcParams['legend.fontsize'] = 10 - fig = plt.figure() - fig.canvas.mpl_connect('key_press_event', press_key) - ax = fig.gca(projection='3d') - ax.set_xlabel("x") - ax.set_ylabel("y") - ax.set_zlabel("speed") - - for planning_file in g_args.planning_files: - plot_planning(ax, planning_file) - - if g_args.figure: - plt.savefig(g_args.figure) - print('picture saved to %s' % g_args.figure) - else: - plt.show() diff --git a/modules/tools/plot_trace/plot_trace.py b/modules/tools/plot_trace/plot_trace.py deleted file mode 100755 index 5a21b282383..00000000000 --- a/modules/tools/plot_trace/plot_trace.py +++ /dev/null @@ -1,114 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import sys - -import matplotlib.animation as animation -import matplotlib.pyplot as plt -import numpy as np - -from cyber.python.cyber_py3 import cyber -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.localization_msgs import localization_pb2 - - -GPS_X = list() -GPS_Y = list() -GPS_LINE = None -DRIVING_MODE_TEXT = "" -CHASSIS_TOPIC = "/apollo/canbus/chassis" -LOCALIZATION_TOPIC = "/apollo/localization/pose" -IS_AUTO_MODE = False - - -def chassis_callback(chassis_data): - global IS_AUTO_MODE - if chassis_data.driving_mode == chassis_pb2.Chassis.COMPLETE_AUTO_DRIVE: - IS_AUTO_MODE = True - else: - IS_AUTO_MODE = False - - DRIVING_MODE_TEXT = str(chassis_data.driving_mode) - - -def localization_callback(localization_data): - global GPS_X - global GPS_Y - global IS_AUTO_MODE - if IS_AUTO_MODE: - GPS_X.append(localization_data.pose.position.x) - GPS_Y.append(localization_data.pose.position.y) - - -def setup_listener(node): - node.create_reader(CHASSIS_TOPIC, chassis_pb2.Chassis, chassis_callback) - node.create_reader(LOCALIZATION_TOPIC, - localization_pb2.LocalizationEstimate, - localization_callback) - while not cyber.is_shutdown(): - time.sleep(0.002) - - -def update(frame_number): - global GPS_X - global GPS_Y - if IS_AUTO_MODE and len(GPS_X) > 1: - min_len = min(len(GPS_X), len(GPS_Y)) - 1 - GPS_LINE.set_data(GPS_X[-min_len:], GPS_Y[-min_len:]) - - -if __name__ == '__main__': - import argparse - parser = argparse.ArgumentParser( - description="""A visualization tool that can plot a manual driving trace produced by the rtk_player tool, - and plot the autonomous driving trace in real time. - The manual driving trace is the blue lines, and the autonomous driving trace is the red lines. - It is visualization a way to verify the precision of the autonomous driving trace. - If you have a cyber record file, you can play the record and the tool will plot the received localization - message in realtime. To do that, start this tool first with a manual driving trace, and then - play record use another terminal with the following command [replace your_file.record to your - own record file]: cyber_record play -f your_file.record - """) - parser.add_argument( - "trace", - action='store', - type=str, - help='the manual driving trace produced by rtk_player') - - args = parser.parse_args() - - fig, ax = plt.subplots() - - with open(args.trace, 'r') as fp: - trace_data = np.genfromtxt(handle, delimiter=',', names=True) - ax.plot(trace_data['x'], trace_data['y'], 'b-', alpha=0.5, linewidth=1) - - cyber.init() - node = cyber.Node("plot_trace") - setup_listener(node) - - x_min = min(trace_data['x']) - x_max = max(trace_data['x']) - y_min = min(trace_data['y']) - y_max = max(trace_data['y']) - - GPS_LINE, = ax.plot(GPS_X, GPS_Y, 'r', linewidth=3, label="gps") - - ani = animation.FuncAnimation(fig, update, interval=100) - - plt.show() diff --git a/modules/tools/prediction/data_pipelines/BUILD b/modules/tools/prediction/data_pipelines/BUILD deleted file mode 100644 index f9802abbd7a..00000000000 --- a/modules/tools/prediction/data_pipelines/BUILD +++ /dev/null @@ -1,51 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") - -package(default_visibility = ["//visibility:public"]) - -py_binary( - name = "cruise_h5_preprocessing", - srcs = ["cruise_h5_preprocessing.py"], -) - -py_library( - name = "cruise_models", - srcs = ["cruise_models.py"], - deps = [ - "//modules/tools/prediction/data_pipelines/common:configure", - "//modules/tools/prediction/data_pipelines/proto:cruise_model_py_pb2", - ], -) - -py_binary( - name = "cruiseMLP_train", - srcs = ["cruiseMLP_train.py"], - deps = [ - ":cruise_models", - "//modules/tools/prediction/data_pipelines/common:configure", - "//modules/tools/prediction/data_pipelines/proto:cruise_model_py_pb2", - ], -) - -py_binary( - name = "junctionMLP_train", - srcs = ["junctionMLP_train.py"], - deps = [ - "//modules/tools/prediction/data_pipelines/proto:fnn_model_py_pb2", - ], -) - -py_binary( - name = "merge_h5", - srcs = ["merge_h5.py"], -) - -py_binary( - name = "mlp_train", - srcs = ["mlp_train.py"], - deps = [ - "//modules/tools/prediction/data_pipelines/common:configure", - "//modules/tools/prediction/data_pipelines/common:data_preprocess", - "//modules/tools/prediction/data_pipelines/common:log", - "//modules/tools/prediction/data_pipelines/proto:fnn_model_py_pb2", - ], -) diff --git a/modules/tools/prediction/data_pipelines/common/BUILD b/modules/tools/prediction/data_pipelines/common/BUILD deleted file mode 100644 index 1af21d9a8cf..00000000000 --- a/modules/tools/prediction/data_pipelines/common/BUILD +++ /dev/null @@ -1,74 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_library") - -package(default_visibility = ["//visibility:public"]) - -py_library( - name = "bounding_rectangle", - srcs = ["bounding_rectangle.py"], - deps = [ - ":rotation2d", - ":util", - ":vector2d", - ], -) - -py_library( - name = "configure", - srcs = ["configure.py"], -) - -py_library( - name = "data_preprocess", - srcs = ["data_preprocess.py"], -) - -py_library( - name = "feature_io", - srcs = ["feature_io.py"], - deps = [ - "//modules/common_msgs/prediction_msgs:feature_py_pb2", - "//modules/prediction/proto:offline_features_py_pb2", - ], -) - -py_library( - name = "log", - srcs = ["log.py"], -) - -py_library( - name = "online_to_offline", - srcs = ["online_to_offline.py"], - deps = [ - ":bounding_rectangle", - ":configure", - "//modules/prediction/proto:offline_features_py_pb2", - ], -) - -py_library( - name = "rotation2d", - srcs = ["rotation2d.py"], - deps = [ - ":vector2d", - ], -) - -py_library( - name = "trajectory", - srcs = ["trajectory.py"], - deps = [ - ":bounding_rectangle", - ":configure", - ], -) - -py_library( - name = "util", - srcs = ["util.py"], -) - -py_library( - name = "vector2d", - srcs = ["vector2d.py"], -) diff --git a/modules/tools/prediction/data_pipelines/common/bounding_rectangle.py b/modules/tools/prediction/data_pipelines/common/bounding_rectangle.py deleted file mode 100644 index a05c7b5b8e9..00000000000 --- a/modules/tools/prediction/data_pipelines/common/bounding_rectangle.py +++ /dev/null @@ -1,89 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - - -from modules.tools.prediction.data_pipelines.common.vector2d import Vector2 -from modules.tools.prediction.data_pipelines.common.rotation2d import rotate_fast -from modules.tools.prediction.data_pipelines.common.util import segment_overlap - - -class BoundingRectangle: - def __init__(self, x, y, theta, length, width): - - self.vertices = [None] * 4 - dx = 0.5 * length - dy = 0.5 * width - - cos_theta = cos(theta) - sin_theta = sin(theta) - - self.vertices[0] = rotate_fast(Vector2(dx, -dy), cos_theta, sin_theta) - self.vertices[1] = rotate_fast(Vector2(dx, dy), cos_theta, sin_theta) - self.vertices[2] = rotate_fast(Vector2(-dx, dy), cos_theta, sin_theta) - self.vertices[3] = rotate_fast(Vector2(-dx, -dy), cos_theta, sin_theta) - - for i in range(4): - self.vertices[i].x += x - self.vertices[i].y += y - - def overlap(self, rect): - for i in range(4): - v0 = self.vertices[i] - v1 = self.vertices[(i + 1) % 4] - - range_self = self.project(v0, v1) - range_other = rect.project(v0, v1) - - if segment_overlap(range_self[0], range_self[1], range_other[0], range_other[1]) == False: - return False - - for i in range(4): - v0 = rect.vertices[i] - v1 = rect.vertices[(i + 1) % 4] - - range_self = self.project(v0, v1) - range_other = rect.project(v0, v1) - - if segment_overlap(range_self[0], range_self[1], range_other[0], range_other[1]) == False: - return False - - return True - - def project(self, p0, p1): - v = p1.subtract(p0) - n = v.norm() - - rmin = float("inf") - rmax = float("-inf") - - for i in range(4): - t = self.vertices[i].subtract(p0) - r = t.dot(v) / n - - if r < rmin: - rmin = r - - if r > rmax: - rmax = r - - return [rmin, rmax] - - def print_vertices(self): - for i in range(4): - print(str(self.vertices[i].x) + "\t" + - str(self.vertices[i].y) + "\n") diff --git a/modules/tools/prediction/data_pipelines/common/configure.py b/modules/tools/prediction/data_pipelines/common/configure.py deleted file mode 100644 index e985f07f56f..00000000000 --- a/modules/tools/prediction/data_pipelines/common/configure.py +++ /dev/null @@ -1,57 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -parameters = { - 'config': { - 'need_to_label': True, - 'maximum_observation_time': 8.0 - }, - 'mlp': { - 'train_data_rate': 0.8, - 'size_obstacle_feature': 22, - 'size_lane_sequence_feature': 40, - 'dim_input': 22 + 40, - 'dim_hidden_1': 30, - 'dim_hidden_2': 15, - 'dim_output': 1 - }, - 'cruise_mlp': { - 'dim_input': 23 + 5 * 9 + 20 * 4 + 8, - 'dim_hidden_1': 50, - 'dim_hidden_2': 18, - 'dim_output': 1 - }, - 'junction_mlp': { - 'dim_input': 3 + 60, - 'dim_hidden_1': 30, - 'dim_hidden_2': 15, - 'dim_output': 12 - }, - 'feature': { - 'threshold_label_time_delta': 1.0, - 'prediction_label_timeframe': 3.0, - 'maximum_maneuver_finish_time': 3.0, - - # Lane change is defined to be finished if the ratio of deviation - # from center-line to the lane width is within this: (must be < 0.5) - 'lane_change_finish_condition': 0.1, - 'maximum_observation_time': 6.0 - } -} - -labels = {'go_false': 0, 'go_true': 1, 'cutin_false': -1, 'cutin_true': 2} diff --git a/modules/tools/prediction/data_pipelines/common/data_preprocess.py b/modules/tools/prediction/data_pipelines/common/data_preprocess.py deleted file mode 100644 index 5f381bdb910..00000000000 --- a/modules/tools/prediction/data_pipelines/common/data_preprocess.py +++ /dev/null @@ -1,81 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import os -import h5py -import numpy as np -from random import choice -from random import randint -from random import shuffle -from time import time - - -def load_h5(filename): - if not (os.path.exists(filename)): - logging.error("file: {}, does not exist".format(filename)) - os._exit(1) - if os.path.splitext(filename)[1] != '.h5': - logging.error("file: {} is not an hdf5 file".format(filename)) - os._exit(1) - - samples = dict() - h5_file = h5py.File(filename, 'r') - for key in h5_file.keys(): - samples[key] = h5_file[key][:] - - return samples['data'] - - -def down_sample(data): - cutin_false_drate = 0.5 - go_false_drate = 0.8 - go_true_drate = 0.9 - cutin_true_drate = 0.0 - - label = data[:, -1] - size = np.shape(label)[0] - - cutin_false_index = (label == -1) - go_false_index = (label == 0) - go_true_index = (label == 1) - cutin_true_index = (label == 2) - - rand = np.random.random((size)) - - cutin_false_select = np.logical_and(cutin_false_index, - rand > cutin_false_drate) - cutin_true_select = np.logical_and(cutin_true_index, - rand > cutin_true_drate) - go_false_select = np.logical_and(go_false_index, rand > go_false_drate) - go_true_select = np.logical_and(go_true_index, rand > go_true_drate) - - all_select = np.logical_or(cutin_false_select, cutin_true_select) - all_select = np.logical_or(all_select, go_false_select) - all_select = np.logical_or(all_select, go_true_select) - - data_downsampled = data[all_select, :] - - return data_downsampled - - -def train_test_split(data, train_rate): - data_size = np.shape(data)[0] - train_size = int(data_size * train_rate) - train = data[0:train_size, ] - test = data[train_size:, ] - return train, test diff --git a/modules/tools/prediction/data_pipelines/common/feature_io.py b/modules/tools/prediction/data_pipelines/common/feature_io.py deleted file mode 100644 index b4c45b78446..00000000000 --- a/modules/tools/prediction/data_pipelines/common/feature_io.py +++ /dev/null @@ -1,103 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import copy -import logging -import sys - -from google.protobuf.internal import decoder -from google.protobuf.internal import encoder -import google.protobuf.text_format as text_format - -from modules.common_msgs.prediction_msgs import feature_pb2 -from modules.prediction.proto import offline_features_pb2 - - -def readVarint32(stream): - """ - read block size from file stream - """ - mask = 0x80 # (1 << 7) - raw_varint32 = [] - while 1: - b = stream.read(1) - if b == "": - break - raw_varint32.append(b) - if not (ord(b) & mask): - break - return raw_varint32 - - -def load_protobuf(filename): - """ - read a file in protobuf binary - """ - offline_features = offline_features_pb2.Features() - with open(filename, 'rb') as file_in: - offline_features.ParseFromString(file_in.read()) - return offline_features.feature - - -def load_label_feature(filename): - features = [] - with open(filename, 'rb') as f: - size = readVarint32(f) - while size: - read_bytes, _ = decoder._DecodeVarint32(size, 0) - data = f.read(read_bytes) - if len(data) < read_bytes: - print("Failed to load protobuf") - break - fea = feature_pb2.Feature() - fea.ParseFromString(data) - features.append(fea) - size = readVarint32(f) - return features - - -def save_protobuf(filename, feature_trajectories): - """ - save a features in the given filename - """ - with open(filename, 'wb') as f: - for features in feature_trajectories: - for fea in features: - serializedMessage = fea.SerializeToString() - delimiter = encoder._VarintBytes(len(serializedMessage)) - f.write(delimiter + serializedMessage) - - -def build_trajectory(features): - """ - classify features by id and build trajectories of feature - """ - fea_dict = dict() - for fea in features: - if fea.id in fea_dict.keys(): - fea_dict[fea.id].append(fea) - else: - fea_dict[fea.id] = [fea] - - for k in fea_dict.keys(): - if len(fea_dict[k]) < 2: - del fea_dict[k] - continue - fea_dict[k].sort(key=lambda x: x.timestamp) - - return fea_dict diff --git a/modules/tools/prediction/data_pipelines/common/log.py b/modules/tools/prediction/data_pipelines/common/log.py deleted file mode 100644 index ce3eeaf2c8a..00000000000 --- a/modules/tools/prediction/data_pipelines/common/log.py +++ /dev/null @@ -1,49 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import os -import logging -import logging.handlers - - -def init_log( - log_path, - level=logging.INFO, - when="D", - backup=7, - format="%(levelname)s: %(asctime)s: %(filename)s:%(lineno)d * %(thread)d %(message)s", - datefmt="%m-%d %H:%M:%S"): - formatter = logging.Formatter(format, datefmt) - logger = logging.getLogger() - logger.setLevel(level) - - dir = os.path.dirname(log_path) - if not os.path.isdir(dir): - os.makedirs(dir) - - handler = logging.handlers.TimedRotatingFileHandler( - log_path + ".log", when=when, backupCount=backup) - handler.setLevel(level) - handler.setFormatter(formatter) - logger.addHandler(handler) - - handler = logging.handlers.TimedRotatingFileHandler( - log_path + ".log.wf", when=when, backupCount=backup) - handler.setLevel(logging.WARNING) - handler.setFormatter(formatter) - logger.addHandler(handler) diff --git a/modules/tools/prediction/data_pipelines/common/online_to_offline.py b/modules/tools/prediction/data_pipelines/common/online_to_offline.py deleted file mode 100644 index fa913edd364..00000000000 --- a/modules/tools/prediction/data_pipelines/common/online_to_offline.py +++ /dev/null @@ -1,494 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import abc -import logging -import math - -from google.protobuf.internal import decoder -from google.protobuf.internal import encoder -import numpy as np - -from modules.prediction.proto import offline_features_pb2 -from modules.tools.prediction.data_pipelines.common.bounding_rectangle import BoundingRectangle -from modules.tools.prediction.data_pipelines.common.configure import parameters - - -param_fea = parameters['feature'] - - -class LabelGenerator(object): - - def __init__(self): - self.filepath = None - ''' - feature_dict contains the organized Feature in the following way: - obstacle_ID --> [Feature1, Feature2, Feature3, ...] (sequentially sorted) - ''' - self.feature_dict = dict() - - ''' - observation_dict contains the important observations of the subsequent - Features for each obstacle at every timestamp: - obstacle_ID@timestamp --> dictionary of observations - where dictionary of observations contains: - 'obs_traj': the trajectory points (x, y, vel_heading) up to - max_observation_time this trajectory poitns must - be consecutive (0.1sec sampling period) - 'obs_traj_len': length of trajectory points - 'obs_actual_lane_ids': the actual sequence of lane_segment ids - the obstacle steps on - 'has_started_lane_change': whether the obstacle has started lane - changing within max_observation_time - 'has_finished_lane_change': whether it has finished lane changing - 'lane_change_start_time': - 'lane_change_finish_time': - 'is_jittering': - 'new_lane_id': - 'total_observed_time_span': - This observation_dict, once constructed, can be reused by various labeling - functions. - ''' - self.observation_dict = dict() - self.future_status_dict = dict() - self.cruise_label_dict = dict() - self.junction_label_dict = dict() - - def LoadFeaturePBAndSaveLabelFiles(self, input_filepath): - ''' - This function will be used to replace all the functionalities in - generate_cruise_label.py - ''' - self.filepath = input_filepath - feature_sequences = self.LoadPBFeatures(input_filepath) - self.OrganizeFeatures(feature_sequences) - del feature_sequences # Try to free up some memory - self.ObserveAllFeatureSequences() - - ''' - @brief: parse the pb file of Feature of all obstacles at all times. - @input filepath: the path of the pb file that contains all the features of - every obstacle at every timestamp. - @output: python readable format of the same content. - ''' - - def LoadPBFeatures(self, filepath): - self.filepath = filepath - offline_features = offline_features_pb2.Features() - with open(filepath, 'rb') as file_in: - offline_features.ParseFromString(file_in.read()) - return offline_features.feature - - ''' - @brief: save the feature_sequences to an output protobuf file. - @input filepath: the path of the output pb file. - @input feature_sequences: the content to be saved. - ''' - @staticmethod - def SaveOutputPB(filepath, pb_message): - with open(filepath, 'wb') as file: - serializedMessage = pb_message.SerializeToString() - file.write(serializedMessage) - - ''' - @brief: organize the features by obstacle IDs first, then sort each - obstacle's feature according to time sequence. - @input features: the unorganized features - @output: organized (meaning: grouped by obstacle ID and sorted by time) - features. - ''' - - def OrganizeFeatures(self, features): - # Organize Feature by obstacle_ID (put those belonging to the same obstacle together) - for feature in features: - if feature.id in self.feature_dict.keys(): - self.feature_dict[feature.id].append(feature) - else: - self.feature_dict[feature.id] = [feature] - - # For the same obstacle, sort the Feature sequentially. - for obs_id in self.feature_dict.keys(): - if len(self.feature_dict[obs_id]) < 2: - del self.feature_dict[obs_id] - continue - self.feature_dict[obs_id].sort(key=lambda x: x.timestamp) - - ''' - @brief: observe all feature sequences and build observation_dict. - @output: the complete observation_dict. - ''' - - def ObserveAllFeatureSequences(self): - for obs_id, feature_sequence in self.feature_dict.items(): - for idx, feature in enumerate(feature_sequence): - if not feature.HasField('lane') or \ - not feature.lane.HasField('lane_feature'): - # print('No lane feature, cancel labeling') - continue - self.ObserveFeatureSequence(feature_sequence, idx) - np.save(self.filepath + '.npy', self.observation_dict) - - ''' - @brief: Observe the sequence of Features following the Feature at - idx_curr and save some important observations in the class - so that it can be used by various label functions. - @input feature_sequence: A sorted sequence of Feature corresponding to - one obstacle. - @input idx_curr: The index of the current Feature to be labelled. - We will look at the subsequent Features following this - one to complete labeling. - @output: All saved as class variables in observation_dict, - including: its trajectory info and its lane changing info. - ''' - - def ObserveFeatureSequence(self, feature_sequence, idx_curr): - # Initialization. - feature_curr = feature_sequence[idx_curr] - dict_key = "{}@{:.3f}".format(feature_curr.id, feature_curr.timestamp) - if dict_key in self.observation_dict.keys(): - return - - # Record all the lane segments belonging to the lane sequence that the - # obstacle is currently on. - curr_lane_segments = set() - for lane_sequence in feature_curr.lane.lane_graph.lane_sequence: - if lane_sequence.vehicle_on_lane: - for lane_segment in lane_sequence.lane_segment: - curr_lane_segments.add(lane_segment.lane_id) - if len(curr_lane_segments) == 0: - # print("Obstacle is not on any lane.") - return - - # Declare needed varables. - new_lane_id = None - has_started_lane_change = False - has_finished_lane_change = False - lane_change_start_time = None - lane_change_finish_time = None - is_jittering = False - feature_seq_len = len(feature_sequence) - prev_timestamp = -1.0 - obs_actual_lane_ids = [] - obs_traj = [] - total_observed_time_span = 0.0 - - # This goes through all the subsequent features in this sequence - # of features up to the maximum_observation_time. - for j in range(idx_curr, feature_seq_len): - # If timespan exceeds max. observation time, then end observing. - time_span = feature_sequence[j].timestamp - feature_curr.timestamp - if time_span > param_fea['maximum_observation_time']: - break - total_observed_time_span = time_span - - ##################################################################### - # Update the obstacle trajectory: - # Only update for consecutive (sampling rate = 0.1sec) points. - obs_traj.append((feature_sequence[j].position.x, - feature_sequence[j].position.y, - feature_sequence[j].velocity_heading, - feature_sequence[j].speed, - feature_sequence[j].length, - feature_sequence[j].width, - feature_sequence[j].timestamp)) - - ##################################################################### - # Update the lane-change info (mainly for cruise scenario): - if feature_sequence[j].HasField('lane') and \ - feature_sequence[j].lane.HasField('lane_feature'): - # If jittering or done, then jump over this part. - if (is_jittering or has_finished_lane_change): - continue - # Record the sequence of lane_segments the obstacle stepped on. - lane_id_j = feature_sequence[j].lane.lane_feature.lane_id - if lane_id_j not in obs_actual_lane_ids: - obs_actual_lane_ids.append(lane_id_j) - # If step into another lane, label lane change to be started. - if lane_id_j not in curr_lane_segments: - # If it's the first time, log new_lane_id - if not has_started_lane_change: - has_started_lane_change = True - lane_change_start_time = time_span - new_lane_id = lane_id_j - else: - # If it stepped into other lanes and now comes back, it's jittering! - if has_started_lane_change: - is_jittering = True - continue - # If roughly get to the center of another lane, label lane change to be finished. - left_bound = feature_sequence[j].lane.lane_feature.dist_to_left_boundary - right_bound = feature_sequence[j].lane.lane_feature.dist_to_right_boundary - if left_bound / (left_bound + right_bound) > (0.5 - param_fea['lane_change_finish_condition']) and \ - left_bound / (left_bound + right_bound) < (0.5 + param_fea['lane_change_finish_condition']): - if has_started_lane_change: - # This means that the obstacle has finished lane change. - has_finished_lane_change = True - lane_change_finish_time = time_span - else: - # This means that the obstacle moves back to the center - # of the original lane for the first time. - if lane_change_finish_time is None: - lane_change_finish_time = time_span - - if len(obs_actual_lane_ids) == 0: - # print("No lane id") - return - - # Update the observation_dict: - dict_val = dict() - dict_val['obs_traj'] = obs_traj - dict_val['obs_traj_len'] = len(obs_traj) - dict_val['obs_actual_lane_ids'] = obs_actual_lane_ids - dict_val['has_started_lane_change'] = has_started_lane_change - dict_val['has_finished_lane_change'] = has_finished_lane_change - dict_val['lane_change_start_time'] = lane_change_start_time - dict_val['lane_change_finish_time'] = lane_change_finish_time - dict_val['is_jittering'] = is_jittering - dict_val['new_lane_id'] = new_lane_id - dict_val['total_observed_time_span'] = total_observed_time_span - self.observation_dict["{}@{:.3f}".format( - feature_curr.id, feature_curr.timestamp)] = dict_val - return - - ''' - @brief Based on the observation, label each lane sequence accordingly: - - label whether the obstacle is on the lane_sequence - within a certain amount of time. - - if there is lane chage, label the time it takes to get to that lane. - ''' - - def LabelSingleLane(self, period_of_interest=3.0): - output_features = offline_features_pb2.Features() - for obs_id, feature_sequence in self.feature_dict.items(): - feature_seq_len = len(feature_sequence) - for idx, feature in enumerate(feature_sequence): - if not feature.HasField('lane') or \ - not feature.lane.HasField('lane_feature'): - # print "No lane feature, cancel labeling" - continue - - # Observe the subsequent Features - if "{}@{:.3f}".format(feature.id, feature.timestamp) not in self.observation_dict: - continue - observed_val = self.observation_dict["{}@{:.3f}".format( - feature.id, feature.timestamp)] - - lane_sequence_dict = dict() - # Based on the observation, label data. - for lane_sequence in feature.lane.lane_graph.lane_sequence: - # Sanity check. - if len(lane_sequence.lane_segment) == 0: - print('There is no lane segment in this sequence.') - continue - - # Handle jittering data - if observed_val['is_jittering']: - lane_sequence.label = -10 - lane_sequence.time_to_lane_center = -1.0 - lane_sequence.time_to_lane_edge = -1.0 - continue - - # Handle the case that we didn't obesrve enough Features to label - if observed_val['total_observed_time_span'] < period_of_interest and \ - not observed_val['has_started_lane_change']: - lane_sequence.label = -20 - lane_sequence.time_to_lane_center = -1.0 - lane_sequence.time_to_lane_edge = -1.0 - - # The current lane is obstacle's original lane. (labels: 0,2,4) - if lane_sequence.vehicle_on_lane: - # Obs is following ONE OF its original lanes: - if not observed_val['has_started_lane_change'] or \ - observed_val['lane_change_start_time'] > period_of_interest: - # Record this lane_sequence's lane_ids - current_lane_ids = [] - for k in range(len(lane_sequence.lane_segment)): - if lane_sequence.lane_segment[k].HasField('lane_id'): - current_lane_ids.append(lane_sequence.lane_segment[k].lane_id) - - is_following_this_lane = True - for l_id in range(1, min(len(current_lane_ids), - len(observed_val['obs_actual_lane_ids']))): - if current_lane_ids[l_id] != observed_val['obs_actual_lane_ids'][l_id]: - is_following_this_lane = False - break - - # Obs is following this original lane: - if is_following_this_lane: - # Obstacle is following this original lane and moved to lane-center - if observed_val['lane_change_finish_time'] is not None: - lane_sequence.label = 4 - lane_sequence.time_to_lane_edge = -1.0 - lane_sequence.time_to_lane_center = -1.0 - # Obstacle is following this original lane but is never at lane-center: - else: - lane_sequence.label = 2 - lane_sequence.time_to_lane_edge = -1.0 - lane_sequence.time_to_lane_center = -1.0 - # Obs is following another original lane: - else: - lane_sequence.label = 0 - lane_sequence.time_to_lane_edge = -1.0 - lane_sequence.time_to_lane_center = -1.0 - - # Obs has stepped out of this lane within period_of_interest. - else: - lane_sequence.label = 0 - lane_sequence.time_to_lane_edge = -1.0 - lane_sequence.time_to_lane_center = -1.0 - - # The current lane is NOT obstacle's original lane. (labels: -1,1,3) - else: - # Obstacle is following the original lane. - if not observed_val['has_started_lane_change'] or \ - observed_val['lane_change_start_time'] > period_of_interest: - lane_sequence.label = -1 - lane_sequence.time_to_lane_edge = -1.0 - lane_sequence.time_to_lane_center = -1.0 - else: - new_lane_id_is_in_this_lane_seq = False - for lane_segment in lane_sequence.lane_segment: - if lane_segment.lane_id == observed_val['new_lane_id']: - new_lane_id_is_in_this_lane_seq = True - break - # Obstacle has changed to this lane. - if new_lane_id_is_in_this_lane_seq: - # Obstacle has finished lane changing within time_of_interest. - if observed_val['has_finished_lane_change'] and \ - observed_val['lane_change_finish_time'] < period_of_interest: - lane_sequence.label = 3 - lane_sequence.time_to_lane_edge = observed_val['lane_change_start_time'] - lane_sequence.time_to_lane_center = observed_val['lane_change_finish_time'] - # Obstacle started lane changing but haven't finished yet. - else: - lane_sequence.label = 1 - lane_sequence.time_to_lane_edge = observed_val['lane_change_start_time'] - lane_sequence.time_to_lane_center = -1.0 - - # Obstacle has changed to some other lane. - else: - lane_sequence.label = -1 - lane_sequence.time_to_lane_edge = -1.0 - lane_sequence.time_to_lane_center = -1.0 - - for lane_sequence in feature.lane.lane_graph.lane_sequence: - lane_sequence_dict[lane_sequence.lane_sequence_id] = [lane_sequence.label, - lane_sequence.time_to_lane_center, lane_sequence.time_to_lane_edge] - self.cruise_label_dict["{}@{:.3f}".format( - feature.id, feature.timestamp)] = lane_sequence_dict - np.save(self.filepath + '.cruise_label.npy', self.cruise_label_dict) - - def LabelTrajectory(self, period_of_interest=3.0): - output_features = offline_features_pb2.Features() - for obs_id, feature_sequence in self.feature_dict.items(): - for idx, feature in enumerate(feature_sequence): - # Observe the subsequent Features - if "{}@{:.3f}".format(feature.id, feature.timestamp) not in self.observation_dict: - continue - observed_val = self.observation_dict["{}@{:.3f}".format( - feature.id, feature.timestamp)] - self.future_status_dict["{}@{:.3f}".format( - feature.id, feature.timestamp)] = observed_val['obs_traj'] - np.save(self.filepath + '.future_status.npy', self.future_status_dict) - # for point in observed_val['obs_traj']: - # traj_point = feature.future_trajectory_points.add() - # traj_point.path_point.x = point[0] - # traj_point.path_point.y = point[1] - # traj_point.path_point.velocity_heading = point[2] - # traj_point.timestamp = point[3] - - # output_features.feature.add().CopyFrom(feature) - - # self.SaveOutputPB(self.filepath + '.future_status.label', output_features) - - def LabelJunctionExit(self): - ''' - label feature trajectory according to real future lane sequence in 7s - ''' - output_features = offline_features_pb2.Features() - for obs_id, feature_sequence in self.feature_dict.items(): - feature_seq_len = len(feature_sequence) - for i, fea in enumerate(feature_sequence): - # Sanity check. - if not fea.HasField('junction_feature') or \ - not len(fea.junction_feature.junction_exit): - # print("No junction_feature, junction_exit, or junction_mlp_feature, not labeling this frame.") - continue - curr_pos = np.array([fea.position.x, fea.position.y]) - # Only keep speed > 1 - # TODO(all) consider recovery - # if fea.speed <= 1: - # continue - heading = math.atan2(fea.raw_velocity.y, fea.raw_velocity.x) - # Construct dictionary of all exit with dict[exit_lane_id] = np.array(exit_position) - exit_dict = dict() - exit_pos_dict = dict() - mask = [0] * 12 - for junction_exit in fea.junction_feature.junction_exit: - if junction_exit.HasField('exit_lane_id'): - exit_dict[junction_exit.exit_lane_id] = \ - BoundingRectangle(junction_exit.exit_position.x, - junction_exit.exit_position.y, - junction_exit.exit_heading, - 0.01, - junction_exit.exit_width) - exit_pos = np.array([junction_exit.exit_position.x, - junction_exit.exit_position.y]) - exit_pos_dict[junction_exit.exit_lane_id] = exit_pos - delta_pos = exit_pos - curr_pos - angle = math.atan2(delta_pos[1], delta_pos[0]) - heading - d_idx = int((angle / (2.0 * np.pi) + 1.0 / 24) * 12 % 12) - mask[d_idx] = 1 - - # Searching for up to 100 frames (10 seconds) - for j in range(i, min(i + 100, feature_seq_len)): - car_bounding = BoundingRectangle(feature_sequence[j].position.x, - feature_sequence[j].position.y, - math.atan2(feature_sequence[j].raw_velocity.y, - feature_sequence[j].raw_velocity.x), - feature_sequence[j].length, - feature_sequence[j].width) - for key, value in exit_dict.items(): - if car_bounding.overlap(value): - exit_pos = exit_pos_dict[key] - delta_pos = exit_pos - curr_pos - angle = math.atan2( - delta_pos[1], delta_pos[0]) - heading - d_idx = int((angle / (2.0 * np.pi) + 1.0 / 24) * 12 % 12) - label = [0] * 12 - label[d_idx] = 1 - fea.junction_feature.junction_mlp_label.extend(label) - self.junction_label_dict["{}@{:.3f}".format( - fea.id, fea.timestamp)] = label + mask - break # actually break two level - else: - continue - break - np.save(self.filepath + '.junction_label.npy', self.junction_label_dict) - # if fea.HasField('junction_feature') and \ - # len(fea.junction_feature.junction_mlp_label) > 0: - # output_features.feature.add().CopyFrom(fea) - - # self.SaveOutputPB(self.filepath + '.junction.label', output_features) - - def Label(self): - self.LabelTrajectory() - self.LabelSingleLane() - self.LabelJunctionExit() - # TODO(all): - # - implement label multiple lane diff --git a/modules/tools/prediction/data_pipelines/common/rotation2d.py b/modules/tools/prediction/data_pipelines/common/rotation2d.py deleted file mode 100644 index 5da7dc2894a..00000000000 --- a/modules/tools/prediction/data_pipelines/common/rotation2d.py +++ /dev/null @@ -1,35 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - - -from math import cos, sin -from modules.tools.prediction.data_pipelines.common.vector2d import Vector2 - - -def rotate(v, theta): - cos_theta = cos(theta) - sin_theta = sin(theta) - - return rotate_fast(v, cos_theta, sin_theta) - - -def rotate_fast(v, cos_theta, sin_theta): - x = cos_theta * v.x - sin_theta * v.y - y = sin_theta * v.x + cos_theta * v.y - - return Vector2(x, y) diff --git a/modules/tools/prediction/data_pipelines/common/trajectory.py b/modules/tools/prediction/data_pipelines/common/trajectory.py deleted file mode 100644 index 767ea882920..00000000000 --- a/modules/tools/prediction/data_pipelines/common/trajectory.py +++ /dev/null @@ -1,431 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import abc -import logging -import math - -import numpy as np - -from modules.tools.prediction.data_pipelines.common.bounding_rectangle import BoundingRectangle -from modules.tools.prediction.data_pipelines.common.configure import parameters - - -param_fea = parameters['feature'] - - -class TrajectoryToSample(object, metaclass=abc.ABCMeta): - - def __call__(self, trajectory): - self.clean(trajectory) - self.label(trajectory) - data = self.pack(trajectory) - return data - - @staticmethod - def clean(trajectory): - ''' - Clean up the feature points when lane_id changing abruptly, - meaning that if the lane_id of current timestamp is different - from that of the previous one and that of the next one, remove - this contaminated data. - ''' - results = [] - traj_len = len(trajectory) - for i in range(traj_len - 2, 0, -1): - if not trajectory[i].HasField('lane') or \ - not trajectory[i].lane.HasField('lane_feature'): - continue - - lane_seq_sz = len(trajectory[i].lane.lane_graph.lane_sequence) - if lane_seq_sz == 0: - continue - elif lane_seq_sz > 10: - print("Too many lane sequences:", lane_seq_sz) - - fea_prev = trajectory[i - 1] - fea_curr = trajectory[i] - fea_post = trajectory[i + 1] - - if fea_prev.HasField('lane') and \ - fea_prev.lane.HasField('lane_feature'): - lane_id_prev = fea_prev.lane.lane_feature.lane_id - else: - continue - - if fea_curr.HasField('lane') and \ - fea_curr.lane.HasField('lane_feature'): - lane_id_curr = fea_curr.lane.lane_feature.lane_id - else: - continue - - if fea_post.HasField('lane') and \ - fea_post.lane.HasField('lane_feature'): - lane_id_post = fea_post.lane.lane_feature.lane_id - else: - continue - - if lane_id_curr == lane_id_prev or lane_id_curr == lane_id_post: - results.append(trajectory[i]) - - results.reverse() - return results - - @staticmethod - def cmp_lane_seq(real_seq, predict_seq): - ''' - -1: False Cutin - 0: False Go - 1: True Go - 2: True Cutin - ''' - if real_seq[0] == predict_seq[0]: - for i in range(1, len(real_seq)): - if len(real_seq) > len(predict_seq): - return 0 - if real_seq[i] != predict_seq[i]: - return 0 - return 1 - - else: - if len(real_seq) == 1: - return -1 - - for i in range(1, len(real_seq)): - if len(real_seq) - 1 > len(predict_seq): - return -1 - if real_seq[i] != predict_seq[i - 1]: - return -1 - return 2 - - def is_successor_lane(self, feature, lane_id): - ''' - return True if lane_id is the successor lane of feature - ''' - if feature.HasField('lane') and \ - feature.lane.HasField('lane_graph') and \ - len(feature.lane.lane_graph.lane_sequence) > 0: - for lane_seq in feature.lane.lane_graph.lane_sequence: - seq_lane_ids = [] - for lan_seq in lane_seq.lane_segment: - seq_lane_ids.append(lane_seg.lane_id) - if feature.lane.lane_feature.lane_id in seq_lane_ids and \ - lane_id in seq_lane_ids: - return True - return False - else: - return True - - @classmethod - def label(cls, trajectory): - ''' - label feature trajectory according to real future lane sequence in 3s - ''' - traj_len = len(trajectory) - for i, fea in enumerate(trajectory): - if not fea.HasField('lane') or \ - not fea.lane.HasField('lane_feature'): - print("No lane feature, cancel labeling") - continue - - future_lane_ids = [] - for j in range(i, traj_len): - time_span = trajectory[j].timestamp - fea.timestamp - if time_span > param_fea['prediction_label_timeframe']: - break - if not trajectory[j].HasField('lane') or \ - not trajectory[j].lane.HasField('lane_feature'): - continue - - lane_id_j = trajectory[j].lane.lane_feature.lane_id - trajectory[i].label_update_time_delta = time_span - if lane_id_j in future_lane_ids: - continue - else: - future_lane_ids.append(lane_id_j) - - if len(future_lane_ids) < 1: - print("No lane id") - continue - - seq_size = len(fea.lane.lane_graph.lane_sequence) - for j in range(seq_size): - seq = fea.lane.lane_graph.lane_sequence[j] - if len(seq.lane_segment) == 0: - continue - predict_lane_ids = [] - for k in range(len(seq.lane_segment)): - if seq.lane_segment[k].HasField('lane_id'): - predict_lane_ids.append(seq.lane_segment[k].lane_id) - - seq.label = cls.cmp_lane_seq(future_lane_ids, predict_lane_ids) - return trajectory - - @classmethod - def label_cruise(cls, feature_sequence): - ''' - Label feature trajectory according to real future lane sequence - in 6sec - ''' - feature_seq_len = len(feature_sequence) - for i, fea in enumerate(feature_sequence): - # Sanity check. - if not fea.HasField('lane') or \ - not fea.lane.HasField('lane_feature'): - print("No lane feature, cancel labeling") - continue - - # Find the lane_sequence at which the obstacle is located, - # and put all the lane_segment ids into a set. - curr_lane_seq = set() - for lane_sequence in fea.lane.lane_graph.lane_sequence: - if lane_sequence.vehicle_on_lane: - for lane_segment in lane_sequence.lane_segment: - curr_lane_seq.add(lane_segment.lane_id) - if len(curr_lane_seq) == 0: - print("Obstacle is not on any lane.") - continue - - new_lane_id = None - has_started_lane_change = False - has_finished_lane_change = False - lane_change_start_time = None - lane_change_finish_time = None - is_jittering = False - - # This goes through all the subsequent features in this sequence - # of features (this is the GROUND_TRUTH!) - obs_actual_lane_ids = [] - for j in range(i, feature_seq_len): - # If timespan exceeds max. maneuver finish time, then break. - time_span = feature_sequence[j].timestamp - fea.timestamp - if time_span > param_fea['maximum_maneuver_finish_time']: - break - - # Sanity check. - if not feature_sequence[j].HasField('lane') or \ - not feature_sequence[j].lane.HasField('lane_feature'): - continue - fea.label_update_time_delta = time_span - - # If step into another lane, label lane change to be started. - lane_id_j = feature_sequence[j].lane.lane_feature.lane_id - - if lane_id_j not in obs_actual_lane_ids: - obs_actual_lane_ids.append(lane_id_j) - - if lane_id_j not in curr_lane_seq: - # If it's the first time, log new_lane_id - if has_started_lane_change == False: - has_started_lane_change = True - lane_change_start_time = time_span - new_lane_id = lane_id_j - else: - # If it stepped into other lanes and now comes back, it's jittering! - if has_started_lane_change: - is_jittering = True - # This is to let such data not be eliminated by label_file function - fea.label_update_time_delta = param_fea['maximum_maneuver_finish_time'] - break - - # If roughly get to the center of another lane, label lane change to be finished. - left_bound = feature_sequence[j].lane.lane_feature.dist_to_left_boundary - right_bound = feature_sequence[j].lane.lane_feature.dist_to_right_boundary - if left_bound / (left_bound + right_bound) > (0.5 - param_fea['lane_change_finish_condition']) and \ - left_bound / (left_bound + right_bound) < (0.5 + param_fea['lane_change_finish_condition']): - if has_started_lane_change: - has_finished_lane_change = True - lane_change_finish_time = time_span - # new_lane_id = lane_id_j - - # This is to let such data not be eliminated by label_file function - fea.label_update_time_delta = param_fea['maximum_maneuver_finish_time'] - break - else: - # This means that the obstacle moves back to the center - # of the original lane for the first time. - if lane_change_finish_time is None: - lane_change_finish_time = time_span - - if len(obs_actual_lane_ids) < 1: - print("No lane id") - continue - - ''' - For every lane_sequence in the lane_graph, - assign a label and a finish_time. - - -10: Lane jittering - - -1: False Cut-in - 1: True Cut-in but not to lane_center - 3: True Cut-in and reached lane_center - - 0: Fales Go - 2: True Go but not to lane_center - 4: True Go and reached lane_center - ''' - - # This is to label each saved lane_sequence. - for lane_sequence in fea.lane.lane_graph.lane_sequence: - # Sanity check. - if len(lane_sequence.lane_segment) == 0: - continue - - if is_jittering: - lane_sequence.label = -10 - lane_sequence.time_to_lane_center = -1.0 - lane_sequence.time_to_lane_edge = -1.0 - continue - - # The current lane is obstacle's original lane. - if lane_sequence.vehicle_on_lane: - - # Obs is following ONE OF its original lanes: - if not has_started_lane_change: - # Record this lane_sequence's lane_ids - current_lane_ids = [] - for k in range(len(lane_sequence.lane_segment)): - if lane_sequence.lane_segment[k].HasField('lane_id'): - current_lane_ids.append( - lane_sequence.lane_segment[k].lane_id) - - is_following_this_lane = True - for l_id in range(1, min(len(current_lane_ids), len(obs_actual_lane_ids))): - if current_lane_ids[l_id] != obs_actual_lane_ids[l_id]: - is_following_this_lane = False - break - - # Obs is following this original lane: - if is_following_this_lane: - # Obstacle is following this original lane and moved to lane-center - if lane_change_finish_time is not None: - lane_sequence.label = 4 - lane_sequence.time_to_lane_edge = -1.0 - lane_sequence.time_to_lane_center = lane_change_finish_time - # Obstacle is following this original lane but is never at lane-center: - else: - lane_sequence.label = 2 - lane_sequence.time_to_lane_edge = -1.0 - lane_sequence.time_to_lane_center = -1.0 - # Obs is following another original lane: - else: - lane_sequence.label = 0 - lane_sequence.time_to_lane_edge = -1.0 - lane_sequence.time_to_lane_center = -1.0 - - # Obs has stepped out of this lane within 6sec. - else: - lane_sequence.label = 0 - lane_sequence.time_to_lane_edge = -1.0 - lane_sequence.time_to_lane_center = -1.0 - - # The current lane is NOT obstacle's original lane. - else: - # Obstacle is following the original lane. - if not has_started_lane_change: - lane_sequence.label = -1 - lane_sequence.time_to_lane_edge = -1.0 - lane_sequence.time_to_lane_center = -1.0 - else: - new_lane_id_is_in_this_lane_seq = False - for lane_segment in lane_sequence.lane_segment: - if lane_segment.lane_id == new_lane_id: - new_lane_id_is_in_this_lane_seq = True - break - # Obstacle has changed to this lane. - if new_lane_id_is_in_this_lane_seq: - # Obstacle has finished lane changing within 6 sec. - if has_finished_lane_change: - lane_sequence.label = 3 - lane_sequence.time_to_lane_edge = lane_change_start_time - lane_sequence.time_to_lane_center = lane_change_finish_time - # Obstacle started lane changing but haven't finished yet. - else: - lane_sequence.label = 1 - lane_sequence.time_to_lane_edge = lane_change_start_time - lane_sequence.time_to_lane_center = -1.0 - - # Obstacle has changed to some other lane. - else: - lane_sequence.label = -1 - lane_sequence.time_to_lane_edge = -1.0 - lane_sequence.time_to_lane_center = -1.0 - - return feature_sequence - - @classmethod - def label_junction(cls, trajectory): - ''' - label feature trajectory according to real future lane sequence in 7s - ''' - traj_len = len(trajectory) - for i, fea in enumerate(trajectory): - # Sanity check. - if not fea.HasField('junction_feature') or \ - not len(fea.junction_feature.junction_exit) or \ - not len(fea.junction_feature.junction_mlp_feature): - # print("No junction_feature, junction_exit, or junction_mlp_feature, not labeling this frame.") - continue - curr_pos = np.array([fea.position.x, fea.position.y]) - # Only keep speed > 1 - # TODO(all) consider recovery - # if fea.speed <= 1: - # continue - heading = math.atan2(fea.raw_velocity.y, fea.raw_velocity.x) - # Construct dictionary of all exit with dict[exit_lane_id] = np.array(exit_position) - exit_dict = dict() - exit_pos_dict = dict() - for junction_exit in fea.junction_feature.junction_exit: - if junction_exit.HasField('exit_lane_id'): - exit_dict[junction_exit.exit_lane_id] = \ - BoundingRectangle(junction_exit.exit_position.x, - junction_exit.exit_position.y, - junction_exit.exit_heading, - 0.01, - junction_exit.exit_width) - exit_pos_dict[junction_exit.exit_lane_id] = np.array( - [junction_exit.exit_position.x, junction_exit.exit_position.y]) - # Searching for up to 100 frames (10 seconds) - for j in range(i, min(i + 100, traj_len)): - car_bounding = BoundingRectangle(trajectory[j].position.x, - trajectory[j].position.y, - math.atan2(trajectory[j].raw_velocity.y, - trajectory[j].raw_velocity.x), - trajectory[j].length, - trajectory[j].width) - for key, value in exit_dict.items(): - if car_bounding.overlap(value): - exit_pos = exit_pos_dict[key] - delta_pos = exit_pos - curr_pos - angle = math.atan2( - delta_pos[1], delta_pos[0]) - heading - d_idx = int((angle / (2.0 * np.pi)) * 12 % 12) - label = [0 for idx in range(12)] - label[d_idx] = 1 - fea.junction_feature.junction_mlp_label.extend(label) - break # actually break two level - else: - continue - break - return trajectory - - @abc.abstractmethod - def pack(self, trajectory): - """ abstractmethod""" - raise NotImplementedError diff --git a/modules/tools/prediction/data_pipelines/common/util.py b/modules/tools/prediction/data_pipelines/common/util.py deleted file mode 100644 index 64a247ca6a9..00000000000 --- a/modules/tools/prediction/data_pipelines/common/util.py +++ /dev/null @@ -1,42 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - - -def segment_overlap(a, b, x, y): - if b < x or a > y: - return False - - return True - - -def vector_projection_overlap(p0, p1, p2, p3): - v = p1.subtract(p0) - n_square = v.norm_square() - - v0 = p2.subtract(p0) - v1 = p3.subtract(p0) - - t0 = v0.dot(v) - t1 = v1.dot(v) - - if t0 > t1: - t = t0 - t0 = t1 - t1 = t - - return segment_overlap(t0, t1, 0.0, n_square) diff --git a/modules/tools/prediction/data_pipelines/common/vector2d.py b/modules/tools/prediction/data_pipelines/common/vector2d.py deleted file mode 100644 index 75ab3fb094e..00000000000 --- a/modules/tools/prediction/data_pipelines/common/vector2d.py +++ /dev/null @@ -1,42 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### -from math import sqrt - - -class Vector2: - def __init__(self, x, y): - self.x = x - self.y = y - - def add(self, v): - return Vector2(self.x + v.x, self.y + v.y) - - def subtract(self, v): - return Vector2(self.x - v.x, self.y - v.y) - - def dot(self, v): - return self.x * v.x + self.y * v.y - - def norm(self): - return sqrt(self.x * self.x + self.y * self.y) - - def norm_square(self): - return self.x * self.x + self.y * self.y - - def print_point(self): - print(str(self.x) + "\t" + str(self.y) + "\n") diff --git a/modules/tools/prediction/data_pipelines/cruiseMLP_train.py b/modules/tools/prediction/data_pipelines/cruiseMLP_train.py deleted file mode 100644 index 9ea5796cde0..00000000000 --- a/modules/tools/prediction/data_pipelines/cruiseMLP_train.py +++ /dev/null @@ -1,684 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -""" -@requirement: - pytorch 0.4.1 -""" - -import argparse -import logging -import os - -from sklearn.model_selection import train_test_split -from sklearn.utils import class_weight -from torch.autograd import Variable -from torch.utils.data import Dataset, DataLoader, sampler -import h5py -import numpy as np -import sklearn -import torch -import torch.nn as nn -import torch.nn.functional as F -import torch.optim as optim - -from modules.tools.prediction.data_pipelines.common.configure import parameters -from modules.tools.prediction.data_pipelines.cruise_models import FullyConn_NN, FCNN_CNN1D -from modules.tools.prediction.data_pipelines.proto.cruise_model_pb2 import TensorParameter, InputParameter,\ - Conv1dParameter, DenseParameter, ActivationParameter, MaxPool1dParameter,\ - AvgPool1dParameter, LaneFeatureConvParameter, ObsFeatureFCParameter,\ - ClassifyParameter, RegressParameter, CruiseModelParameter - - -# TODO(panjiacheng): the data-loader part needs to be modified. - -# Constants -dim_input = parameters['cruise_mlp']['dim_input'] -dim_hidden_1 = parameters['cruise_mlp']['dim_hidden_1'] -dim_hidden_2 = parameters['cruise_mlp']['dim_hidden_2'] -dim_output = parameters['cruise_mlp']['dim_output'] - -# Setup -cuda_is_available = torch.cuda.is_available() -logging.basicConfig(filename='training.log', level=logging.INFO) - - -def load_Conv1dParameter(model, key, stride=1): - - model_pb = Conv1dParameter() - - model_pb.shape.extend(list(model.state_dict()[key+'.weight'].shape)) - - model_pb.use_bias = True - - kernel_param = TensorParameter() - kernel_param.shape.extend(list(model.state_dict()[key+'.weight'].shape)) - kernel_param.data.extend( - list(model.state_dict()[key+'.weight'].numpy().reshape(-1))) - model_pb.kernel.CopyFrom(kernel_param) - - bias_param = TensorParameter() - bias_param.shape.extend(list(model.state_dict()[key+'.bias'].shape)) - bias_param.data.extend( - list(model.state_dict()[key+'.bias'].numpy().reshape(-1))) - model_pb.bias.CopyFrom(bias_param) - - model_pb.stride = stride - - return model_pb - - -def load_DenseParameter(model, key): - - model_pb = DenseParameter() - - model_pb.use_bias = True - - weights_param = TensorParameter() - weights_param.shape.extend( - list(model.state_dict()[key+'.weight'].numpy().T.shape)) - weights_param.data.extend( - list(model.state_dict()[key+'.weight'].numpy().T.reshape(-1))) - model_pb.weights.CopyFrom(weights_param) - - bias_param = TensorParameter() - bias_param.shape.extend( - list(model.state_dict()[key+'.bias'].numpy().shape)) - bias_param.data.extend(list(model.state_dict()[key+'.bias'].numpy())) - model_pb.bias.CopyFrom(bias_param) - - model_pb.units = model_pb.bias.shape[0] - - return model_pb - - -def save_FCNN_CNN1D(model, filename): - - model_pb = CruiseModelParameter() - - lane_feature_conv = LaneFeatureConvParameter() - lane_feature_conv.conv1d_0.CopyFrom( - load_Conv1dParameter(model, 'lane_feature_conv.0', stride=1)) - lane_feature_conv.activation_1.activation = 'relu' - lane_feature_conv.conv1d_2.CopyFrom( - load_Conv1dParameter(model, 'lane_feature_conv.2', stride=2)) - lane_feature_conv.activation_3.activation = 'relu' - lane_feature_conv.conv1d_4.CopyFrom( - load_Conv1dParameter(model, 'lane_feature_conv.4', stride=2)) - - lane_feature_maxpool = MaxPool1dParameter() - lane_feature_maxpool.kernel_size = 3 - lane_feature_maxpool.stride = 3 - - lane_feature_avgpool = AvgPool1dParameter() - lane_feature_avgpool.kernel_size = 3 - lane_feature_avgpool.stride = 3 - - obs_feature_fc = ObsFeatureFCParameter() - obs_feature_fc.linear_0.CopyFrom( - load_DenseParameter(model, 'obs_feature_fc.0')) - obs_feature_fc.activation_1.activation = 'sigmoid' - obs_feature_fc.linear_3.CopyFrom( - load_DenseParameter(model, 'obs_feature_fc.3')) - obs_feature_fc.activation_4.activation = 'sigmoid' - - classify = ClassifyParameter() - classify.linear_0.CopyFrom(load_DenseParameter(model, 'classify.0')) - classify.activation_1.activation = 'sigmoid' - classify.linear_3.CopyFrom(load_DenseParameter(model, 'classify.3')) - classify.activation_4.activation = 'sigmoid' - classify.linear_6.CopyFrom(load_DenseParameter(model, 'classify.6')) - classify.activation_7.activation = 'sigmoid' - classify.linear_9.CopyFrom(load_DenseParameter(model, 'classify.9')) - classify.activation_10.activation = 'sigmoid' - - regress = RegressParameter() - regress.linear_0.CopyFrom(load_DenseParameter(model, 'regress.0')) - regress.activation_1.activation = 'relu' - regress.linear_3.CopyFrom(load_DenseParameter(model, 'regress.3')) - regress.activation_4.activation = 'relu' - regress.linear_6.CopyFrom(load_DenseParameter(model, 'regress.6')) - regress.activation_7.activation = 'relu' - regress.linear_9.CopyFrom(load_DenseParameter(model, 'regress.9')) - regress.activation_10.activation = 'relu' - - model_pb.lane_feature_conv.CopyFrom(lane_feature_conv) - model_pb.lane_feature_maxpool.CopyFrom(lane_feature_maxpool) - model_pb.lane_feature_avgpool.CopyFrom(lane_feature_avgpool) - model_pb.obs_feature_fc.CopyFrom(obs_feature_fc) - model_pb.classify.CopyFrom(classify) - model_pb.regress.CopyFrom(regress) - - with open(filename, 'wb') as params_file: - params_file.write(model_pb.SerializeToString()) - - -''' -Custom defined loss function that lumps the loss of classification and -of regression together. -''' - - -def loss_fn(c_pred, r_pred, target, balance): - loss_C = nn.BCEWithLogitsLoss( - pos_weight=torch.FloatTensor([balance]).cuda()) # nn.BCELoss() - loss_R = nn.MSELoss() - - #loss = loss_C(c_pred, target[:,0].view(target.shape[0],1)) - loss = 4 * loss_C(c_pred, target[:, 0].view(target.shape[0], 1)) + \ - loss_R(((target[:, 2] > 0.0) * (target[:, 2] <= 3.0)).float().view(target.shape[0], 1) * r_pred + - ((target[:, 2] <= 0.0) + (target[:, 2] > 3.0)).float().view( - target.shape[0], 1) * target[:, 2].view(target.shape[0], 1), - target[:, 2].view(target.shape[0], 1)) - # loss_R((target[:,1] < 10.0).float().view(target.shape[0],1) * r_pred + \ - # (target[:,1] >= 10.0).float().view(target.shape[0],1) * target[:,1].view(target.shape[0],1), \ - # target[:,1].view(target.shape[0],1)) - return loss - - -# ======================================================================== -# Helper functions -''' -Get the full path of all files under the directory: 'dirName' -''' - - -def getListOfFiles(dirName): - listOfFiles = os.listdir(dirName) - allFiles = list() - - for entry in listOfFiles: - fullPath = os.path.join(dirName, entry) - if os.path.isdir(fullPath): - allFiles = allFiles + getListOfFiles(fullPath) - else: - allFiles.append(fullPath) - - return allFiles - - -''' -Print the distribution of data labels. -''' - - -def print_dist(label): - unique_labels = np.unique(label) - for l in unique_labels: - print('Label = {}: {}%'.format(l, np.sum(label == l)/len(label)*100)) - - -# ======================================================================== - - -# ======================================================================== -# Data Loading and preprocessing (Non Data-Loader case) - - -def load_data(filename): - ''' - Load the data from h5 file to the numpy format. - (Only for non data-loader case) - ''' - if not (os.path.exists(filename)): - logging.error("file: {}, does not exist".format(filename)) - os._exit(1) - if os.path.splitext(filename)[1] != '.h5': - logging.error("file: {} is not an hdf5 file".format(filename)) - os._exit(1) - - samples = dict() - h5_file = h5py.File(filename, 'r') - for key in h5_file.keys(): - samples[key] = h5_file[key][:] - - print("load file success") - return samples['data'] - - -def load_npy_data(dir): - ''' - Load all .npy files under a certain dir; - merge them together into one; - return. - ''' - - -def data_preprocessing(data): - ''' - Preprocess the data. - (Only for non data-loader case) - - separate input X and output y - - process output label from {-1,0,1,2,3,4} to {0,1} - - Take out only those meaningful features - - shuffle data - ''' - # Various input features separation - X_obs_old_features = data[:, 0:23] - X_surround_obs = data[:, -dim_output-8:-dim_output] - X_obs_now = data[:, 23:32] - X_obs_hist_5 = data[:, 23:68] - X_lane = data[:, 68:-dim_output-8] - - # mask out those that don't have any history - # mask5 = (data[:,53] != 100) - - X = np.concatenate((X_obs_old_features, X_obs_hist_5, X_lane), axis=1) - # X = X[mask5, :] - y = data[:, -dim_output:] - # y = y[mask5, :] - - # Binary classification - y[:, 0] = (y[:, 0] > 0).astype(float) - #y[:, 0] = np.logical_and((y[:, 0] > 0), (y[:, 1] < 1.0)) - - # Random shuffling - X_new, X_dummy, y_new, y_dummy = train_test_split( - X, y, test_size=0.0, random_state=233) - - return X_new, y_new # , X_dummy, y_dummy - -# ======================================================================== - - -# ======================================================================== -# Data Loading and preprocessing (Data-Loader case) - -''' -TODO: implement custom collate_fn to incorporate down-sampling function -for certain labels. -''' - - -def collate_wDownSample(batch): - return None - - -''' -If datasets are too large, use Dataloader to load from disk. -''' - - -class TrainValidDataset(Dataset): - ''' - Args: - - root_dir (string): Directory containing all folders with different - dates, each folder containing .cruise.h5 data files. - ''' - - def __init__(self, list_of_files): - self.list_of_files_ = list_of_files - self.data_size_until_this_file_ = [] - self.dataset_size = 0 - for file in self.list_of_files_: - with h5py.File(file, 'r') as h5_file: - data_size = h5_file[list(h5_file.keys())[0]].shape[0] - self.dataset_size += data_size - self.data_size_until_this_file_.append(self.dataset_size) - #print ('Total size of dataset: {}'.format(self.data_size_until_this_file_)) - - def __len__(self): - return self.dataset_size - - def __getitem__(self, index): - bin_idx = self.FindBin(index, 0, len( - self.data_size_until_this_file_)-1) - with h5py.File(self.list_of_files_[bin_idx], 'r') as h5_file: - idx_offset = self.data_size_until_this_file_[bin_idx] - \ - h5_file[list(h5_file.keys())[0]].shape[0] - data = h5_file[list(h5_file.keys())[0]][index-idx_offset] - label = data[-dim_output:] - label[0] = (label[0] > 0.0).astype(float) - return data[:-dim_output], label - - # Binary search to expedite the data-loading process. - def FindBin(self, index, start, end): - if (start == end): - return start - - mid = int((start+end)/2.0) - if (self.data_size_until_this_file_[mid] <= index): - return self.FindBin(index, mid+1, end) - else: - return self.FindBin(index, start, mid) -# ======================================================================== - - -# ======================================================================== -# Data training and validation - -''' -Train the data. (vanilla version without dataloader) -''' - - -def train_vanilla(train_X, train_y, model, optimizer, epoch, batch_size=2048, balance=1.0): - model.train() - - loss_history = [] - logging.info('Epoch: {}'.format(epoch+1)) - print('Epoch: {}.'.format(epoch+1)) - num_of_data = train_X.shape[0] - num_of_batch = int(num_of_data / batch_size) + 1 - pred_y = None - for i in range(num_of_batch): - optimizer.zero_grad() - X = train_X[i*batch_size: min(num_of_data, (i+1)*batch_size), ] - y = train_y[i*batch_size: min(num_of_data, (i+1)*batch_size), ] - c_pred, r_pred = model(X) - loss = loss_fn(c_pred, r_pred, y, balance) - loss_history.append(loss.data) - loss.backward() - optimizer.step() - - c_pred = c_pred.data.cpu().numpy() - c_pred = c_pred.reshape(c_pred.shape[0], 1) - pred_y = np.concatenate((pred_y, c_pred), axis=0) if pred_y is not None \ - else c_pred - - if (i > 0) and (i % 100 == 0): - logging.info('Step: {}, train_loss: {}'.format( - i, np.mean(loss_history[-100:]))) - print("Step: {}, training loss: {}".format( - i, np.mean(loss_history[-100:]))) - - pred_y = (pred_y > 0.0) - train_y = train_y.data.cpu().numpy() - training_accuracy = sklearn.metrics.accuracy_score( - train_y[:, 0], pred_y.reshape(-1)) - train_loss = np.mean(loss_history) - logging.info('Training loss: {}'.format(train_loss)) - logging.info('Training Accuracy: {}.'.format(training_accuracy)) - - print('Training Loss: {}. Training Accuracy: {}' - .format(train_loss, training_accuracy)) - - -''' -Validation (vanilla version without dataloader) -''' - - -def validate_vanilla(valid_X, valid_y, model, batch_size=2048, balance=1.0, pos_label=1.0): - model.eval() - - loss_history = [] - num_of_data = valid_X.shape[0] - num_of_batch = int(num_of_data / batch_size) + 1 - pred_y = None - for i in range(num_of_batch): - X = valid_X[i*batch_size: min(num_of_data, (i+1)*batch_size), ] - y = valid_y[i*batch_size: min(num_of_data, (i+1)*batch_size), ] - c_pred, r_pred = model(X) - valid_loss = loss_fn(c_pred, r_pred, y, balance) - loss_history.append(valid_loss.data) - - c_pred = c_pred.data.cpu().numpy() - c_pred = c_pred.reshape(c_pred.shape[0], 1) - - pred_y = np.concatenate((pred_y, c_pred), axis=0) if pred_y is not None \ - else c_pred - - valid_y = valid_y.data.cpu().numpy() - valid_auc = sklearn.metrics.roc_auc_score( - valid_y[:, 0], pred_y.reshape(-1)) - pred_y = (pred_y > 0.0) - valid_accuracy = sklearn.metrics.accuracy_score( - valid_y[:, 0], pred_y.reshape(-1)) - valid_precision = sklearn.metrics.precision_score( - valid_y[:, 0], pred_y.reshape(-1), pos_label=pos_label) - valid_recall = sklearn.metrics.recall_score( - valid_y[:, 0], pred_y.reshape(-1), pos_label=pos_label) - - logging.info('Validation loss: {}. Accuracy: {}.\ - Precision: {}. Recall: {}. AUC: {}.' - .format(np.mean(loss_history), valid_accuracy, valid_precision, - valid_recall, valid_auc)) - print('Validation loss: {}. Accuracy: {}.\ - Precision: {}. Recall: {}. AUC: {}.' - .format(np.mean(loss_history), valid_accuracy, valid_precision, - valid_recall, valid_auc)) - - return np.mean(loss_history) - - -''' -Train the data. (using dataloader) -''' - - -def train_dataloader(train_loader, model, optimizer, epoch, balance=1.0): - model.train() - - loss_history = [] - train_correct_class = 0 - total_size = 0 - logging.info('Epoch: {}'.format(epoch)) - for i, (inputs, targets) in enumerate(train_loader): - total_size += targets.shape[0] - optimizer.zero_grad() - if cuda_is_available: - X = (inputs).float().cuda() - y = (targets).float().cuda() - c_pred, r_pred = model(X) - loss = loss_fn(c_pred, r_pred, y, balance) - # loss.data[0].cpu().numpy() - loss_history.append(loss.data) - loss.backward() - optimizer.step() - - train_correct_class += \ - np.sum((c_pred.data.cpu().numpy() > 0.5).astype(float) == - y[:, 0].data.cpu().numpy().reshape(c_pred.data.cpu().numpy().shape[0], 1)) - - # if i > 100: - # break - if i % 100 == 0: - logging.info('Step: {}, train_loss: {}'.format( - i, np.mean(loss_history[-100:]))) - print("Step: {}, training loss: {}".format( - i, np.mean(loss_history[-100:]))) - - train_loss = np.mean(loss_history) - logging.info('Training loss: {}'.format(train_loss)) - print('Epoch: {}. Training Loss: {}'.format(epoch, train_loss)) - - -''' -Validation (using dataloader) -''' - - -def validate_dataloader(valid_loader, model, balance=1.0): - model.eval() - - loss_history = [] - valid_correct_class = 0.0 - total_size = 0 - - for i, (X, y) in enumerate(valid_loader): - total_size += y.shape[0] - if cuda_is_available: - X = X.float().cuda() - y = y.float().cuda() - c_pred, r_pred = model(X) - valid_loss = loss_fn(c_pred, r_pred, y, balance) - loss_history.append(valid_loss.data) - valid_correct_class += \ - np.sum((c_pred.data.cpu().numpy() > 0.5).astype(float) == - y[:, 0].data.cpu().numpy().reshape(c_pred.data.cpu().numpy().shape[0], 1)) - - valid_classification_accuracy = valid_correct_class / total_size - logging.info('Validation loss: {}. Validation classification accuracy: {}' - .format(np.mean(loss_history), valid_classification_accuracy)) - print('Validation loss: {}. Classification accuracy: {}.' - .format(np.mean(loss_history), valid_classification_accuracy)) - - return valid_loss -# ======================================================================== - - -# ======================================================================== -# Main function: - -if __name__ == "__main__": - - parser = argparse.ArgumentParser( - description='train neural network based on feature files and save parameters') - parser.add_argument('train_file', type=str, help='training data (h5)') - parser.add_argument('valid_file', type=str, help='validation data (h5)') - parser.add_argument('-n', '--network-structure', type=int, default=1, - help='Specify which network to use:\n \ - \t 0: Fully connected neural network.\n \ - \t 1: 1D-CNN for lane feature extraction.') - parser.add_argument('-d', '--data-loader', action='store_true', - help='Use the dataloader (when memory size is smaller than dataset size)') - parser.add_argument('-s', '--save-path', type=str, default='./', - help='Specify the directory to save trained models.') - parser.add_argument('-g', '--go', action='store_true', - help='It is training lane-follow (go) cases.') - parser.add_argument('-b', '--balance', type=float, default=1.0, - help='Specify the weight for positive predictions.') - # parser.add_argument('-g', '--gpu_num', type=int, default=0, \ - # help='Specify which GPU to use.') - - args = parser.parse_args() - - # os.environ['CUDA_DEVICE_ORDER'] = 'PCI_BUS_ID' #specifies the same order as nvidia-smi - #os.environ['CUDA_VISIBLE_DEVICES'] = str(args.gpu_num) - - if not args.data_loader: - - # Load from file and print out general information of the data. - train_file = args.train_file - valid_file = args.valid_file - train_data = load_data(train_file) - valid_data = load_data(valid_file) - print('Data loaded successfully.') - classes_train = np.asarray(train_data[:, -dim_output]) - print('Total number of training samples: {}'.format(len(classes_train))) - print('Training set distribution:') - print_dist(classes_train) - classes_valid = np.asarray(valid_data[:, -dim_output]) - print('Total number of validation samples: {}'.format(len(classes_valid))) - print('Validation set distribution:') - print_dist(classes_valid) - - # Data preprocessing - X_train, y_train = data_preprocessing(train_data) - X_valid, y_valid = data_preprocessing(valid_data) - - # Model declaration - model = None - if args.network_structure == 0: - model = FullyConn_NN() - elif args.network_structure == 1: - model = FCNN_CNN1D() - print("The model used is: ") - print(model) - learning_rate = 6.561e-4 - optimizer = optim.Adam(model.parameters(), lr=learning_rate) - scheduler = optim.lr_scheduler.ReduceLROnPlateau( - optimizer, factor=0.3, patience=2, min_lr=1e-8, verbose=1, mode='min') - - # CUDA set-up: - cuda_is_available = torch.cuda.is_available() - if (cuda_is_available): - print("Using CUDA to speed up training.") - model.cuda() - X_train = Variable(torch.FloatTensor(X_train).cuda()) - X_valid = Variable(torch.FloatTensor(X_valid).cuda()) - y_train = Variable(torch.FloatTensor(y_train).cuda()) - y_valid = Variable(torch.FloatTensor(y_valid).cuda()) - - # Model training: - pos_label = 1.0 - if args.go: - pos_label = 0.0 - best_valid_loss = float('+inf') - for epoch in range(50): - train_vanilla(X_train, y_train, model, optimizer, - epoch, balance=args.balance) - valid_loss = validate_vanilla( - X_valid, y_valid, model, balance=args.balance, pos_label=pos_label) - scheduler.step(valid_loss) - if valid_loss < best_valid_loss: - best_valid_loss = valid_loss - torch.save(model.state_dict(), args.save_path + 'cruise_model{}_epoch{}_valloss{:.6f}.pt' - .format(args.network_structure, epoch+1, valid_loss)) - - else: - train_dir = args.train_file - valid_dir = args.valid_file - - # Data preprocessing (training data balancing). - list_of_training_files = getListOfFiles(train_dir) - list_of_validation_files = getListOfFiles(valid_dir) - - classes_train = [] - for file in list_of_training_files: - with h5py.File(file, 'r') as h5_file: - data = h5_file[list(h5_file.keys())[0]][:, -2] - classes_train.append(data.tolist()) - # "Flattening" the list of lists - classes_train = [item for sublist in classes_train for item in sublist] - classes_train = np.asarray(classes_train) - print('Total number of training samples: {}'.format(len(classes_train))) - print('Training set distribution:') - print_dist(classes_train) - - classes_valid = [] - for file in list_of_validation_files: - with h5py.File(file, 'r') as h5_file: - data = h5_file[list(h5_file.keys())[0]][:, -2] - classes_valid.append(data.tolist()) - # "Flattening" the list of lists - classes_valid = [item for sublist in classes_valid for item in sublist] - classes_valid = np.asarray(classes_valid) - print('Total number of validation samples: {}'.format(len(classes_valid))) - print('Validation set distribution:') - print_dist(classes_valid) - - #class_weights = class_weight.compute_class_weight('balanced', np.unique(classes_train), classes_train) - #weights = [class_weights[int(i+1)] for i in classes_train] - #weights = torch.DoubleTensor(weights) - #train_sampler = sampler.WeightedRandomSampler(weights, int(len(weights)/1), replacement=True) - - model = FCNN_CNN1D() - learning_rate = 6.561e-4 - optimizer = optim.Adam(model.parameters(), lr=learning_rate) - scheduler = optim.lr_scheduler.ReduceLROnPlateau( - optimizer, factor=0.3, patience=2, min_lr=1e-8, verbose=1, mode='min') - if (cuda_is_available): - print('Using CUDA to speed up training.') - model.cuda() - - train_dataset = TrainValidDataset(list_of_training_files) - valid_dataset = TrainValidDataset(list_of_validation_files) - - train_loader = DataLoader(train_dataset, batch_size=1024, num_workers=8, - pin_memory=True, shuffle=True) # sampler=train_sampler) - valid_loader = DataLoader( - valid_dataset, batch_size=1024, num_workers=8, pin_memory=True) - - for epoch in range(100): - train_dataloader(train_loader, model, optimizer, epoch) - valid_loss = validate_dataloader(valid_loader, model) - scheduler.step(valid_loss) - -# ======================================================================== diff --git a/modules/tools/prediction/data_pipelines/cruise_h5_preprocessing.py b/modules/tools/prediction/data_pipelines/cruise_h5_preprocessing.py deleted file mode 100644 index 49b06ac718b..00000000000 --- a/modules/tools/prediction/data_pipelines/cruise_h5_preprocessing.py +++ /dev/null @@ -1,211 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -''' -This .py file includes functions for data preprocessing: - - splitting data into two categories: go and cut-in for separate training. - - balancing the datasets -''' - -import argparse -import datetime -import os - -import h5py -import numpy as np - - -def getListOfFiles(dirName): - ''' - Given a directory (dirName), return a list containing the full-path - of all files inside that directory (including all hierarchy). - ''' - listOfFiles = os.listdir(dirName) - allFiles = list() - - for entry in listOfFiles: - fullPath = os.path.join(dirName, entry) - if os.path.isdir(fullPath): - allFiles = allFiles + getListOfFiles(fullPath) - else: - allFiles.append(fullPath) - - return allFiles - - -def load_hdf5(filename): - """ - load training samples from *.hdf5 file - """ - if not(os.path.exists(filename)): - print("file:", filename, "does not exist") - os._exit(1) - if os.path.splitext(filename)[1] != '.h5': - print("file:", filename, "is not an hdf5 file") - os._exit(1) - - h5_file = h5py.File(filename, 'r') - values = h5_file[list(h5_file.keys())[0]] - #values = h5_file.values()[0] - print("load data size:", values.shape[0]) - return values - - -def data_splitting(feature): - ''' - Split data into two categories: go and cut-in. - ''' - - # Don't consider those anomaly data - idx_normal = (feature[:, -3] != -10) - go_idx = (feature[:, -3] % 2 == 0) - cutin_idx = (feature[:, -3] % 2 == 1) - - go_idx = np.logical_and(go_idx, idx_normal) - cutin_idx = np.logical_and(cutin_idx, idx_normal) - - feature = np.asarray(feature) - - return feature[go_idx], feature[cutin_idx] - - -def down_sample(feature, label, drop_rate): - ''' - feature: the input data - label and drop_rate: one-to-one mapping of the drop-rate for each - specific label - ''' - fea_label = feature[:, -2] - selected_idx = np.zeros(fea_label.shape[0], dtype=bool) - mask_random = np.random.random(fea_label.shape[0]) - - for i in range(len(label)): - l = label[i] - dr = drop_rate[i] - - idx_of_curr_label = (fea_label == l) - selected_idx_of_curr_label = np.logical_and(idx_of_curr_label, - mask_random > dr) - selected_idx = np.logical_or(selected_idx, selected_idx_of_curr_label) - - data_downsampled = feature[selected_idx, :] - return data_downsampled - - -if __name__ == '__main__': - parser = argparse.ArgumentParser(description='Data preprocessing.') - parser.add_argument('directory', type=str, - help='directory contains feature files in .h5') - parser.add_argument('-m', '--merge_files', action='store_true', - help='Merge output files into one.') - parser.add_argument('-s', '--split_category', action='store_true', - help='Split the output into Go and Cutin.') - - args = parser.parse_args() - - path = args.directory - print("Loading h5 from directory: {}".format(path)) - - if not args.merge_files: - - if os.path.isdir(path): - - h5_files = getListOfFiles(path) - print("Total number of files:", len(h5_files)) - - # For each file in the total list of files: - for i, file in enumerate(h5_files): - print("Process File", i, ":", file) - feature = load_hdf5(file) - if np.any(np.isinf(feature)): - print("inf data found") - - if args.split_category: - # Split data into two categories: - fea_go, fea_cutin = data_splitting(feature) - - # Balance data by down-sampling oversized bins: - #fea_go = down_sample(fea_go, [0, 1, 4], [0.0, 0.95, 0.83]) - #fea_cutin = down_sample(fea_cutin, [-1, 2, 3], [0.985 ,0.0, 0.0]) - - go_path = path + 'go/' + \ - file.split('/')[-2] + '-' + file.split('/')[-1] - h5_file = h5py.File(go_path, 'w') - h5_file.create_dataset('data', data=fea_go) - h5_file.close() - - cutin_path = path + 'cutin/' + \ - file.split('/')[-2] + '-' + file.split('/')[-1] - h5_file = h5py.File(cutin_path, 'w') - h5_file.create_dataset('data', data=fea_cutin) - h5_file.close() - - else: - print(None) - # TODO: implement those non-splitting category - else: - print("Fail to find", path) - os._exit(-1) - - else: - - if os.path.isdir(path): - features_go = None - features_cutin = None - features = None - labels = None - - h5_files = getListOfFiles(path) - print("Total number of files:", len(h5_files)) - - # For each file in the total list of files: - for i, file in enumerate(h5_files): - print("Process File", i, ":", file) - feature = load_hdf5(file) - if np.any(np.isinf(feature)): - print("inf data found") - - if args.split_category: - # Split data into two categories: - fea_go, fea_cutin = data_splitting(feature) - - # Balance data by down-sampling oversized bins: - #fea_go = down_sample(fea_go, [0, 1, 4], [0.0, 0.95, 0.83]) - #fea_cutin = down_sample(fea_cutin, [-1, 2, 3], [0.985 ,0.0, 0.0]) - - features_go = np.concatenate((features_go, fea_go), axis=0) if features_go is not None \ - else fea_go - features_cutin = np.concatenate((features_cutin, fea_cutin), axis=0) if features_cutin is not None \ - else fea_cutin - else: - print("Fail to find", path) - os._exit(-1) - - if args.split_category: - date = datetime.datetime.now().strftime('%Y-%m-%d') - sample_file = path + 'merged_go' + date + '.h5' - print("Save samples file to:", sample_file) - h5_file = h5py.File(sample_file, 'w') - h5_file.create_dataset('data', data=features_go) - h5_file.close() - - sample_file = path + 'merged_cutin' + date + '.h5' - print("Save samples file to:", sample_file) - h5_file = h5py.File(sample_file, 'w') - h5_file.create_dataset('data', data=features_cutin) - h5_file.close() diff --git a/modules/tools/prediction/data_pipelines/cruise_models.py b/modules/tools/prediction/data_pipelines/cruise_models.py deleted file mode 100644 index 6723946d3b0..00000000000 --- a/modules/tools/prediction/data_pipelines/cruise_models.py +++ /dev/null @@ -1,184 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import argparse -import logging -import os - -from sklearn.model_selection import train_test_split -from sklearn.utils import class_weight -from torch.autograd import Variable -from torch.utils.data import Dataset, DataLoader, sampler -import h5py -import numpy as np -import sklearn -import torch -import torch.nn as nn -import torch.nn.functional as F -import torch.optim as optim - -from modules.tools.prediction.data_pipelines.common.configure import parameters -from proto.cruise_model_pb2 import TensorParameter, InputParameter,\ - Conv1dParameter, DenseParameter, ActivationParameter, MaxPool1dParameter,\ - AvgPool1dParameter, LaneFeatureConvParameter, ObsFeatureFCParameter,\ - ClassifyParameter, RegressParameter, CruiseModelParameter - - -""" -@requirement: - pytorch 0.4.1 -""" - -''' -This file includes all model definitions and related loss functions. -''' - - -''' -Model details: - - Fully-connected layers for classification and regression, respectively. - - It will compute a classification score indicating the probability - of the obstacle choosing the given lane. - - It will also compute a time indicating how soon the obstacle will reach - the center of the given lane. -''' - - -class FullyConn_NN(torch.nn.Module): - def __init__(self): - super(FullyConn_NN, self).__init__() - self.classify = torch.nn.Sequential( - nn.Linear(174, 88), - nn.Sigmoid(), - nn.Dropout(0.3), - - nn.Linear(88, 55), - nn.Sigmoid(), - nn.Dropout(0.2), - - nn.Linear(55, 23), - nn.Sigmoid(), - nn.Dropout(0.3), - - nn.Linear(23, 10), - nn.Sigmoid(), - nn.Dropout(0.0), - - nn.Linear(10, 1), - nn.Sigmoid() - ) - self.regress = torch.nn.Sequential( - nn.Linear(174, 88), - nn.ReLU(), - nn.Dropout(0.1), - - nn.Linear(88, 23), - nn.ReLU(), - nn.Dropout(0.1), - - nn.Linear(23, 1), - nn.ReLU() - ) - - def forward(self, x): - out_c = self.classify(x) - out_r = self.regress(x) - return out_c, out_r - - -class FCNN_CNN1D(torch.nn.Module): - def __init__(self): - super(FCNN_CNN1D, self).__init__() - self.lane_feature_conv = torch.nn.Sequential( - nn.Conv1d(4, 10, 3, stride=1),\ - # nn.BatchNorm1d(10),\ - nn.ReLU(),\ - #nn.Conv1d(10, 16, 3, stride=2),\ - # nn.BatchNorm1d(16),\ - # nn.ReLU(),\ - nn.Conv1d(10, 25, 3, stride=2),\ - # nn.BatchNorm1d(25) - ) - self.lane_feature_maxpool = nn.MaxPool1d(4) - self.lane_feature_avgpool = nn.AvgPool1d(4) - self.lane_feature_dropout = nn.Dropout(0.0) - - self.obs_feature_fc = torch.nn.Sequential( - nn.Linear(68, 40), - nn.Sigmoid(), - nn.Dropout(0.0), - nn.Linear(40, 24), - nn.Sigmoid(), - nn.Dropout(0.0), - ) - - self.classify = torch.nn.Sequential( - nn.Linear(124, 66), - nn.Sigmoid(), - nn.Dropout(0.3), - - nn.Linear(66, 48), - nn.Sigmoid(), - nn.Dropout(0.1), - - nn.Linear(48, 11), - nn.Sigmoid(), - nn.Dropout(0.1), - - nn.Linear(11, 1),\ - # nn.Sigmoid() - ) - self.regress = torch.nn.Sequential( - nn.Linear(125, 77), - nn.ReLU(), - nn.Dropout(0.2), - - nn.Linear(77, 46), - nn.ReLU(), - nn.Dropout(0.2), - - nn.Linear(46, 12), - nn.ReLU(), - nn.Dropout(0.1), - - nn.Linear(12, 1), - nn.ReLU() - ) - - def forward(self, x): - lane_fea = x[:, -80:] - lane_fea = lane_fea.view(lane_fea.size(0), 4, 20) - - obs_fea = x[:, :-80] - - lane_fea = self.lane_feature_conv(lane_fea) - - lane_fea_max = self.lane_feature_maxpool(lane_fea) - lane_fea_avg = self.lane_feature_avgpool(lane_fea) - - lane_fea = torch.cat([lane_fea_max.view(lane_fea_max.size(0), -1), - lane_fea_avg.view(lane_fea_avg.size(0), -1)], 1) - lane_fea = self.lane_feature_dropout(lane_fea) - - obs_fea = self.obs_feature_fc(obs_fea) - - tot_fea = torch.cat([lane_fea, obs_fea], 1) - out_c = self.classify(tot_fea) - out_r = self.regress(torch.cat([tot_fea, out_c], 1)) - - return out_c, out_r diff --git a/modules/tools/prediction/data_pipelines/data_preprocessing/BUILD b/modules/tools/prediction/data_pipelines/data_preprocessing/BUILD deleted file mode 100644 index 1ecda2727c4..00000000000 --- a/modules/tools/prediction/data_pipelines/data_preprocessing/BUILD +++ /dev/null @@ -1,67 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") - -package(default_visibility = ["//visibility:public"]) - -py_library( - name = "combine_features_and_labels", - srcs = ["combine_features_and_labels.py"], - deps = [ - ":features_labels_utils", - ], -) - -py_library( - name = "combine_features_and_labels_for_junction", - srcs = ["combine_features_and_labels_for_junction.py"], - deps = [ - ":features_labels_utils", - ], -) - -py_library( - name = "features_labels_utils", - srcs = ["features_labels_utils.py"], - deps = [ - "//modules/prediction/proto:offline_features_py_pb2", - ], -) - -py_binary( - name = "generate_cruise_labels", - srcs = ["generate_cruise_labels.py"], - deps = [ - "//modules/tools/prediction/data_pipelines/common:online_to_offline", - ], -) - -py_binary( - name = "generate_future_trajectory", - srcs = ["generate_future_trajectory.py"], - deps = [ - "//modules/tools/prediction/data_pipelines/common:online_to_offline", - ], -) - -py_binary( - name = "generate_junction_labels", - srcs = ["generate_junction_labels.py"], - deps = [ - "//modules/tools/prediction/data_pipelines/common:online_to_offline", - ], -) - -py_binary( - name = "generate_labels", - srcs = ["generate_labels.py"], - deps = [ - "//modules/tools/prediction/data_pipelines/common:online_to_offline", - ], -) - -py_binary( - name = "merge_label_dicts", - srcs = ["merge_label_dicts.py"], - deps = [ - ":features_labels_utils", - ], -) diff --git a/modules/tools/prediction/data_pipelines/data_preprocessing/combine_features_and_labels.py b/modules/tools/prediction/data_pipelines/data_preprocessing/combine_features_and_labels.py deleted file mode 100644 index 70ec89a42b5..00000000000 --- a/modules/tools/prediction/data_pipelines/data_preprocessing/combine_features_and_labels.py +++ /dev/null @@ -1,43 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import argparse -import os -import re - -from modules.tools.prediction.data_pipelines.data_preprocessing.features_labels_utils import CombineFeaturesAndLabels, MergeCombinedFeaturesAndLabels - - -if __name__ == "__main__": - parser = argparse.ArgumentParser(description='Merge all label_dicts in each' - 'terminal folder.') - parser.add_argument('features_dirpath', type=str, - help='Path of terminal folder for data_for_learn.') - parser.add_argument('labels_dirpath', type=str, - help='Path of terminal folder for labels') - args = parser.parse_args() - - list_of_files = os.listdir(args.features_dirpath) - for file in list_of_files: - full_file_path = os.path.join(args.features_dirpath, file) - if file.split('.')[-1] == 'bin' and \ - file.split('.')[0] == 'datalearn': - label_path = args.labels_dirpath - CombineFeaturesAndLabels(full_file_path, label_path + '/labels.npy') - - MergeCombinedFeaturesAndLabels(args.features_dirpath) diff --git a/modules/tools/prediction/data_pipelines/data_preprocessing/combine_features_and_labels_for_junction.py b/modules/tools/prediction/data_pipelines/data_preprocessing/combine_features_and_labels_for_junction.py deleted file mode 100644 index ffdb039b8e9..00000000000 --- a/modules/tools/prediction/data_pipelines/data_preprocessing/combine_features_and_labels_for_junction.py +++ /dev/null @@ -1,42 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import argparse -import os -import re - -from modules.tools.prediction.data_pipelines.data_preprocessing.features_labels_utils import CombineFeaturesAndLabels - - -if __name__ == "__main__": - parser = argparse.ArgumentParser( - description='Merge all label_dicts in each terminal folder.') - parser.add_argument('features_dirpath', type=str, - help='Path of terminal folder for data_for_learn.') - parser.add_argument('labels_dirpath', type=str, - help='Path of terminal folder for labels') - args = parser.parse_args() - - list_of_files = os.listdir(args.features_dirpath) - for file in list_of_files: - full_file_path = os.path.join(args.features_dirpath, file) - if file.split('.')[-1] == 'bin' and \ - file.split('.')[0] == 'datalearn': - label_path = args.labels_dirpath - CombineFeaturesAndLabels(full_file_path, label_path + - '/junction_label.npy', 'junction_label') diff --git a/modules/tools/prediction/data_pipelines/data_preprocessing/features_labels_utils.py b/modules/tools/prediction/data_pipelines/data_preprocessing/features_labels_utils.py deleted file mode 100644 index 5504dbff2c0..00000000000 --- a/modules/tools/prediction/data_pipelines/data_preprocessing/features_labels_utils.py +++ /dev/null @@ -1,168 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - - -import h5py -import numpy as np -import os - -from modules.prediction.proto import offline_features_pb2 - - -junction_label_label_dim = 12 -future_status_label_dim = 30 - -''' -Read a single dataforlearn.bin file and output a list of DataForLearning -that is contained in that file. -''' - - -def LoadDataForLearning(filepath): - list_of_data_for_learning = \ - offline_features_pb2.ListDataForLearning() - with open(filepath, 'rb') as file_in: - list_of_data_for_learning.ParseFromString(file_in.read()) - return list_of_data_for_learning.data_for_learning - - -''' -Read a single .npy dictionary file and get its content. -''' - - -def LoadLabels(filepath): - mydict = np.load(filepath).item() - return mydict - - -''' -Merge two dictionary into a single one and return. -''' - - -def MergeTwoDicts(dict1, dict2): - newdict = dict1.copy() - newdict.update(dict2) - return newdict - - -''' -Merge all dictionaries directly under a directory -''' - - -def MergeDicts(dirpath, dict_name='future_status'): - list_of_files = os.listdir(dirpath) - dict_merged = None - - for file in list_of_files: - full_path = os.path.join(dirpath, file) - if file.split('.')[-1] == 'npy' and file.split('.')[-2] == dict_name: - dict_curr = LoadLabels(full_path) - if dict_merged is None: - dict_merged = dict_curr.copy() - else: - dict_merged.update(dict_curr) - - np.save(dirpath + '/' + dict_name + '.npy', dict_merged) - return dict_merged - - -''' -Go through every entry of data_for_learn proto and get the corresponding labels. -Save the output file into h5 format (array of lists with each list being a data -point for training/validating). -''' - - -def CombineFeaturesAndLabels(feature_path, label_path, dict_name='future_status'): - list_of_data_for_learning = LoadDataForLearning(feature_path) - dict_labels = LoadLabels(label_path) - - output_np_array = [] - for data_for_learning in list_of_data_for_learning: - # features_for_learning: list of doubles - features_for_learning = list(data_for_learning.features_for_learning) - key = "{}@{:.3f}".format(data_for_learning.id, data_for_learning.timestamp) - - # Sanity checks to see if this data-point is valid or not. - if key not in dict_labels: - print('Cannot find a feature-to-label mapping.') - continue - - labels = None - list_curr = None - if dict_name == 'junction_label': - if len(dict_labels[key]) != junction_label_label_dim: - continue - labels = dict_labels[key] - list_curr = features_for_learning + labels - elif dict_name == 'future_status': - if len(dict_labels[key]) < future_status_label_dim: - continue - labels = dict_labels[key][:30] - list_curr = [len(features_for_learning)] + \ - features_for_learning + labels - - output_np_array.append(list_curr) - - output_np_array = np.array(output_np_array) - - np.save(feature_path + '.features+' + dict_name + '.npy', output_np_array) - - -''' -Merge all files of features+labels into a single one -''' - - -def MergeCombinedFeaturesAndLabels(dirpath): - list_of_files = os.listdir(dirpath) - - features_labels_merged = [] - for file in list_of_files: - full_path = os.path.join(dirpath, file) - if file.split('.')[-1] == 'npy' and \ - file.split('.')[-2] == 'labels' and \ - file.split('.')[0] == 'datalearn': - features_labels_curr = np.load(full_path).tolist() - features_labels_merged += features_labels_curr - - np.save(dirpath + '/training_data.npy', np.array(features_labels_merged)) - - -''' -It takes terminal folder as input, then -1. Merge all label dicts. -2. Go through every data_for_learn proto, and find the corresponding label -3. Merge all features+labels files into a single one: data.npy -''' - - -def PrepareDataForTraining(dirpath): - MergeDicts(dirpath) - - list_of_files = os.listdir(dirpath) - for file in list_of_files: - full_path = os.path.join(dirpath, file) - if file.split('.')[-1] == 'bin' and \ - file.split('.')[0] == 'datalearn': - CombineFeaturesAndLabels(full_path, dirpath + 'labels.npy') - - MergeCombinedFeaturesAndLabels(dirpath) diff --git a/modules/tools/prediction/data_pipelines/data_preprocessing/generate_cruise_labels.py b/modules/tools/prediction/data_pipelines/data_preprocessing/generate_cruise_labels.py deleted file mode 100644 index cd186db6923..00000000000 --- a/modules/tools/prediction/data_pipelines/data_preprocessing/generate_cruise_labels.py +++ /dev/null @@ -1,41 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import argparse -import glob -import logging -import os -import sys - -from modules.tools.prediction.data_pipelines.common.online_to_offline import LabelGenerator - - -if __name__ == "__main__": - - parser = argparse.ArgumentParser(description='Generate labels') - parser.add_argument('input', type=str, help='input file') - args = parser.parse_args() - - label_gen = LabelGenerator() - - print("Create Label {}".format(args.input)) - if os.path.isfile(args.input): - label_gen.LoadFeaturePBAndSaveLabelFiles(args.input) - label_gen.LabelSingleLane() - else: - print("{} is not a valid file".format(args.input)) diff --git a/modules/tools/prediction/data_pipelines/data_preprocessing/generate_future_trajectory.py b/modules/tools/prediction/data_pipelines/data_preprocessing/generate_future_trajectory.py deleted file mode 100644 index 1783ebfc6ee..00000000000 --- a/modules/tools/prediction/data_pipelines/data_preprocessing/generate_future_trajectory.py +++ /dev/null @@ -1,41 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import argparse -import glob -import logging -import os -import sys - -from modules.tools.prediction.data_pipelines.common.online_to_offline import LabelGenerator - - -if __name__ == "__main__": - - parser = argparse.ArgumentParser(description='Generate labels') - parser.add_argument('input', type=str, help='input file') - args = parser.parse_args() - - label_gen = LabelGenerator() - - print("Create Label {}".format(args.input)) - if os.path.isfile(args.input): - label_gen.LoadFeaturePBAndSaveLabelFiles(args.input) - label_gen.LabelTrajectory() - else: - print("{} is not a valid file".format(args.input)) diff --git a/modules/tools/prediction/data_pipelines/data_preprocessing/generate_junction_labels.py b/modules/tools/prediction/data_pipelines/data_preprocessing/generate_junction_labels.py deleted file mode 100644 index dcb2ec45097..00000000000 --- a/modules/tools/prediction/data_pipelines/data_preprocessing/generate_junction_labels.py +++ /dev/null @@ -1,41 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import argparse -import glob -import logging -import os -import sys - -from modules.tools.prediction.data_pipelines.common.online_to_offline import LabelGenerator - - -if __name__ == "__main__": - - parser = argparse.ArgumentParser(description='Generate labels') - parser.add_argument('input', type=str, help='input file') - args = parser.parse_args() - - label_gen = LabelGenerator() - - print("Create Label {}".format(args.input)) - if os.path.isfile(args.input): - label_gen.LoadFeaturePBAndSaveLabelFiles(args.input) - label_gen.LabelJunctionExit() - else: - print("{} is not a valid file".format(args.input)) diff --git a/modules/tools/prediction/data_pipelines/data_preprocessing/generate_labels.py b/modules/tools/prediction/data_pipelines/data_preprocessing/generate_labels.py deleted file mode 100644 index b7adf9675bf..00000000000 --- a/modules/tools/prediction/data_pipelines/data_preprocessing/generate_labels.py +++ /dev/null @@ -1,41 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import argparse -import glob -import logging -import os -import sys - -from modules.tools.prediction.data_pipelines.common.online_to_offline import LabelGenerator - - -if __name__ == "__main__": - - parser = argparse.ArgumentParser(description='Generate labels') - parser.add_argument('input', type=str, help='input file') - args = parser.parse_args() - - label_gen = LabelGenerator() - - print("Create Label {}".format(args.input)) - if os.path.isfile(args.input): - label_gen.LoadFeaturePBAndSaveLabelFiles(args.input) - label_gen.Label() - else: - print("{} is not a valid file".format(args.input)) diff --git a/modules/tools/prediction/data_pipelines/data_preprocessing/merge_label_dicts.py b/modules/tools/prediction/data_pipelines/data_preprocessing/merge_label_dicts.py deleted file mode 100644 index 540cb96a09b..00000000000 --- a/modules/tools/prediction/data_pipelines/data_preprocessing/merge_label_dicts.py +++ /dev/null @@ -1,32 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import argparse - -import modules.tools.prediction.data_pipelines.data_preprocessing.features_labels_utils as features_labels_utils - - -if __name__ == "__main__": - parser = argparse.ArgumentParser(description='Merge all label_dicts in each' - 'terminal folder.') - parser.add_argument('dirpath', type=str, help='Path of terminal folder.') - args = parser.parse_args() - - features_labels_utils.MergeDicts(args.dirpath, dict_name='future_status') - features_labels_utils.MergeDicts(args.dirpath, dict_name='junction_label') - features_labels_utils.MergeDicts(args.dirpath, dict_name='cruise_label') diff --git a/modules/tools/prediction/data_pipelines/junctionMLP_train.py b/modules/tools/prediction/data_pipelines/junctionMLP_train.py deleted file mode 100644 index 76d43ec24a6..00000000000 --- a/modules/tools/prediction/data_pipelines/junctionMLP_train.py +++ /dev/null @@ -1,119 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### -""" -@requirement: - tensorflow 1.11 -""" - -import os -import h5py -import logging -import argparse -import numpy as np -import tensorflow as tf -from modules.tools.prediction.data_pipelines.proto import fnn_model_pb2 -from fnn_model_pb2 import FnnModel, Layer -from sklearn.model_selection import train_test_split - -dim_input = 7 + 72 -dim_output = 12 - - -def load_data(filename): - """ - Load the data from h5 file to the format of numpy - """ - if not (os.path.exists(filename)): - logging.error("file: {}, does not exist".format(filename)) - os._exit(1) - if os.path.splitext(filename)[1] != '.h5': - logging.error("file: {} is not an hdf5 file".format(filename)) - os._exit(1) - samples = dict() - h5_file = h5py.File(filename, 'r') - for key in h5_file.keys(): - samples[key] = h5_file[key][:] - print("load file success") - return samples['data'] - - -def data_preprocessing(data): - X = data[:, :dim_input] - Y = data[:, -dim_output:] - return X, Y - - -def save_model(model, filename): - """ - Save the trained model parameters into protobuf binary format file - """ - net_params = FnnModel() - net_params.num_layer = 0 - for layer in model.layers: - net_params.num_layer += 1 - net_layer = net_params.layer.add() - config = layer.get_config() - net_layer.layer_input_dim = dim_input - net_layer.layer_output_dim = dim_output - if config['activation'] == 'relu': - net_layer.layer_activation_func = fnn_model_pb2.Layer.RELU - elif config['activation'] == 'tanh': - net_layer.layer_activation_func = fnn_model_pb2.Layer.TANH - elif config['activation'] == 'sigmoid': - net_layer.layer_activation_func = fnn_model_pb2.Layer.SIGMOID - elif config['activation'] == 'softmax': - net_layer.layer_activation_func = fnn_model_pb2.Layer.SOFTMAX - - weights, bias = layer.get_weights() - net_layer.layer_bias.columns.extend(bias.reshape(-1).tolist()) - for col in weights.tolist(): - row = net_layer.layer_input_weight.rows.add() - row.columns.extend(col) - net_params.dim_input = dim_input - net_params.dim_output = dim_output - with open(filename, 'wb') as params_file: - params_file.write(net_params.SerializeToString()) - - -if __name__ == "__main__": - - parser = argparse.ArgumentParser( - description='train neural network based on feature files and save parameters') - parser.add_argument('filename', type=str, help='h5 file of data.') - args = parser.parse_args() - file = args.filename - # load_data - data = load_data(file) - print("Data load success, with data shape: " + str(data.shape)) - train_data, test_data = train_test_split(data, test_size=0.2) - X_train, Y_train = data_preprocessing(train_data) - X_test, Y_test = data_preprocessing(test_data) - model = tf.keras.models.Sequential([ - tf.keras.layers.Dense(30, activation=tf.nn.relu), - tf.keras.layers.Dense(20, activation=tf.nn.relu), - tf.keras.layers.Dense(12, activation=tf.nn.softmax)]) - model.compile(optimizer='adam', - loss='categorical_crossentropy', - # loss='MSE', - metrics=['accuracy']) - model.fit(X_train, Y_train, epochs=5) - model_path = os.path.join(os.getcwd(), "junction_mlp_vehicle_model.bin") - save_model(model, model_path) - print("Model saved to: " + model_path) - score = model.evaluate(X_test, Y_test) - print("Testing accuracy is: " + str(score)) diff --git a/modules/tools/prediction/data_pipelines/merge_h5.py b/modules/tools/prediction/data_pipelines/merge_h5.py deleted file mode 100644 index 745be0c6520..00000000000 --- a/modules/tools/prediction/data_pipelines/merge_h5.py +++ /dev/null @@ -1,141 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import argparse -import datetime -import os - -import numpy as np -import h5py - - -def getListOfFiles(dirName): - listOfFiles = os.listdir(dirName) - allFiles = list() - - for entry in listOfFiles: - fullPath = os.path.join(dirName, entry) - if os.path.isdir(fullPath): - allFiles = allFiles + getListOfFiles(fullPath) - else: - allFiles.append(fullPath) - - return allFiles - - -def load_hdf5(filename): - """ - load training samples from *.hdf5 file - """ - if not(os.path.exists(filename)): - print("file:", filename, "does not exist") - os._exit(1) - if os.path.splitext(filename)[1] != '.h5': - print("file:", filename, "is not an hdf5 file") - os._exit(1) - - h5_file = h5py.File(filename, 'r') - values = list(h5_file.values())[0] - print("load data size:", values.shape[0]) - return values - - -if __name__ == '__main__': - parser = argparse.ArgumentParser(description='generate training samples\ - from a specified directory') - parser.add_argument('directory', type=str, - help='directory contains feature files in .h5') - parser.add_argument('-n', '--npy', action='store_true', - help='if is .npy rather than .h5, use this.') - args = parser.parse_args() - path = args.directory - - if not args.npy: - print("load h5 from directory: {}".format(path)) - if os.path.isdir(path): - features = None - labels = None - - h5_files = getListOfFiles(path) - print("Total number of files:", len(h5_files)) - for i, h5_file in enumerate(h5_files): - print("Process File", i, ":", h5_file) - feature = load_hdf5(h5_file) - if np.any(np.isinf(feature)): - print("inf data found") - features = np.concatenate((features, feature), axis=0) if features is not None \ - else feature - else: - print("Fail to find", path) - os._exit(-1) - - date = datetime.datetime.now().strftime('%Y-%m-%d') - sample_file = path + '/merged' + date + '.h5' - print("Save samples file to:", sample_file) - h5_file = h5py.File(sample_file, 'w') - h5_file.create_dataset('data', data=features) - h5_file.close() - else: - print("load npy from directory: {}".format(path)) - if os.path.isdir(path): - features_go = None - features_cutin = None - npy_files = getListOfFiles(path) - print("Total number of files:", len(npy_files)) - for i, npy_file in enumerate(npy_files): - print("Process File", i, ":", npy_file) - temp_features = np.load(npy_file) - feature_go = np.zeros((temp_features.shape[0], 157)) - feature_cutin = np.zeros((temp_features.shape[0], 157)) - count_go = 0 - count_cutin = 0 - for j in range(temp_features.shape[0]): - fea = np.asarray(temp_features[j]) - if fea.shape[0] != 157: - continue - if fea[-1] < -1 or fea[-1] > 4: - continue - fea = fea.reshape((1, 157)) - if fea[0, -1] % 2 == 0: - feature_go[count_go] = fea - count_go += 1 - else: - feature_cutin[count_cutin] = fea - count_cutin += 1 - - feature_go = feature_go[:count_go] - feature_cutin = feature_cutin[:count_cutin] - features_go = np.concatenate((features_go, feature_go), axis=0) if features_go is not None \ - else feature_go - features_cutin = np.concatenate((features_cutin, feature_cutin), axis=0) if features_cutin is not None \ - else feature_cutin - else: - print("Fail to find", path) - os._exit(-1) - - print(features_go.shape) - print(features_cutin.shape) - date = datetime.datetime.now().strftime('%Y-%m-%d') - sample_file_go = path + '/merged_go_' + date + '.h5' - sample_file_cutin = path + '/merged_cutin_' + date + '.h5' - h5_file_go = h5py.File(sample_file_go, 'w') - h5_file_go.create_dataset('data', data=features_go) - h5_file_go.close() - h5_file_cutin = h5py.File(sample_file_cutin, 'w') - h5_file_cutin.create_dataset('data', data=features_cutin) - h5_file_cutin.close() diff --git a/modules/tools/prediction/data_pipelines/mlp_train.py b/modules/tools/prediction/data_pipelines/mlp_train.py deleted file mode 100644 index f2d93c069a7..00000000000 --- a/modules/tools/prediction/data_pipelines/mlp_train.py +++ /dev/null @@ -1,323 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### -""" -@requirement: - tensorflow- 1.3.0 - Keras-1.2.2 -""" - -import argparse -import logging -import os - -import h5py -import numpy as np - -from keras.callbacks import ModelCheckpoint -from keras.metrics import mse -from keras.models import Sequential, Model -from keras.layers.normalization import BatchNormalization -from keras.layers import Activation -from keras.layers import Dense, Input -from keras.layers import Dropout -from keras.regularizers import l2, l1 -from keras.utils import np_utils -from sklearn.model_selection import train_test_split -import google.protobuf.text_format as text_format - -from modules.tools.prediction.data_pipelines.proto import fnn_model_pb2 -from modules.tools.prediction.data_pipelines.common import log -from modules.tools.prediction.data_pipelines.common.data_preprocess import load_h5 -from modules.tools.prediction.data_pipelines.common.data_preprocess import down_sample -from modules.tools.prediction.data_pipelines.common.data_preprocess import train_test_split -from modules.tools.prediction.data_pipelines.common.configure import parameters -from modules.tools.prediction.data_pipelines.common.configure import labels -from fnn_model_pb2 import FnnModel, Layer - - -# Constants -dim_input = parameters['mlp']['dim_input'] -dim_hidden_1 = parameters['mlp']['dim_hidden_1'] -dim_hidden_2 = parameters['mlp']['dim_hidden_2'] -dim_output = parameters['mlp']['dim_output'] -train_data_rate = parameters['mlp']['train_data_rate'] - -evaluation_log_path = os.path.join(os.getcwd(), "evaluation_report") -log.init_log(evaluation_log_path, level=logging.DEBUG) - - -def load_data(filename): - """ - Load the data from h5 file to the format of numpy - """ - if not (os.path.exists(filename)): - logging.error("file: {}, does not exist".format(filename)) - os._exit(1) - if os.path.splitext(filename)[1] != '.h5': - logging.error("file: {} is not an hdf5 file".format(filename)) - os._exit(1) - - samples = dict() - h5_file = h5py.File(filename, 'r') - for key in h5_file.keys(): - samples[key] = h5_file[key][:] - - print("load file success") - - return samples['data'] - - -def down_sample(data): - cutin_false_drate = 0.9 - go_false_drate = 0.9 - go_true_drate = 0.7 - cutin_true_drate = 0.0 - - label = data[:, -1] - size = np.shape(label)[0] - - cutin_false_index = (label == -1) - go_false_index = (label == 0) - go_true_index = (label == 1) - cutin_true_index = (label == 2) - - rand = np.random.random((size)) - - cutin_false_select = np.logical_and(cutin_false_index, - rand > cutin_false_drate) - cutin_true_select = np.logical_and(cutin_true_index, - rand > cutin_true_drate) - go_false_select = np.logical_and(go_false_index, rand > go_false_drate) - go_true_select = np.logical_and(go_true_index, rand > go_true_drate) - - all_select = np.logical_or(cutin_false_select, cutin_true_select) - all_select = np.logical_or(all_select, go_false_select) - all_select = np.logical_or(all_select, go_true_select) - - data_downsampled = data[all_select, :] - - return data_downsampled - - -def get_param_norm(feature): - """ - Normalize the samples and save normalized parameters - """ - fea_mean = np.mean(feature, axis=0) - fea_std = np.std(feature, axis=0) + 1e-6 - param_norm = (fea_mean, fea_std) - return param_norm - - -def setup_model(): - """ - Set up neural network based on keras.Sequential - """ - model = Sequential() - model.add( - Dense( - dim_hidden_1, - input_dim=dim_input, - init='he_normal', - activation='relu', - W_regularizer=l2(0.01))) - - model.add( - Dense( - dim_hidden_2, - init='he_normal', - activation='relu', - W_regularizer=l2(0.01))) - - model.add( - Dense( - dim_output, - init='he_normal', - activation='sigmoid', - W_regularizer=l2(0.01))) - - model.compile( - loss='binary_crossentropy', optimizer='rmsprop', metrics=['accuracy']) - - return model - - -def evaluate_model(y, pred): - """ - give the performance [recall, precision] of nn model - - Parameters - ---------- - y: numpy.array; real classess - pred: numpy.array; prediction classes - - Returns - ------- - performance dict, store the performance in log file - """ - y = y.reshape(-1) - pred = pred.reshape(-1) - - go_true = (y == labels['go_true']).sum() - go_false = (y == labels['go_false']).sum() - index_go = np.logical_or(y == labels['go_false'], y == labels['go_true']) - go_positive = (pred[index_go] == 1).sum() - go_negative = (pred[index_go] == 0).sum() - - cutin_true = (y == labels['cutin_true']).sum() - cutin_false = (y == labels['cutin_false']).sum() - index_cutin = np.logical_or(y == labels['cutin_false'], - y == labels['cutin_true']) - cutin_positive = (pred[index_cutin] == 1).sum() - cutin_negative = (pred[index_cutin] == 0).sum() - - logging.info("data size: {}, included:".format(y.shape[0])) - logging.info("\t True False Positive Negative") - logging.info(" Go: {:7} {:7} {:7} {:7}".format(go_true, go_false, - go_positive, go_negative)) - logging.info("Cutin:{:7} {:7} {:7} {:7}".format( - cutin_true, cutin_false, cutin_positive, cutin_negative)) - - logging.info("--------------------SCORE-----------------------------") - logging.info(" recall precision F1-score") - ctrue = float(go_true + cutin_true) - positive = float(go_positive + cutin_positive) - tp = float((pred[y > 0.1] == 1).sum()) - recall = tp / ctrue if ctrue != 0 else 0.0 - precision = tp / positive if positive != 0 else 0.0 - fscore = 2 * precision * recall / ( - precision + recall) if precision + recall != 0 else 0.0 - logging.info("Positive:{:6.3} {:6.3} {:6.3}".format( - recall, precision, fscore)) - - go_tp = float((pred[y == 1] == 1).sum()) - go_recall = go_tp / go_true if go_true != 0 else 0.0 - go_precision = go_tp / go_positive if go_positive != 0 else 0.0 - go_fscore = 2 * go_precision * go_recall / ( - go_precision + go_recall) if go_precision + go_recall != 0 else 0.0 - logging.info(" Go:{:6.3} {:6.3} {:6.3}".format( - go_recall, go_precision, go_fscore)) - - cutin_tp = float((pred[y == 2] == 1).sum()) - cutin_recall = cutin_tp / cutin_true if cutin_true != 0 else 0.0 - cutin_precision = cutin_tp / cutin_positive if cutin_positive != 0 else 0.0 - cutin_fscore = 2 * cutin_precision * cutin_recall / ( - cutin_precision + - cutin_recall) if cutin_precision + cutin_recall != 0 else 0.0 - logging.info(" Cutin:{:6.3} {:6.3} {:6.3}".format( - cutin_recall, cutin_precision, cutin_fscore)) - logging.info("-----------------------------------------------------\n\n") - - performance = { - 'recall': [recall, go_recall, cutin_recall], - 'precision': [precision, go_precision, cutin_precision] - } - return performance - - -def save_model(model, param_norm, filename): - """ - Save the trained model parameters into protobuf binary format file - """ - net_params = FnnModel() - net_params.samples_mean.columns.extend(param_norm[0].reshape(-1).tolist()) - net_params.samples_std.columns.extend(param_norm[1].reshape(-1).tolist()) - net_params.num_layer = 0 - for layer in model.flattened_layers: - net_params.num_layer += 1 - net_layer = net_params.layer.add() - config = layer.get_config() - net_layer.layer_input_dim = dim_input - net_layer.layer_output_dim = dim_output - if config['activation'] == 'relu': - net_layer.layer_activation_func = fnn_model_pb2.Layer.RELU - elif config['activation'] == 'tanh': - net_layer.layer_activation_func = fnn_model_pb2.Layer.TANH - elif config['activation'] == 'sigmoid': - net_layer.layer_activation_func = fnn_model_pb2.Layer.SIGMOID - - weights, bias = layer.get_weights() - net_layer.layer_bias.columns.extend(bias.reshape(-1).tolist()) - for col in weights.tolist(): - row = net_layer.layer_input_weight.rows.add() - row.columns.extend(col) - net_params.dim_input = dim_input - net_params.dim_output = dim_output - with open(filename, 'wb') as params_file: - params_file.write(net_params.SerializeToString()) - - -if __name__ == "__main__": - - parser = argparse.ArgumentParser( - description='train neural network based on feature files and save parameters') - parser.add_argument('filename', type=str, help='h5 file of data.') - - args = parser.parse_args() - file = args.filename - - data = load_data(file) - data = down_sample(data) - print("Data load success.") - print("data size =", data.shape) - - train_data, test_data = train_test_split(data, train_data_rate) - - print("training size =", train_data.shape) - - X_train = train_data[:, 0:dim_input] - Y_train = train_data[:, -1] - Y_trainc = Y_train > 0.1 - - X_test = test_data[:, 0:dim_input] - Y_test = test_data[:, -1] - Y_testc = Y_test > 0.1 - - param_norm = get_param_norm(X_train) - - X_train = (X_train - param_norm[0]) / param_norm[1] - - X_test = (X_test - param_norm[0]) / param_norm[1] - - model = setup_model() - - model.fit(X_train, Y_trainc, shuffle=True, nb_epoch=20, batch_size=32) - print("Model trained success.") - - X_test = (X_test - param_norm[0]) / param_norm[1] - - score = model.evaluate(X_test, Y_testc) - print("\nThe accuracy on testing dat is", score[1]) - - logging.info("Test data loss: {}, accuracy: {} ".format( - score[0], score[1])) - Y_train_hat = model.predict_classes(X_train, batch_size=32) - Y_test_hat = model.predict_proba(X_test, batch_size=32) - logging.info("## Training Data:") - evaluate_model(Y_train, Y_train_hat) - for thres in [x / 100.0 for x in range(20, 80, 5)]: - logging.info("##threshond = {} Testing Data:".format(thres)) - performance = evaluate_model(Y_test, Y_test_hat > thres) - performance['accuracy'] = [score[1]] - - print("\nFor more detailed evaluation results, please refer to", - evaluation_log_path + ".log") - - model_path = os.path.join(os.getcwd(), "mlp_model.bin") - save_model(model, param_norm, model_path) - print("Model has been saved to", model_path) diff --git a/modules/tools/prediction/data_pipelines/proto/BUILD b/modules/tools/prediction/data_pipelines/proto/BUILD deleted file mode 100644 index 84f431d64ad..00000000000 --- a/modules/tools/prediction/data_pipelines/proto/BUILD +++ /dev/null @@ -1,43 +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") - -package(default_visibility = ["//visibility:public"]) - -cc_proto_library( - name = "fnn_model_cc_proto", - deps = [ - ":fnn_model_proto", - ], -) - -proto_library( - name = "fnn_model_proto", - srcs = ["fnn_model.proto"], -) - -py_proto_library( - name = "fnn_model_py_pb2", - deps = [ - ":fnn_model_proto", - ], -) -cc_proto_library( - name = "cruise_model_cc_proto", - deps = [ - ":cruise_model_proto", - ], -) - -proto_library( - name = "cruise_model_proto", - srcs = ["cruise_model.proto"], -) - -py_proto_library( - name = "cruise_model_py_pb2", - deps = [ - ":cruise_model_proto", - ], -) diff --git a/modules/tools/prediction/data_pipelines/proto/cruise_model.proto b/modules/tools/prediction/data_pipelines/proto/cruise_model.proto deleted file mode 100644 index 3dcb8fd7e94..00000000000 --- a/modules/tools/prediction/data_pipelines/proto/cruise_model.proto +++ /dev/null @@ -1,97 +0,0 @@ -syntax = "proto2"; - -// Helpers: - -message TensorParameter { - repeated float data = 1 [packed = true]; - repeated int32 shape = 2; -} - -message InputParameter { - repeated int32 input_shape = 1; - optional string dtype = 2; // data type of the input - optional bool sparse = 3; -} - -// Basic layers - -message Conv1dParameter { - repeated int32 shape = 1; - optional bool use_bias = 2; - optional TensorParameter kernel = 3; - optional TensorParameter bias = 4; - optional int32 stride = 5; -} - -message DenseParameter { - optional int32 units = 1; - optional string activation = 2; - optional bool use_bias = 3; - optional TensorParameter weights = 4; - optional TensorParameter bias = 5; -} - -message ActivationParameter { - optional string activation = 1; -} - -message MaxPool1dParameter { - optional int32 kernel_size = 1; - optional int32 stride = 2; -} - -message AvgPool1dParameter { - optional int32 kernel_size = 1; - optional int32 stride = 2; -} - -// Intermediate building blocks: - -message LaneFeatureConvParameter { - optional Conv1dParameter conv1d_0 = 1; - optional ActivationParameter activation_1 = 2; - optional Conv1dParameter conv1d_2 = 3; - optional ActivationParameter activation_3 = 4; - optional Conv1dParameter conv1d_4 = 5; -} - -message ObsFeatureFCParameter { - optional DenseParameter linear_0 = 1; - optional ActivationParameter activation_1 = 2; - optional DenseParameter linear_3 = 3; - optional ActivationParameter activation_4 = 4; -} - -message ClassifyParameter { - optional DenseParameter linear_0 = 1; - optional ActivationParameter activation_1 = 2; - optional DenseParameter linear_3 = 3; - optional ActivationParameter activation_4 = 4; - optional DenseParameter linear_6 = 5; - optional ActivationParameter activation_7 = 6; - optional DenseParameter linear_9 = 7; - optional ActivationParameter activation_10 = 8; -} - -message RegressParameter { - optional DenseParameter linear_0 = 1; - optional ActivationParameter activation_1 = 2; - optional DenseParameter linear_3 = 3; - optional ActivationParameter activation_4 = 4; - optional DenseParameter linear_6 = 5; - optional ActivationParameter activation_7 = 6; - optional DenseParameter linear_9 = 7; - optional ActivationParameter activation_10 = 8; -} - -// Final model - -// next id = -message CruiseModelParameter { - optional LaneFeatureConvParameter lane_feature_conv = 1; - optional MaxPool1dParameter lane_feature_maxpool = 2; - optional AvgPool1dParameter lane_feature_avgpool = 3; - optional ObsFeatureFCParameter obs_feature_fc = 5; - optional ClassifyParameter classify = 6; - optional RegressParameter regress = 7; -} diff --git a/modules/tools/prediction/data_pipelines/proto/fnn_model.proto b/modules/tools/prediction/data_pipelines/proto/fnn_model.proto deleted file mode 100644 index 2ae2be3f5dd..00000000000 --- a/modules/tools/prediction/data_pipelines/proto/fnn_model.proto +++ /dev/null @@ -1,35 +0,0 @@ -syntax = "proto2"; - -message Vector { - repeated double columns = 1; -} - -message Matrix { - repeated Vector rows = 1; -} - -message Layer { - enum ActivationFunc { - RELU = 0; - TANH = 1; - SIGMOID = 2; - SOFTMAX = 3; - } - optional int32 layer_input_dim = 1; - optional int32 layer_output_dim = 2; - optional Matrix layer_input_weight = - 3; // weight matrix of |input_dim| x |output_dim| - optional Vector layer_bias = 4; // vector of bias, size of |output_dim| - optional ActivationFunc layer_activation_func = 5; -} - -message FnnModel { - optional int32 dim_input = 1; - optional Vector samples_mean = 2; - optional Vector samples_std = 3; - optional int32 num_layer = 4; - repeated Layer layer = - 5; // num_layer must equal to first layer layer_input_dim - optional int32 dim_output = - 6; // dim_ouput must equal to last layer layer_output_dim -} diff --git a/modules/tools/prediction/data_pipelines/scripts/combine_features_and_labels_script.sh b/modules/tools/prediction/data_pipelines/scripts/combine_features_and_labels_script.sh deleted file mode 100644 index b5820410daa..00000000000 --- a/modules/tools/prediction/data_pipelines/scripts/combine_features_and_labels_script.sh +++ /dev/null @@ -1,37 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# 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. -############################################################################### -# -# Usage: -# sudo bash /apollo/modules/tools/prediction/mlp_train/scripts/generate_labels.sh -# -# The input feature.X.bin will generate furture_status.label, cruise.label, junction.label - -SRC_DIR=$1 -LBL_DIR=$2 -SCENARIO=$3 - -set -e - -source /apollo/scripts/apollo_base.sh -source /apollo/cyber/setup.bash - -if [ ${SCENARIO} == "junction" ]; then - /apollo/bazel-bin/modules/tools/prediction/data_pipelines/data_preprocessing/combine_features_and_labels_for_junction ${SRC_DIR} ${LBL_DIR} -else - /apollo/bazel-bin/modules/tools/prediction/data_pipelines/data_preprocessing/combine_features_and_labels ${SRC_DIR} ${LBL_DIR} -fi diff --git a/modules/tools/prediction/data_pipelines/scripts/evaluate_prediction_result_script.sh b/modules/tools/prediction/data_pipelines/scripts/evaluate_prediction_result_script.sh deleted file mode 100644 index b7292c8cbe2..00000000000 --- a/modules/tools/prediction/data_pipelines/scripts/evaluate_prediction_result_script.sh +++ /dev/null @@ -1,34 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# 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. -############################################################################### -# -# Usage: -# sudo bash /apollo/modules/tools/prediction/data_pipelines/scripts/evaluate_prediction_result_script.sh -# -# - -RESULTS_DIR=$1 -LABELS_DIR=$2 -TIME_RANGE=$3 - -set -e - -source /apollo/scripts/apollo_base.sh -source /apollo/cyber/setup.bash - -/apollo/bazel-bin/modules/tools/prediction/data_pipelines/performance_evaluation/evaluate_prediction_result \ - ${RESULTS_DIR} ${LABELS_DIR} ${TIME_RANGE} diff --git a/modules/tools/prediction/data_pipelines/scripts/generate_labels.sh b/modules/tools/prediction/data_pipelines/scripts/generate_labels.sh deleted file mode 100644 index 470cec62a4a..00000000000 --- a/modules/tools/prediction/data_pipelines/scripts/generate_labels.sh +++ /dev/null @@ -1,31 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# 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. -############################################################################### -# -# Usage: -# sudo bash /apollo/modules/tools/prediction/mlp_train/scripts/generate_labels.sh -# -# The input feature.X.bin will generate 4 files: .npy, .furture_status.npy, cruise_label.npy, junction_label.npy - -SRC_FILE=$1 - -set -e - -source /apollo/scripts/apollo_base.sh -source /apollo/cyber/setup.bash - -/apollo/bazel-bin/modules/tools/prediction/data_pipelines/data_preprocessing/generate_labels ${SRC_FILE} diff --git a/modules/tools/prediction/data_pipelines/scripts/merge_label_dicts_script.sh b/modules/tools/prediction/data_pipelines/scripts/merge_label_dicts_script.sh deleted file mode 100644 index 639f06131c5..00000000000 --- a/modules/tools/prediction/data_pipelines/scripts/merge_label_dicts_script.sh +++ /dev/null @@ -1,31 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# 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. -############################################################################### -# -# Usage: -# sudo bash /apollo/modules/tools/prediction/mlp_train/scripts/generate_labels.sh -# -# The input feature.X.bin will generate furture_status.label, cruise.label, junction.label - -SRC_FILE=$1 - -set -e - -source /apollo/scripts/apollo_base.sh -source /apollo/cyber/setup.bash - -/apollo/bazel-bin/modules/tools/prediction/data_pipelines/data_preprocessing/merge_label_dicts ${SRC_FILE} diff --git a/modules/tools/prediction/data_pipelines/scripts/records_to_data_for_learning.sh b/modules/tools/prediction/data_pipelines/scripts/records_to_data_for_learning.sh deleted file mode 100644 index 483fc3d99f2..00000000000 --- a/modules/tools/prediction/data_pipelines/scripts/records_to_data_for_learning.sh +++ /dev/null @@ -1,46 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# 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. -############################################################################### - -SRC_DIR=$1 -TARGET_DIR=$2 - -set -e - -source /apollo/scripts/apollo_base.sh -source /apollo/cyber/setup.bash - -if [ ! -z "$4" ]; then - export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$4 -fi - -sudo mkdir -p ${TARGET_DIR} - -if [ -z "$3" ]; then - MAP_DIR="sunnyvale" -else - MAP_DIR=$3 -fi - -/apollo/bazel-bin/modules/prediction/pipeline/records_to_offline_data \ - --flagfile=/apollo/modules/prediction/conf/prediction.conf \ - --map_dir=/apollo/modules/map/data/${MAP_DIR} \ - --prediction_offline_mode=2 \ - --prediction_offline_bags=${SRC_DIR} \ - --prediction_data_dir=${TARGET_DIR} \ - --noenable_multi_thread \ - --noenable_async_draw_base_image diff --git a/modules/tools/prediction/data_pipelines/scripts/records_to_data_for_tuning.sh b/modules/tools/prediction/data_pipelines/scripts/records_to_data_for_tuning.sh deleted file mode 100644 index a6f2c0b78df..00000000000 --- a/modules/tools/prediction/data_pipelines/scripts/records_to_data_for_tuning.sh +++ /dev/null @@ -1,46 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# 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. -############################################################################### - -SRC_DIR=$1 -TARGET_DIR=$2 - -set -e - -source /apollo/scripts/apollo_base.sh -source /apollo/cyber/setup.bash - -if [ ! -z "$4" ]; then - export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$4 -fi - -sudo mkdir -p ${TARGET_DIR} - -if [ -z "$3" ]; then - MAP_DIR="sunnyvale" -else - MAP_DIR=$3 -fi - -/apollo/bazel-bin/modules/prediction/pipeline/records_to_offline_data \ - --flagfile=/apollo/modules/prediction/conf/prediction.conf \ - --map_dir=/apollo/modules/map/data/${MAP_DIR} \ - --prediction_offline_mode=5 \ - --noenable_multi_thread \ - --prediction_offline_bags=${SRC_DIR} \ - --prediction_data_dir=${TARGET_DIR} \ - --noenable_multi_thread diff --git a/modules/tools/prediction/data_pipelines/scripts/records_to_dump_feature_proto.sh b/modules/tools/prediction/data_pipelines/scripts/records_to_dump_feature_proto.sh deleted file mode 100644 index 6436d2b5b1a..00000000000 --- a/modules/tools/prediction/data_pipelines/scripts/records_to_dump_feature_proto.sh +++ /dev/null @@ -1,45 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# 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. -############################################################################### - -SRC_DIR=$1 -TARGET_DIR=$2 - -set -e - -source /apollo/scripts/apollo_base.sh -source /apollo/cyber/setup.bash - -if [ ! -z "$4" ]; then - export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$4 -fi - -sudo mkdir -p ${TARGET_DIR} - -if [ -z "$3" ]; then - MAP_DIR="sunnyvale" -else - MAP_DIR=$3 -fi - -/apollo/bazel-bin/modules/prediction/pipeline/records_to_offline_data \ - --flagfile=/apollo/modules/prediction/conf/prediction.conf \ - --map_dir=/apollo/modules/map/data/${MAP_DIR} \ - --prediction_offline_mode=1 \ - --noenable_multi_thread \ - --prediction_offline_bags=${SRC_DIR} \ - --prediction_data_dir=${TARGET_DIR} diff --git a/modules/tools/prediction/data_pipelines/scripts/records_to_dump_records.sh b/modules/tools/prediction/data_pipelines/scripts/records_to_dump_records.sh deleted file mode 100644 index 3937f4e185f..00000000000 --- a/modules/tools/prediction/data_pipelines/scripts/records_to_dump_records.sh +++ /dev/null @@ -1,44 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# 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. -############################################################################### - -SRC_DIR=$1 - -set -e - -source /apollo/scripts/apollo_base.sh -source /apollo/cyber/setup.bash - -if [ ! -z "$3" ]; then - export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$3 -fi - -if [ -z "$2" ]; then - MAP_DIR="sunnyvale" -else - MAP_DIR=$2 -fi - -/apollo/bazel-bin/modules/prediction/pipeline/records_to_offline_data \ - --flagfile=/apollo/modules/prediction/conf/prediction.conf \ - --map_dir=/apollo/modules/map/data/${MAP_DIR} \ - --prediction_offline_mode=6 \ - --prediction_offline_bags=${SRC_DIR} \ - --noenable_multi_thread \ - --noenable_async_draw_base_image \ - --enable_all_pedestrian_caution_in_front \ - --noenable_rank_caution_obstacles diff --git a/modules/tools/prediction/data_pipelines/scripts/records_to_frame_env.sh b/modules/tools/prediction/data_pipelines/scripts/records_to_frame_env.sh deleted file mode 100644 index 2e202e56e47..00000000000 --- a/modules/tools/prediction/data_pipelines/scripts/records_to_frame_env.sh +++ /dev/null @@ -1,48 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# 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. -############################################################################### - -SRC_DIR=$1 -TARGET_DIR=$2 - -set -e - -source /apollo/scripts/apollo_base.sh -source /apollo/cyber/setup.bash - -if [ ! -z "$4" ]; then - export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$4 -fi - -sudo mkdir -p ${TARGET_DIR} - -if [ -z "$3" ]; then - MAP_DIR="sunnyvale" -else - MAP_DIR=$3 -fi - -/apollo/bazel-bin/modules/prediction/pipeline/records_to_offline_data \ - --flagfile=/apollo/modules/prediction/conf/prediction.conf \ - --map_dir=/apollo/modules/map/data/${MAP_DIR} \ - --prediction_offline_mode=4 \ - --noenable_multi_thread \ - --prediction_offline_bags=${SRC_DIR} \ - --prediction_data_dir=${TARGET_DIR} \ - --max_num_dump_feature=1000 \ - --noenable_semantic_map \ - --noenable_async_draw_base_image diff --git a/modules/tools/prediction/data_pipelines/scripts/records_to_prediction_result.sh b/modules/tools/prediction/data_pipelines/scripts/records_to_prediction_result.sh deleted file mode 100644 index 55f7efe6ebd..00000000000 --- a/modules/tools/prediction/data_pipelines/scripts/records_to_prediction_result.sh +++ /dev/null @@ -1,45 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# 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. -############################################################################### - -SRC_DIR=$1 -TARGET_DIR=$2 - -set -e - -source /apollo/scripts/apollo_base.sh -source /apollo/cyber/setup.bash - -if [ ! -z "$4" ]; then - export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$4 -fi - -sudo mkdir -p ${TARGET_DIR} - -if [ -z "$3" ]; then - MAP_DIR="sunnyvale" -else - MAP_DIR=$3 -fi - -/apollo/bazel-bin/modules/prediction/pipeline/records_to_offline_data \ - --flagfile=/apollo/modules/prediction/conf/prediction.conf \ - --map_dir=/apollo/modules/map/data/${MAP_DIR} \ - --prediction_offline_mode=3 \ - --prediction_offline_bags=${SRC_DIR} \ - --noenable_multi_thread \ - --prediction_data_dir=${TARGET_DIR} diff --git a/modules/tools/prediction/data_pipelines/scripts/vector_net.sh b/modules/tools/prediction/data_pipelines/scripts/vector_net.sh deleted file mode 100644 index dae25a45664..00000000000 --- a/modules/tools/prediction/data_pipelines/scripts/vector_net.sh +++ /dev/null @@ -1,40 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# Copyright 2021 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. -############################################################################### - -OBSTACLE_X=$1 -OBSTACLE_Y=$2 -OBSTACLE_PHI=$3 -TARGET_FILE=$4 - -set -e - -source /apollo/scripts/apollo_base.sh -source /apollo/cyber/setup.bash - -if [ -z "$5" ]; then - MAP_DIR="sunnyvale" -else - MAP_DIR=$5 -fi - -/apollo/bazel-bin/modules/prediction/pipeline/vector_net_feature \ - --map_dir=/apollo/modules/map/data/${MAP_DIR} \ - --prediction_target_file=${TARGET_FILE} \ - --obstacle_x=${OBSTACLE_X} \ - --obstacle_y=${OBSTACLE_Y} \ - --obstacle_phi=${OBSTACLE_PHI} diff --git a/modules/tools/prediction/fake_prediction/BUILD b/modules/tools/prediction/fake_prediction/BUILD deleted file mode 100644 index 922db71d83d..00000000000 --- a/modules/tools/prediction/fake_prediction/BUILD +++ /dev/null @@ -1,27 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_binary") -load("//tools:cpplint.bzl", "cpplint") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -install( - name = "install", - library_dest = "tools/lib", - targets = [":libfake_prediction_component.so"], - visibility = ["//visibility:public"], -) - -cc_binary( - name = "libfake_prediction_component.so", - srcs = ["fake_prediction.cc"], - linkshared = True, - linkstatic = False, - deps = [ - "//cyber", - "//modules/common/adapters:adapter_gflags", - "//modules/common/util:util_tool", - "//modules/common_msgs/prediction_msgs:prediction_obstacle_cc_proto", - ], -) - -cpplint() diff --git a/modules/tools/prediction/fake_prediction/fake_prediction.cc b/modules/tools/prediction/fake_prediction/fake_prediction.cc deleted file mode 100644 index 7ec290e13c9..00000000000 --- a/modules/tools/prediction/fake_prediction/fake_prediction.cc +++ /dev/null @@ -1,59 +0,0 @@ -/****************************************************************************** - * Copyright 2017 The Apollo Authors. All Rights Reserved. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - *****************************************************************************/ - -/** - * @file - */ - -#include "cyber/component/timer_component.h" -#include "cyber/cyber.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/common/util/message_util.h" -#include "modules/common_msgs/prediction_msgs/prediction_obstacle.pb.h" - -namespace apollo { -namespace prediction { - -/** - * class FakePredictionComponent - * This class generates fake prediction messages. The prediction message only - * has valid headers. - * - * This tool is used to trigger modules that depends on prediction message. - */ - -class FakePredictionComponent : public apollo::cyber::TimerComponent { - public: - bool Init() override { - prediction_writer_ = - node_->CreateWriter(FLAGS_prediction_topic); - return true; - } - bool Proc() override { - auto prediction = std::make_shared(); - common::util::FillHeader("fake_prediction", prediction.get()); - prediction_writer_->Write(prediction); - return true; - } - - private: - std::shared_ptr> - prediction_writer_; -}; -CYBER_REGISTER_COMPONENT(FakePredictionComponent); - -} // namespace prediction -} // namespace apollo diff --git a/modules/tools/prediction/fake_prediction/fake_prediction.dag b/modules/tools/prediction/fake_prediction/fake_prediction.dag deleted file mode 100644 index 0b455275168..00000000000 --- a/modules/tools/prediction/fake_prediction/fake_prediction.dag +++ /dev/null @@ -1,10 +0,0 @@ -module_config { - module_library : "/apollo/bazel-bin/modules/tools/prediction/fake_prediction/libfake_prediction_component.so" - timer_components { - class_name : "FakePredictionComponent" - config { - name: "fake_prediction" - interval: 100 - } - } -} diff --git a/modules/tools/prediction/fake_prediction/fake_prediction.launch b/modules/tools/prediction/fake_prediction/fake_prediction.launch deleted file mode 100644 index affc7a0f01f..00000000000 --- a/modules/tools/prediction/fake_prediction/fake_prediction.launch +++ /dev/null @@ -1,7 +0,0 @@ - - - fake_prediction - /apollo/modules/tools/prediction/fake_prediction/fake_prediction.dag - - - diff --git a/modules/tools/prediction/multiple_gpu_estimator/BUILD b/modules/tools/prediction/multiple_gpu_estimator/BUILD deleted file mode 100644 index 881b8fd4fb3..00000000000 --- a/modules/tools/prediction/multiple_gpu_estimator/BUILD +++ /dev/null @@ -1,51 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") - -package(default_visibility = ["//visibility:public"]) - -py_binary( - name = "convert_to_tfrecords", - srcs = ["convert_to_tfrecords.py"], -) - -py_binary( - name = "counting", - srcs = ["counting.py"], -) - -py_library( - name = "mlp_data", - srcs = ["mlp_data.py"], -) - -py_binary( - name = "mlp_main", - srcs = ["mlp_main.py"], - deps = [ - ":mlp_data", - ":mlp_model", - ":mlp_utils", - ], -) - -py_library( - name = "mlp_model", - srcs = ["mlp_model.py"], - deps = [ - ":model_base", - ], -) - -py_library( - name = "mlp_utils", - srcs = ["mlp_utils.py"], -) - -py_library( - name = "model_base", - srcs = ["model_base.py"], -) - -py_binary( - name = "preprocessing", - srcs = ["preprocessing.py"], -) diff --git a/modules/tools/prediction/multiple_gpu_estimator/convert_to_tfrecords.py b/modules/tools/prediction/multiple_gpu_estimator/convert_to_tfrecords.py deleted file mode 100644 index 546e531d4b7..00000000000 --- a/modules/tools/prediction/multiple_gpu_estimator/convert_to_tfrecords.py +++ /dev/null @@ -1,98 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Modification 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. -############################################################################### - -# Copyright 2015 The TensorFlow 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. -# ============================================================================== -"""Converts MLP data to TFRecords file format with Example protos.""" - -import argparse -import os -import sys - -import numpy as np -import tensorflow as tf - - -FLAGS = None -feature_dim = 62 - - -def _float_feature(value): - return tf.train.Feature(float_list=tf.train.FloatList(value=value)) - - -def convert_to(bin_data, name): - """Converts bin_data to tfrecords.""" - if bin_data.shape[0] % (feature_dim + 1) != 0: - raise ValueError( - 'data size (%d) must be multiple of feature_dim + 1 (%d).' % - (bin_data.shape[0], feature_dim + 1)) - num_examples = bin_data.shape[0] // (feature_dim + 1) - print("num_examples:", num_examples) - filename = os.path.join(name + '.tfrecords') - print('Writing', filename) - with tf.python_io.TFRecordWriter(filename) as writer: - for index in range(0, num_examples): - data_raw = bin_data[index * (feature_dim + 1):index * - (feature_dim + 1) + feature_dim] - label_raw = np.array( - [bin_data[index*(feature_dim + 1)+feature_dim]]) - example = tf.train.Example( - features=tf.train.Features( - feature={ - 'data': _float_feature(data_raw), - 'label': _float_feature(label_raw) - })) - writer.write(example.SerializeToString()) - - -def main(unused_argv): - # Get the data. - for path, subdirs, files in os.walk(FLAGS.directory): - print("path:", path) - print("subdirs:", subdirs) - for name in files: - filename = os.path.join(path, name) - print("processing ", filename) - bin_data = np.fromfile(filename, dtype=np.float32) - - # Convert to Examples and write the result to TFRecords. - convert_to(bin_data, filename) - - -if __name__ == '__main__': - parser = argparse.ArgumentParser() - parser.add_argument( - '--directory', - type=str, - default='/tmp/data/prediction', - help='Directory to download data files and write the converted result') - FLAGS, unparsed = parser.parse_known_args() - tf.app.run(main=main, argv=[sys.argv[0]] + unparsed) diff --git a/modules/tools/prediction/multiple_gpu_estimator/counting.py b/modules/tools/prediction/multiple_gpu_estimator/counting.py deleted file mode 100644 index e92e0a1f6b4..00000000000 --- a/modules/tools/prediction/multiple_gpu_estimator/counting.py +++ /dev/null @@ -1,35 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import numpy as np -import os -from collections import Counter -from glob import glob - -feature_dim = 62 -count = Counter() -filenames = glob('/tmp/data/feature_v1_bin/*/*.label.bin') -for filename in filenames: - bin_data = np.fromfile(filename, dtype=np.float32) - if bin_data.shape[0] % (feature_dim + 1) != 0: - raise ValueError('data size (%d) must be multiple of feature_dim + 1 (%d).' % - (bin_data.shape[0], feature_dim + 1)) - label = bin_data[feature_dim::(feature_dim+1)].astype(np.int32) - count.update(label) - -print(count) diff --git a/modules/tools/prediction/multiple_gpu_estimator/mlp_data.py b/modules/tools/prediction/multiple_gpu_estimator/mlp_data.py deleted file mode 100644 index ec8c6b40598..00000000000 --- a/modules/tools/prediction/multiple_gpu_estimator/mlp_data.py +++ /dev/null @@ -1,108 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Modification 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. -############################################################################### - -# Copyright 2017 The TensorFlow 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. -# ============================================================================== - -"""Prediction data set""" - -import os - -import tensorflow as tf - - -dim_input = 62 - - -class MlpDataSet(object): - """Prediction mlp data set. - - """ - - def __init__(self, data_dir, subset='train'): - self.data_dir = data_dir - self.subset = subset - - def get_filenames(self): - if self.subset in ['train', 'validation', 'eval']: - return [os.path.join(self.data_dir, self.subset + '.tfrecords')] - else: - raise ValueError('Invalid data subset "%s"' % self.subset) - - def parser(self, serialized_example): - """Parses a single tf.Example into image and label tensors.""" - # Dimensions of the images in the CIFAR-10 dataset. - - features = tf.parse_single_example( - serialized_example, - features={ - 'data': tf.FixedLenFeature([62], tf.float32), - 'label': tf.FixedLenFeature([1], tf.float32), - }) - - image = features['data'] - label = tf.cast(features['label'], tf.int32)+1 - return image, label - - def make_batch(self, batch_size): - """Read the images and labels from 'filenames'.""" - filenames = self.get_filenames() - # Repeat infinitely. - dataset = tf.data.TFRecordDataset(filenames).repeat() - - # Parse records. - dataset = dataset.map(self.parser, num_parallel_calls=batch_size) - - # Potentially shuffle records. - if self.subset == 'train': - min_queue_examples = int( - MlpDataSet.num_examples_per_epoch(self.subset) * 0.1) - # Ensure that the capacity is sufficiently large to provide good random - # shuffling. - dataset = dataset.shuffle(buffer_size=min_queue_examples + - 3 * batch_size) - - # Batch it up. - dataset = dataset.batch(batch_size) - iterator = dataset.make_one_shot_iterator() - image_batch, label_batch = iterator.get_next() - - return image_batch, label_batch - - @staticmethod - def num_examples_per_epoch(subset='train'): - if subset == 'train': - return 13000000 - elif subset == 'validation': - return 1600000 - elif subset == 'eval': - return 1600000 - else: - raise ValueError('Invalid data subset "%s"' % subset) diff --git a/modules/tools/prediction/multiple_gpu_estimator/mlp_main.py b/modules/tools/prediction/multiple_gpu_estimator/mlp_main.py deleted file mode 100644 index d1f91880f64..00000000000 --- a/modules/tools/prediction/multiple_gpu_estimator/mlp_main.py +++ /dev/null @@ -1,507 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Modification 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. -############################################################################### - -# Copyright 2017 The TensorFlow 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. -# ============================================================================== -"""Mlp model for classifying prediction from Mlp dataset. - -""" - -import argparse -import functools -import itertools -import os -import six - -import modules.tools.multiple_gpu_estimator.mlp_data -import modules.tools.multiple_gpu_estimator.mlp_model -import modules.tools.multiple_gpu_estimator.mlp_utils -import numpy as np -import tensorflow as tf - - -tf.logging.set_verbosity(tf.logging.INFO) - - -def get_model_fn(num_gpus, variable_strategy, num_workers): - """Returns a function that will build the mlp model.""" - - def _mlp_model_fn(features, labels, mode, params): - """Mlp model body. - - Support single host, one or more GPU training. Parameter distribution can - be either one of the following scheme. - 1. CPU is the parameter server and manages gradient updates. - 2. Parameters are distributed evenly across all GPUs, and the first GPU - manages gradient updates. - - Args: - features: a list of tensors, one for each tower - labels: a list of tensors, one for each tower - mode: ModeKeys.TRAIN or EVAL - params: Hyperparameters suitable for tuning - Returns: - A EstimatorSpec object. - """ - is_training = (mode == tf.estimator.ModeKeys.TRAIN) - weight_decay = params.weight_decay - momentum = params.momentum - - tower_features = features - tower_labels = labels - tower_losses = [] - tower_gradvars = [] - tower_preds = [] - - # channels first (NCHW) is normally optimal on GPU and channels last (NHWC) - # on CPU. The exception is Intel MKL on CPU which is optimal with - # channels_last. - data_format = params.data_format - if not data_format: - if num_gpus == 0: - data_format = 'channels_last' - else: - data_format = 'channels_first' - - if num_gpus == 0: - num_devices = 1 - device_type = 'cpu' - else: - num_devices = num_gpus - device_type = 'gpu' - - for i in range(num_devices): - worker_device = '/{}:{}'.format(device_type, i) - if variable_strategy == 'CPU': - device_setter = mlp_utils.local_device_setter( - worker_device=worker_device) - elif variable_strategy == 'GPU': - device_setter = mlp_utils.local_device_setter( - ps_device_type='gpu', - worker_device=worker_device, - ps_strategy=tf.contrib.training. - GreedyLoadBalancingStrategy( - num_gpus, tf.contrib.training.byte_size_load_fn)) - with tf.variable_scope('mlp', reuse=bool(i != 0)): - with tf.name_scope('tower_%d' % i) as name_scope: - with tf.device(device_setter): - loss, gradvars, preds = _tower_fn( - is_training, weight_decay, tower_features[i], - tower_labels[i], data_format, - params.batch_norm_decay, params.batch_norm_epsilon) - tower_losses.append(loss) - tower_gradvars.append(gradvars) - tower_preds.append(preds) - if i == 0: - # Only trigger batch_norm moving mean and variance update from - # the 1st tower. Ideally, we should grab the updates from all - # towers but these stats accumulate extremely fast so we can - # ignore the other stats from the other towers without - # significant detriment. - update_ops = tf.get_collection( - tf.GraphKeys.UPDATE_OPS, name_scope) - - # Now compute global loss and gradients. - gradvars = [] - with tf.name_scope('gradient_averaging'): - all_grads = {} - for grad, var in itertools.chain(*tower_gradvars): - if grad is not None: - all_grads.setdefault(var, []).append(grad) - for var, grads in six.iteritems(all_grads): - # Average gradients on the same device as the variables - # to which they apply. - with tf.device(var.device): - if len(grads) == 1: - avg_grad = grads[0] - else: - avg_grad = tf.multiply( - tf.add_n(grads), 1. / len(grads)) - gradvars.append((avg_grad, var)) - - # Device that runs the ops to apply global gradient updates. - consolidation_device = '/gpu:0' if variable_strategy == 'GPU' else '/cpu:0' - with tf.device(consolidation_device): - num_batches_per_epoch = mlp_data.MlpDataSet.num_examples_per_epoch( - 'train') // (params.train_batch_size * num_workers) - boundaries = [ - num_batches_per_epoch * x - for x in np.array([20, 50, 80], dtype=np.int64) - ] - staged_lr = [ - params.learning_rate * x for x in [1, 0.1, 0.01, 0.002] - ] - - learning_rate = tf.train.piecewise_constant( - tf.train.get_global_step(), boundaries, staged_lr) - - loss = tf.reduce_mean(tower_losses, name='loss') - - examples_sec_hook = mlp_utils.ExamplesPerSecondHook( - params.train_batch_size, every_n_steps=10) - - tensors_to_log = {'learning_rate': learning_rate, 'loss': loss} - - logging_hook = tf.train.LoggingTensorHook( - tensors=tensors_to_log, every_n_iter=100) - - train_hooks = [logging_hook, examples_sec_hook] - - optimizer = tf.train.MomentumOptimizer( - learning_rate=learning_rate, momentum=momentum) - - if params.sync: - optimizer = tf.train.SyncReplicasOptimizer( - optimizer, replicas_to_aggregate=num_workers) - sync_replicas_hook = optimizer.make_session_run_hook( - params.is_chief) - train_hooks.append(sync_replicas_hook) - - # Create single grouped train op - train_op = [ - optimizer.apply_gradients( - gradvars, global_step=tf.train.get_global_step()) - ] - train_op.extend(update_ops) - train_op = tf.group(*train_op) - - predictions = { - 'classes': - tf.concat([p['classes'] for p in tower_preds], axis=0), - 'probabilities': - tf.concat([p['probabilities'] for p in tower_preds], axis=0) - } - stacked_labels = tf.concat(labels, axis=0) - metrics = { - 'accuracy': - tf.metrics.accuracy(stacked_labels, predictions['classes']) - } - - return tf.estimator.EstimatorSpec( - mode=mode, - predictions=predictions, - loss=loss, - train_op=train_op, - training_hooks=train_hooks, - eval_metric_ops=metrics) - - return _mlp_model_fn - - -def _tower_fn(is_training, weight_decay, feature, label, data_format, - batch_norm_decay, batch_norm_epsilon): - """Build computation tower. - - Args: - is_training: true if is training graph. - weight_decay: weight regularization strength, a float. - feature: a Tensor. - label: a Tensor. - data_format: channels_last (NHWC) or channels_first (NCHW). - batch_norm_decay: decay for batch normalization, a float. - batch_norm_epsilon: epsilon for batch normalization, a float. - - Returns: - A tuple with the loss for the tower, the gradients and parameters, and - predictions. - - """ - model = mlp_model.MlpModel( - batch_norm_decay=batch_norm_decay, - batch_norm_epsilon=batch_norm_epsilon, - is_training=is_training, - data_format=data_format) - logits = model.forward_pass(feature, input_data_format='channels_last') - tower_pred = { - 'classes': tf.argmax(input=logits, axis=1), - 'probabilities': tf.nn.softmax(logits) - } - - tower_loss = tf.losses.sparse_softmax_cross_entropy( - logits=logits, labels=label) - tower_loss = tf.reduce_mean(tower_loss) - - model_params = tf.trainable_variables() - tower_loss += weight_decay * tf.add_n( - [tf.nn.l2_loss(v) for v in model_params]) - - tower_grad = tf.gradients(tower_loss, model_params) - - return tower_loss, list(zip(tower_grad, model_params)), tower_pred - - -def input_fn(data_dir, subset, num_shards, batch_size): - """Create input graph for model. - - Args: - data_dir: Directory where TFRecords representing the dataset are located. - subset: one of 'train', 'validate' and 'eval'. - num_shards: num of towers participating in data-parallel training. - batch_size: total batch size for training to be divided by the number of - shards. - Returns: - two lists of tensors for features and labels, each of num_shards length. - """ - with tf.device('/cpu:0'): - dataset = mlp_data.MlpDataSet(data_dir, subset) - image_batch, label_batch = dataset.make_batch(batch_size) - if num_shards <= 1: - # No GPU available or only 1 GPU. - return [image_batch], [label_batch] - - # Note that passing num=batch_size is safe here, even though - # dataset.batch(batch_size) can, in some cases, return fewer than batch_size - # examples. This is because it does so only when repeating for a limited - # number of epochs, but our dataset repeats forever. - image_batch = tf.unstack(image_batch, num=batch_size, axis=0) - label_batch = tf.unstack(label_batch, num=batch_size, axis=0) - feature_shards = [[] for i in range(num_shards)] - label_shards = [[] for i in range(num_shards)] - for i in range(batch_size): - idx = i % num_shards - feature_shards[idx].append(image_batch[i]) - label_shards[idx].append(label_batch[i]) - feature_shards = [tf.parallel_stack(x) for x in feature_shards] - label_shards = [tf.parallel_stack(x) for x in label_shards] - return feature_shards, label_shards - - -def get_experiment_fn( - data_dir, - num_gpus, - variable_strategy, -): - """Returns an Experiment function. - - Experiments perform training on several workers in parallel, - in other words experiments know how to invoke train and eval in a sensible - fashion for distributed training. Arguments passed directly to this - function are not tunable, all other arguments should be passed within - tf.HParams, passed to the enclosed function. - - Args: - data_dir: str. Location of the data for input_fns. - num_gpus: int. Number of GPUs on each worker. - variable_strategy: String. CPU to use CPU as the parameter server - and GPU to use the GPUs as the parameter server. - Returns: - A function (tf.estimator.RunConfig, tf.contrib.training.HParams) -> - tf.contrib.learn.Experiment. - - Suitable for use by tf.contrib.learn.learn_runner, which will run various - methods on Experiment (train, evaluate) based on information - about the current runner in `run_config`. - """ - - def _experiment_fn(run_config, hparams): - """Returns an Experiment.""" - # Create estimator. - train_input_fn = functools.partial( - input_fn, - data_dir, - subset='train', - num_shards=num_gpus, - batch_size=hparams.train_batch_size) - - eval_input_fn = functools.partial( - input_fn, - data_dir, - subset='eval', - batch_size=hparams.eval_batch_size, - num_shards=num_gpus) - - num_eval_examples = mlp_data.MlpDataSet.num_examples_per_epoch('eval') - if num_eval_examples % hparams.eval_batch_size != 0: - raise ValueError( - 'validation set size must be multiple of eval_batch_size') - - train_steps = hparams.train_steps - eval_steps = num_eval_examples // hparams.eval_batch_size - - classifier = tf.estimator.Estimator( - model_fn=get_model_fn(num_gpus, variable_strategy, - run_config.num_worker_replicas or 1), - config=run_config, - params=hparams) - - # Create experiment. - return tf.contrib.learn.Experiment( - classifier, - train_input_fn=train_input_fn, - eval_input_fn=eval_input_fn, - train_steps=train_steps, - eval_steps=eval_steps) - - return _experiment_fn - - -def main(job_dir, data_dir, num_gpus, variable_strategy, log_device_placement, - num_intra_threads, **hparams): - # The env variable is on deprecation path, default is set to off. - os.environ['TF_SYNC_ON_FINISH'] = '0' - os.environ['TF_ENABLE_WINOGRAD_NONFUSED'] = '1' - - # Session configuration. - sess_config = tf.ConfigProto( - allow_soft_placement=True, - log_device_placement=log_device_placement, - intra_op_parallelism_threads=num_intra_threads, - gpu_options=tf.GPUOptions(force_gpu_compatible=True)) - - config = mlp_utils.RunConfig(session_config=sess_config, model_dir=job_dir) - tf.contrib.learn.learn_runner.run( - get_experiment_fn(data_dir, num_gpus, variable_strategy), - run_config=config, - hparams=tf.contrib.training.HParams( - is_chief=config.is_chief, **hparams)) - - -if __name__ == '__main__': - parser = argparse.ArgumentParser() - parser.add_argument( - '--data-dir', - type=str, - required=True, - help='The directory where the CIFAR-10 input data is stored.') - parser.add_argument( - '--job-dir', - type=str, - required=True, - help='The directory where the model will be stored.') - parser.add_argument( - '--variable-strategy', - choices=['CPU', 'GPU'], - type=str, - default='CPU', - help='Where to locate variable operations') - parser.add_argument( - '--num-gpus', - type=int, - default=1, - help='The number of gpus used. Uses only CPU if set to 0.') - parser.add_argument( - '--train-steps', - type=int, - default=20000, - help='The number of steps to use for training.') - parser.add_argument( - '--train-batch-size', - type=int, - default=10000, - help='Batch size for training.') - parser.add_argument( - '--eval-batch-size', - type=int, - default=10000, - help='Batch size for validation.') - parser.add_argument( - '--momentum', - type=float, - default=0.9, - help='Momentum for MomentumOptimizer.') - parser.add_argument( - '--weight-decay', - type=float, - default=2e-4, - help='Weight decay for convolutions.') - parser.add_argument( - '--learning-rate', - type=float, - default=0.1, - help="""\ - This is the initial learning rate value. The learning rate will decrease - during training. For more details check the model_fn implementation in - this file.\ - """) - parser.add_argument( - '--sync', - action='store_true', - default=False, - help="""\ - If present when running in a distributed environment will run on sync mode.\ - """) - parser.add_argument( - '--num-intra-threads', - type=int, - default=0, - help="""\ - Number of threads to use for intra-op parallelism. When training on CPU - set to 0 to have the system pick the appropriate number or alternatively - set it to the number of physical CPU cores.\ - """) - parser.add_argument( - '--num-inter-threads', - type=int, - default=0, - help="""\ - Number of threads to use for inter-op parallelism. If set to 0, the - system will pick an appropriate number.\ - """) - parser.add_argument( - '--data-format', - type=str, - default=None, - help="""\ - If not set, the data format best for the training device is used. - Allowed values: channels_first (NCHW) channels_last (NHWC).\ - """) - parser.add_argument( - '--log-device-placement', - action='store_true', - default=False, - help='Whether to log device placement.') - parser.add_argument( - '--batch-norm-decay', - type=float, - default=0.997, - help='Decay for batch norm.') - parser.add_argument( - '--batch-norm-epsilon', - type=float, - default=1e-5, - help='Epsilon for batch norm.') - args = parser.parse_args() - - if args.num_gpus > 0: - assert tf.test.is_gpu_available(), "Requested GPUs but none found." - if args.num_gpus < 0: - raise ValueError( - 'Invalid GPU count: \"--num-gpus\" must be 0 or a positive integer.' - ) - if args.num_gpus == 0 and args.variable_strategy == 'GPU': - raise ValueError( - 'num-gpus=0, CPU must be used as parameter server. Set' - '--variable-strategy=CPU.') - if args.num_gpus != 0 and args.train_batch_size % args.num_gpus != 0: - raise ValueError('--train-batch-size must be multiple of --num-gpus.') - if args.num_gpus != 0 and args.eval_batch_size % args.num_gpus != 0: - raise ValueError('--eval-batch-size must be multiple of --num-gpus.') - - main(**vars(args)) diff --git a/modules/tools/prediction/multiple_gpu_estimator/mlp_model.py b/modules/tools/prediction/multiple_gpu_estimator/mlp_model.py deleted file mode 100644 index 7a57295ae93..00000000000 --- a/modules/tools/prediction/multiple_gpu_estimator/mlp_model.py +++ /dev/null @@ -1,88 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Modification 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. -############################################################################### - -# Copyright 2017 The TensorFlow 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. -# ============================================================================== - -import tensorflow as tf - -import modules.tools.prediction.multiple_gpu_estimator.model_base - - -dim_input = 62 -dim_hidden_1 = 30 -dim_hidden_2 = 15 -dim_output = 4 - - -class MlpModel(model_base.ModelBase): - """prediction model with fully connected layers.""" - - def __init__(self, - is_training=True, - batch_norm_decay=0.999, - batch_norm_epsilon=0.001, - data_format='channels_last'): - super(MlpModel, self).__init__(is_training, data_format, - batch_norm_decay, batch_norm_epsilon) - - def forward_pass(self, x, input_data_format='channels_last'): - """Build the core model within the graph.""" - x = self._fully_connected_with_bn( - x, - dim_input, - kernel_initializer=tf.contrib.keras.initializers.he_normal(), - kernel_regularizer=tf.contrib.layers.l2_regularizer(0.01)) - x = self._fully_connected_with_bn( - x, - dim_hidden_1, - kernel_initializer=tf.contrib.keras.initializers.he_normal(), - kernel_regularizer=tf.contrib.layers.l2_regularizer(0.01)) - x = self._fully_connected_with_bn( - x, - dim_hidden_2, - kernel_initializer=tf.contrib.keras.initializers.he_normal(), - kernel_regularizer=tf.contrib.layers.l2_regularizer(0.01)) - x = self._fully_connected(x, dim_output) - return x - - def _fully_connected_with_bn(self, - x, - out_dim, - kernel_initializer=None, - kernel_regularizer=None): - x = self._fully_connected( - x, - out_dim, - kernel_initializer=kernel_initializer, - kernel_regularizer=kernel_regularizer) - x = self._relu(x) - x = self._batch_norm(x) - return x diff --git a/modules/tools/prediction/multiple_gpu_estimator/mlp_utils.py b/modules/tools/prediction/multiple_gpu_estimator/mlp_utils.py deleted file mode 100644 index 35be16cc860..00000000000 --- a/modules/tools/prediction/multiple_gpu_estimator/mlp_utils.py +++ /dev/null @@ -1,175 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Modification 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. -############################################################################### - -# Copyright 2017 The TensorFlow 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. -# ============================================================================== - -import collections -import six - -from tensorflow.contrib.learn.python.learn import run_config -from tensorflow.core.framework import node_def_pb2 -from tensorflow.python.framework import device as pydev -from tensorflow.python.platform import tf_logging as logging -from tensorflow.python.training import basic_session_run_hooks -from tensorflow.python.training import device_setter -from tensorflow.python.training import session_run_hook -from tensorflow.python.training import training_util -import tensorflow as tf - - -class RunConfig(tf.contrib.learn.RunConfig): - def uid(self, whitelist=None): - """Generates a 'Unique Identifier' based on all internal fields. - Caller should use the uid string to check `RunConfig` instance integrity - in one session use, but should not rely on the implementation details, which - is subject to change. - Args: - whitelist: A list of the string names of the properties uid should not - include. If `None`, defaults to `_DEFAULT_UID_WHITE_LIST`, which - includes most properties user allowes to change. - Returns: - A uid string. - """ - if whitelist is None: - whitelist = run_config._DEFAULT_UID_WHITE_LIST - - state = { - k: v - for k, v in self.__dict__.items() if not k.startswith('__') - } - # Pop out the keys in whitelist. - for k in whitelist: - state.pop('_' + k, None) - - ordered_state = collections.OrderedDict( - sorted(list(state.items()), key=lambda t: t[0])) - # For class instance without __repr__, some special cares are required. - # Otherwise, the object address will be used. - if '_cluster_spec' in ordered_state: - ordered_state['_cluster_spec'] = collections.OrderedDict( - sorted( - list(ordered_state['_cluster_spec'].as_dict().items()), - key=lambda t: t[0])) - return ', '.join( - '%s=%r' % (k, v) for (k, v) in six.iteritems(ordered_state)) - - -class ExamplesPerSecondHook(session_run_hook.SessionRunHook): - """Hook to print out examples per second. - - Total time is tracked and then divided by the total number of steps - to get the average step time and then batch_size is used to determine - the running average of examples per second. The examples per second for the - most recent interval is also logged. - """ - - def __init__( - self, - batch_size, - every_n_steps=100, - every_n_secs=None, - ): - """Initializer for ExamplesPerSecondHook. - - Args: - batch_size: Total batch size used to calculate examples/second from - global time. - every_n_steps: Log stats every n steps. - every_n_secs: Log stats every n seconds. - """ - if (every_n_steps is None) == (every_n_secs is None): - raise ValueError('exactly one of every_n_steps' - ' and every_n_secs should be provided.') - self._timer = basic_session_run_hooks.SecondOrStepTimer( - every_steps=every_n_steps, every_secs=every_n_secs) - - self._step_train_time = 0 - self._total_steps = 0 - self._batch_size = batch_size - - def begin(self): - self._global_step_tensor = training_util.get_global_step() - if self._global_step_tensor is None: - raise RuntimeError( - 'Global step should be created to use StepCounterHook.') - - def before_run(self, run_context): # pylint: disable=unused-argument - return basic_session_run_hooks.SessionRunArgs(self._global_step_tensor) - - def after_run(self, run_context, run_values): - _ = run_context - - global_step = run_values.results - if self._timer.should_trigger_for_step(global_step): - elapsed_time, elapsed_steps = self._timer.update_last_triggered_step( - global_step) - if elapsed_time is not None: - steps_per_sec = elapsed_steps / elapsed_time - self._step_train_time += elapsed_time - self._total_steps += elapsed_steps - - average_examples_per_sec = self._batch_size * ( - self._total_steps / self._step_train_time) - current_examples_per_sec = steps_per_sec * self._batch_size - # Average examples/sec followed by current examples/sec - logging.info('%s: %g (%g), step = %g', 'Average examples/sec', - average_examples_per_sec, - current_examples_per_sec, self._total_steps) - - -def local_device_setter(num_devices=1, - ps_device_type='cpu', - worker_device='/cpu:0', - ps_ops=None, - ps_strategy=None): - if ps_ops is None: - ps_ops = ['Variable', 'VariableV2', 'VarHandleOp'] - - if ps_strategy is None: - ps_strategy = device_setter._RoundRobinStrategy(num_devices) - if not six.callable(ps_strategy): - raise TypeError("ps_strategy must be callable") - - def _local_device_chooser(op): - current_device = pydev.DeviceSpec.from_string(op.device or "") - - node_def = op if isinstance(op, node_def_pb2.NodeDef) else op.node_def - if node_def.op in ps_ops: - ps_device_spec = pydev.DeviceSpec.from_string('/{}:{}'.format( - ps_device_type, ps_strategy(op))) - ps_device_spec.merge_from(current_device) - return ps_device_spec.to_string() - - worker_device_spec = pydev.DeviceSpec.from_string(worker_device or "") - worker_device_spec.merge_from(current_device) - return worker_device_spec.to_string() - - return _local_device_chooser diff --git a/modules/tools/prediction/multiple_gpu_estimator/model_base.py b/modules/tools/prediction/multiple_gpu_estimator/model_base.py deleted file mode 100644 index fa513aeddc5..00000000000 --- a/modules/tools/prediction/multiple_gpu_estimator/model_base.py +++ /dev/null @@ -1,117 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Modification 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. -############################################################################### - -# Copyright 2018 The TensorFlow 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. -# ============================================================================== - -import tensorflow as tf - - -class ModelBase(object): - def __init__(self, - is_training=True, - data_format='channels_last', - batch_norm_decay=0.999, - batch_norm_epsilon=0.001): - """ModelBase constructor. - - Args: - is_training: if build training or inference model. - data_format: the data_format used during computation. - one of 'channels_first' or 'channels_last'. - """ - self._batch_norm_decay = batch_norm_decay - self._batch_norm_epsilon = batch_norm_epsilon - self._is_training = is_training - assert data_format in ('channels_first', 'channels_last') - self._data_format = data_format - - def forward_pass(self, x): - raise NotImplementedError( - 'forward_pass() is implemented in ResNet sub classes') - - def _conv(self, x, kernel_size, filters, strides, is_atrous=False): - """Convolution.""" - - padding = 'SAME' - if not is_atrous and strides > 1: - pad = kernel_size - 1 - pad_beg = pad // 2 - pad_end = pad - pad_beg - if self._data_format == 'channels_first': - x = tf.pad( - x, - [[0, 0], [0, 0], [pad_beg, pad_end], [pad_beg, pad_end]]) - else: - x = tf.pad( - x, - [[0, 0], [pad_beg, pad_end], [pad_beg, pad_end], [0, 0]]) - padding = 'VALID' - return tf.layers.conv2d( - inputs=x, - kernel_size=kernel_size, - filters=filters, - strides=strides, - padding=padding, - use_bias=False, - data_format=self._data_format) - - def _batch_norm(self, x): - if self._data_format == 'channels_first': - data_format = 'NCHW' - else: - data_format = 'NHWC' - return tf.contrib.layers.batch_norm( - x, - decay=self._batch_norm_decay, - center=True, - scale=True, - epsilon=self._batch_norm_epsilon, - is_training=self._is_training, - fused=True, - data_format=data_format) - - def _relu(self, x): - return tf.nn.relu(x) - - def _fully_connected(self, - x, - out_dim, - kernel_initializer=None, - kernel_regularizer=None): - with tf.name_scope('fully_connected') as name_scope: - x = tf.layers.dense( - x, - out_dim, - kernel_initializer=kernel_initializer, - kernel_regularizer=kernel_regularizer) - - tf.logging.info('image after unit %s: %s', name_scope, x.get_shape()) - return x diff --git a/modules/tools/prediction/multiple_gpu_estimator/preprocessing.py b/modules/tools/prediction/multiple_gpu_estimator/preprocessing.py deleted file mode 100644 index 5f7532459be..00000000000 --- a/modules/tools/prediction/multiple_gpu_estimator/preprocessing.py +++ /dev/null @@ -1,75 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import tensorflow as tf -import numpy as np -from glob import glob - -feature_dim = 62 -train_data = np.zeros([20000000, feature_dim+1], dtype=np.float32) -test_data = np.zeros([2000000, feature_dim+1], dtype=np.float32) -eval_data = np.zeros([2000000, feature_dim+1], dtype=np.float32) -train_idx, test_idx, eval_idx = 0, 0, 0 -filenames = glob('/tmp/data/feature_v1_bin/*/*.label.bin') -for filename in filenames: - print(filename) - bin_data = np.fromfile(filename, dtype=np.float32) - if bin_data.shape[0] % (feature_dim + 1) != 0: - raise ValueError('data size (%d) must be multiple of feature_dim + 1 (%d).' % - (bin_data.shape[0], feature_dim + 1)) - num_examples = bin_data.shape[0] // (feature_dim + 1) - for i in range(num_examples): - label = int(bin_data[i*(feature_dim + 1)+feature_dim]) - data = bin_data[i*(feature_dim + 1):(i+1) * - (feature_dim + 1)].reshape([1, (feature_dim+1)]) - if label == 2: - times = 17 - new_data = np.repeat(data, times, axis=0) - elif label == 1: - times = np.random.choice([2, 2, 2, 3, 3]) - new_data = np.repeat(data, times, axis=0) - else: - times = 1 - new_data = data - - if i % 10 == 8: - test_data[test_idx:test_idx+times, :] = new_data - test_idx += times - elif i % 10 == 9: - eval_data[eval_idx:eval_idx+times, :] = new_data - eval_idx += times - else: - train_data[train_idx:train_idx+times, :] = new_data - train_idx += times - -train_data = train_data[:train_idx, :] -np.random.shuffle(train_data) -print(train_data.shape, train_idx) - -test_data = test_data[:test_idx, :] -np.random.shuffle(test_data) -print(test_data.shape, test_idx) - -eval_data = eval_data[:eval_idx, :] -np.random.shuffle(eval_data) -print(eval_data.shape, eval_idx) - -# write to file -train_data[:13000000, :].tofile('/tmp/data/prediction/train.bin') -test_data[:1600000, :].tofile('/tmp/data/prediction/test.bin') -eval_data[:1600000, :].tofile('/tmp/data/prediction/eval.bin') diff --git a/modules/tools/realtime_plot/BUILD b/modules/tools/realtime_plot/BUILD deleted file mode 100644 index e4460a06794..00000000000 --- a/modules/tools/realtime_plot/BUILD +++ /dev/null @@ -1,42 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -py_library( - name = "item", - srcs = ["item.py"], -) - -py_binary( - name = "realtime_plot", - srcs = ["realtime_plot.py"], - deps = [ - ":item", - ":stitem", - ":xyitem", - "//cyber/python/cyber_py3:cyber", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - "//modules/common_msgs/planning_msgs:planning_py_pb2", - "//modules/tools/common:proto_utils", - ], -) - -py_library( - name = "stitem", - srcs = ["stitem.py"], -) - -py_library( - name = "xyitem", - srcs = ["xyitem.py"], -) - -install( - name = "install", - py_dest = "tools/realtime_plot", - targets = [ - ":realtime_plot", - ] -) \ No newline at end of file diff --git a/modules/tools/realtime_plot/item.py b/modules/tools/realtime_plot/item.py deleted file mode 100644 index 403014de42d..00000000000 --- a/modules/tools/realtime_plot/item.py +++ /dev/null @@ -1,148 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -Time Value Item -""" -import numpy -from matplotlib import lines - - -class Item(object): - """ - Specific item to plot - """ - - def __init__(self, ax, title, xlabel, ylabel, ymin, ymax): - self.ax = ax - - self.title = title - self.ax.set_title(title) - self.ax.set_xlabel(xlabel, fontsize=10) - self.ax.set_ylabel(ylabel, fontsize=10) - self.ymin = ymin - self.ymax = ymax - self.ax.set_ylim([ymin, ymax]) - - self.lines = [] - - self.cartimehist = [] - self.carvaluehist = [] - self.targettime = [] - self.targethist = [] - - self.targethistidx = -1 - self.histidx = -1 - - self.prev_auto = False - - self.planningavailable = False - - def reset(self): - """ - Reset - """ - del self.lines[:] - - del self.cartimehist[:] - del self.carvaluehist[:] - del self.targettime[:] - del self.targethist[:] - - self.ax.cla() - - self.ax.set_ylim([self.ymin, self.ymax]) - self.targethistidx = -1 - self.histidx = -1 - - self.prev_auto = False - - self.planningavailable = False - - def new_planning(self, time, values): - """ - new planning - """ - self.planningtime = time - self.planningvalues = values - - if self.planningavailable == False: - self.ax.set_xlim([time[0] - 1, time[-1] + 10]) - self.current_line = lines.Line2D(time, values, color='red', lw=1.5) - self.ax.add_line(self.current_line) - - else: - self.current_line.set_data(time, values) - - xmin, xmax = self.ax.get_xlim() - if (time[-1] >= (xmax - 1)): - self.ax.set_xlim([time[0] - 1, time[-1] + 10]) - - self.planningavailable = True - - def new_carstatus(self, time, value, autodriving): - """ - new carstatus - """ - if autodriving and not self.prev_auto: - self.starttime = time - self.endtime = time + 50 - self.ax.axvspan(self.starttime, self.endtime, fc='0.1', alpha=0.3) - elif autodriving and time >= (self.endtime - 20): - self.endtime = time + 50 - self.ax.patches[-1].remove() - self.ax.axvspan(self.starttime, self.endtime, fc='0.1', alpha=0.3) - elif not autodriving and self.prev_auto: - self.endtime = time - self.ax.patches[-1].remove() - self.ax.axvspan(self.starttime, self.endtime, fc='0.1', alpha=0.3) - - self.prev_auto = autodriving - - self.cartimehist.append(time) - self.carvaluehist.append(value) - - if self.planningavailable: - target = numpy.interp(time, self.planningtime, self.planningvalues) - self.targettime.append(time) - self.targethist.append(target) - - if self.targethistidx == -1: - self.ax.plot( - self.targettime, self.targethist, color='green', lw=1.5) - self.targethistidx = len(self.ax.lines) - 1 - else: - self.ax.lines[self.targethistidx].set_data( - self.targettime, self.targethist) - - if self.histidx == -1: - self.ax.plot(self.cartimehist, self.carvaluehist, color='blue') - self.histidx = len(self.ax.lines) - 1 - - else: - self.ax.lines[self.histidx].set_data(self.cartimehist, - self.carvaluehist) - - def draw_lines(self): - """ - plot lines - """ - for polygon in self.ax.patches: - self.ax.draw_artist(polygon) - - for line in self.ax.lines: - self.ax.draw_artist(line) diff --git a/modules/tools/realtime_plot/realtime_plot.py b/modules/tools/realtime_plot/realtime_plot.py deleted file mode 100644 index 3fce736301d..00000000000 --- a/modules/tools/realtime_plot/realtime_plot.py +++ /dev/null @@ -1,260 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -"""Real Time Plotting of planning and control""" - -import math -import sys -import threading - -import gflags -import matplotlib.pyplot as plt -import numpy as np - -from cyber.python.cyber_py3 import cyber -from modules.tools.realtime_plot.item import Item -from modules.common_msgs.chassis_msgs.chassis_pb2 import Chassis -from modules.common_msgs.localization_msgs.localization_pb2 import LocalizationEstimate -from modules.common_msgs.planning_msgs.planning_pb2 import ADCTrajectory -from modules.tools.realtime_plot.stitem import Stitem -from modules.tools.realtime_plot.xyitem import Xyitem -import modules.tools.common.proto_utils as proto_utils - - -VehicleLength = 2.85 -HistLine2display = 2 # The number of lines to display -MaxSteerAngle = 470 # Maximum Steering Angle -SteerRatio = 16 -WindowSize = 80 - -FLAGS = gflags.FLAGS -gflags.DEFINE_boolean('show_heading', False, - 'Show heading instead of acceleration') -gflags.DEFINE_boolean('show_st_graph', False, 'Show st graph') - - -class Plotter(object): - """Plotter Class""" - - def __init__(self, ax1, ax2, ax3, ax4, stgraph): - self.ax = [ax1, ax2, ax3, ax4] - - self.updategraph = False - self.planningavailable = False - - self.closed = False - self.carspeed = 0.0 - self.steer_angle = 0.0 - self.autodrive = False - self.carcurvature = 0.0 - - self.stgraph = stgraph - - self.lock = threading.Lock() - - def callback_planning(self, data): - """New Planning Trajectory""" - if self.stgraph: - st_s, st_t, polygons_s, polygons_t = proto_utils.flatten( - data.debug.planning_data.st_graph, - ['speed_profile.s', - 'speed_profile.t', - 'boundary.point.s', - 'boundary.point.t']) - - with self.lock: - for i in range(len(st_s)): - self.ax[i].new_planning(st_t[i], st_s[i], - polygons_t[i], polygons_s[i]) - - else: - if len(data.trajectory_point) == 0: - print(data) - return - - x, y, speed, theta, kappa, acc, relative_time = np.array( - proto_utils.flatten(data.trajectory_point, - ['path_point.x', - 'path_point.y', - 'v', - 'path_point.theta', - 'path_point.kappa', - 'a', - 'relative_time'])) - relative_time += data.header.timestamp_sec - - with self.lock: - self.ax[0].new_planning(relative_time, x, y) - self.ax[1].new_planning(relative_time, speed) - - if self.ax[2].title == "Curvature": - self.ax[2].new_planning(relative_time, kappa) - - if self.ax[3].title == "Heading": - self.ax[3].new_planning(relative_time, theta) - else: - self.ax[3].new_planning(relative_time, acc) - - def callback_chassis(self, data): - """New localization pose""" - if self.stgraph: - return - self.carspeed = data.speed_mps - self.steer_angle = \ - data.steering_percentage / 100 * MaxSteerAngle / SteerRatio - - self.autodrive = (data.driving_mode == Chassis.COMPLETE_AUTO_DRIVE) - self.carcurvature = math.tan( - math.radians(self.steer_angle)) / VehicleLength - - def callback_localization(self, data): - """New localization pose""" - if self.stgraph: - return - carheading = data.pose.heading - carx = data.pose.position.x - cary = data.pose.position.y - cartime = data.header.timestamp_sec - with self.lock: - self.ax[0].new_carstatus(cartime, carx, cary, carheading, - self.steer_angle, self.autodrive) - self.ax[1].new_carstatus(cartime, self.carspeed, self.autodrive) - self.ax[2].new_carstatus( - cartime, self.carcurvature, self.autodrive) - - if self.ax[3].title == "Heading": - self.ax[3].new_carstatus(cartime, carheading, self.autodrive) - else: - acc = data.pose.linear_acceleration_vrf.y - self.ax[3].new_carstatus(cartime, acc, self.autodrive) - - def press(self, event): - """Keyboard events during plotting""" - if event.key == 'q' or event.key == 'Q': - plt.close('all') - self.closed = True - - if event.key == 'x' or event.key == 'X': - self.updategraph = True - - if event.key == 'a' or event.key == 'A': - fig = plt.gcf() - fig.gca().autoscale() - fig.canvas.draw() - - if event.key == 'n' or event.key == 'N': - with self.lock: - for ax in self.ax: - ax.reset() - self.updategraph = True - - -def main(argv): - """Main function""" - argv = FLAGS(argv) - - print(""" - Keyboard Shortcut: - [q]: Quit Tool - [s]: Save Figure - [a]: Auto-adjust x, y axis to display entire plot - [x]: Update Figure to Display last few Planning Trajectory instead of all - [h][r]: Go back Home, Display all Planning Trajectory - [f]: Toggle Full Screen - [n]: Reset all Plots - [b]: Unsubscribe Topics - - Legend Description: - Red Line: Current Planning Trajectory - Blue Line: Past Car Status History - Green Line: Past Planning Target History at every Car Status Frame - Cyan Dashed Line: Past Planning Trajectory Frames - """) - cyber.init() - planning_sub = cyber.Node("stat_planning") - - fig = plt.figure() - - if not FLAGS.show_st_graph: - ax1 = plt.subplot(2, 2, 1) - item1 = Xyitem(ax1, WindowSize, VehicleLength, "Trajectory", "X [m]", - "Y [m]") - - ax2 = plt.subplot(2, 2, 2) - item2 = Item(ax2, "Speed", "Time [sec]", "Speed [m/s]", 0, 30) - - ax3 = plt.subplot(2, 2, 3, sharex=ax2) - item3 = Item(ax3, "Curvature", "Time [sec]", "Curvature [m-1]", -0.2, - 0.2) - - ax4 = plt.subplot(2, 2, 4, sharex=ax2) - if not FLAGS.show_heading: - item4 = Item(ax4, "Acceleration", "Time [sec]", - "Acceleration [m/sec^2]", -5, 5) - else: - item4 = Item(ax4, "Heading", "Time [sec]", "Heading [radian]", -4, - 4) - else: - ax1 = plt.subplot(2, 2, 1) - item1 = Stitem(ax1, "ST Graph", "Time [sec]", "S [m]") - - ax2 = plt.subplot(2, 2, 2) - item2 = Stitem(ax2, "ST Graph", "Time [sec]", "S [m]") - - ax3 = plt.subplot(2, 2, 3) - item3 = Stitem(ax3, "ST Graph", "Time [sec]", "S [m]") - - ax4 = plt.subplot(2, 2, 4) - item4 = Stitem(ax4, "ST Graph", "Time [sec]", "S [m]") - - plt.tight_layout(pad=0.20) - plt.ion() - plt.show() - - plotter = Plotter(item1, item2, item3, item4, FLAGS.show_st_graph) - fig.canvas.mpl_connect('key_press_event', plotter.press) - planning_sub.create_reader('/apollo/planning', - ADCTrajectory, plotter.callback_planning) - if not FLAGS.show_st_graph: - localization_sub = cyber.Node("localization_sub") - localization_sub.create_reader('/apollo/localization/pose', - LocalizationEstimate, plotter.callback_localization) - chassis_sub = cyber.Node("chassis_sub") - chassis_sub.create_reader('/apollo/canbus/chassis', - Chassis, plotter.callback_chassis) - - while not cyber.is_shutdown(): - ax1.draw_artist(ax1.patch) - ax2.draw_artist(ax2.patch) - ax3.draw_artist(ax3.patch) - ax4.draw_artist(ax4.patch) - - with plotter.lock: - item1.draw_lines() - item2.draw_lines() - item3.draw_lines() - item4.draw_lines() - - fig.canvas.blit(ax1.bbox) - fig.canvas.blit(ax2.bbox) - fig.canvas.blit(ax3.bbox) - fig.canvas.blit(ax4.bbox) - fig.canvas.flush_events() - - -if __name__ == '__main__': - main(sys.argv) diff --git a/modules/tools/realtime_plot/stitem.py b/modules/tools/realtime_plot/stitem.py deleted file mode 100644 index 74ab0187268..00000000000 --- a/modules/tools/realtime_plot/stitem.py +++ /dev/null @@ -1,76 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -"""S T Item""" - -import numpy as np -from matplotlib import lines -from matplotlib.patches import Polygon - - -class Stitem(object): - """Specific item to plot""" - - def __init__(self, ax, title, xlabel, ylabel): - self.ax = ax - self.title = title - self.ax.set_title(title) - self.ax.set_xlabel(xlabel, fontsize=10) - self.ax.set_ylabel(ylabel, fontsize=10) - self.planningavailable = False - - def reset(self): - """Reset""" - self.ax.cla() - self.ax.set_xlim([-0.1, 0.1]) - self.ax.set_ylim([-0.1, 0.1]) - - def new_planning(self, time, values, polygons_t, polygons_s): - """new planning""" - max_time = max(time) + 1 - max_value = max(values) + 1 - if self.planningavailable == False: - self.ax.set_xlim([0, max_time]) - self.ax.set_ylim([0, max_value]) - self.ymax = max_value - self.tmax = max_time - self.current_line = lines.Line2D(time, values, color='red', lw=1.5) - self.ax.add_line(self.current_line) - else: - self.current_line.set_data(time, values) - _, xmax = self.ax.get_xlim() - if max_time > xmax: - self.ax.set_xlim([0, max_time]) - _, ymax = self.ax.get_ylim() - if max_value > ymax: - self.ax.set_ylim([0, max_value]) - - self.ax.patches = [] - for i in range(len(polygons_s)): - points = np.vstack((polygons_t[i], polygons_s[i])).T - polygon = Polygon(points) - self.ax.add_patch(polygon) - - self.planningavailable = True - - def draw_lines(self): - """plot lines""" - for polygon in self.ax.patches: - self.ax.draw_artist(polygon) - - for line in self.ax.lines: - self.ax.draw_artist(line) diff --git a/modules/tools/realtime_plot/xyitem.py b/modules/tools/realtime_plot/xyitem.py deleted file mode 100644 index 60d73c7c294..00000000000 --- a/modules/tools/realtime_plot/xyitem.py +++ /dev/null @@ -1,210 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -X Y Item -""" -import math - -import numpy as np -from matplotlib import lines -from matplotlib import patches - - -class Xyitem(object): - """XY item to plot""" - - def __init__(self, ax, windowsize, vehiclelength, title, xlabel, ylabel): - self.ax = ax - self.windowsize = windowsize - self.vehiclelength = vehiclelength - - self.ax.set_title(title) - self.ax.set_xlabel(xlabel, fontsize=10) - self.ax.set_ylabel(ylabel, fontsize=10) - - self.lines = [] - - self.pathstartx = [] - self.pathstarty = [] - - self.carxhist = [] - self.caryhist = [] - - self.targetx = [] - self.targety = [] - - self.pathstartidx = -1 - self.carxyhistidx = -1 - self.carposidx = -1 - self.targethistidx = -1 - - self.axx = float('inf') - self.axy = float('inf') - - self.planningavailable = False - - def reset(self): - """Reset""" - del self.pathstartx[:] - del self.pathstarty[:] - - del self.carxhist[:] - del self.caryhist[:] - - del self.targetx[:] - del self.targety[:] - - self.ax.cla() - - self.pathstartidx = -1 - self.carxyhistidx = -1 - self.carposidx = -1 - self.targethistidx = -1 - - self.axx = float('inf') - self.axy = float('inf') - - self.planningavailable = False - - def new_planning(self, time, x, y): - """new planning""" - self.planningtime = time - self.planningx = x - self.planningy = y - - self.pathstartx.append(x[0]) - self.pathstarty.append(y[0]) - - if self.pathstartidx == -1: - self.ax.plot( - self.pathstartx, - self.pathstarty, - color='red', - marker='*', - ls='None') - self.pathstartidx = len(self.ax.lines) - 1 - self.current_line = lines.Line2D(x, y, color='red', lw=1.5) - self.ax.add_line(self.current_line) - else: - self.ax.lines[self.pathstartidx].set_data(self.pathstartx, - self.pathstarty) - self.current_line.set_data(x, y) - - self.planningavailable = True - - def new_carstatus(self, time, x, y, heading, steer_angle, autodriving): - """new carstatus""" - self.carxhist.append(x) - self.caryhist.append(y) - - angle = math.degrees(heading) - 90 - carcolor = 'red' if autodriving else 'blue' - if self.carxyhistidx == -1: - self.ax.plot(self.carxhist, self.caryhist, color="blue") - self.carxyhistidx = len(self.ax.lines) - 1 - - self.ax.plot( - self.carxhist, - self.caryhist, - marker=(3, 0, angle), - markersize=20, - mfc=carcolor) - self.carposidx = len(self.ax.lines) - 1 - - else: - self.ax.lines[self.carxyhistidx].set_data(self.carxhist, - self.caryhist) - self.ax.lines[self.carposidx].set_data(x, y) - self.ax.lines[self.carposidx].set_marker((3, 0, angle)) - self.ax.lines[self.carposidx].set_mfc(carcolor) - self.ax.patches[0].remove() - - if self.planningavailable: - xtarget = np.interp(time, self.planningtime, self.planningx) - self.targetx.append(xtarget) - ytarget = np.interp(time, self.planningtime, self.planningy) - self.targety.append(ytarget) - - if self.targethistidx == -1: - self.ax.plot(self.targetx, self.targety, color="green", lw=1.5) - self.targethistidx = len(self.ax.lines) - 1 - else: - self.ax.lines[self.targethistidx].set_data( - self.targetx, self.targety) - - self.ax.add_patch(self.gen_steer_curve(x, y, heading, steer_angle)) - # Update Window X, Y Axis Limits - xcenter = x + math.cos(heading) * 40 - ycenter = y + math.sin(heading) * 40 - if xcenter >= (self.axx + 20) or xcenter <= (self.axx - 20) or \ - ycenter >= (self.axy + 20) or ycenter <= (self.axy - 20): - scale = self.ax.get_window_extent( - )._transform._boxout._bbox.get_points()[1] - original = self.ax.get_position().get_points() - finalscale = (original[1] - original[0]) * scale - ratio = finalscale[1] / finalscale[0] - self.axx = xcenter - self.axy = ycenter - self.ax.set_xlim( - [xcenter - self.windowsize, xcenter + self.windowsize]) - self.ax.set_ylim([ - ycenter - self.windowsize * ratio, - ycenter + self.windowsize * ratio - ]) - - def gen_steer_curve(self, x, y, heading, steer_angle): - """Generate Steering Curve to predict car trajectory""" - if abs(math.tan(math.radians(steer_angle))) > 0.0001: - R = self.vehiclelength / math.tan(math.radians(steer_angle)) - else: - R = 100000 - - radius = abs(R) - lengthangle = 7200 / (2 * math.pi * radius) - if R >= 0: - centerangle = math.pi / 2 + heading - startangle = math.degrees(heading - math.pi / 2) - theta1 = 0 - theta2 = lengthangle - else: - centerangle = heading - math.pi / 2 - startangle = math.degrees(math.pi / 2 + heading) - theta1 = -lengthangle - theta2 = 0 - - centerx = x + math.cos(centerangle) * radius - centery = y + math.sin(centerangle) * radius - - curve = patches.Arc( - (centerx, centery), - 2 * radius, - 2 * radius, - angle=startangle, - theta1=theta1, - theta2=theta2, - linewidth=2, - zorder=2) - return curve - - def draw_lines(self): - """plot lines""" - for polygon in self.ax.patches: - self.ax.draw_artist(polygon) - - for line in self.ax.lines: - self.ax.draw_artist(line) diff --git a/modules/tools/record_analyzer/BUILD b/modules/tools/record_analyzer/BUILD deleted file mode 100644 index 31c956a3ada..00000000000 --- a/modules/tools/record_analyzer/BUILD +++ /dev/null @@ -1,79 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -filegroup( - name = "readme", - srcs = [ - "README.md", - ], -) - -py_library( - name = "lidar_endtoend_analyzer", - srcs = ["lidar_endtoend_analyzer.py"], - deps = [ - "//modules/tools/record_analyzer/common:statistical_analyzer", - ], -) - -py_binary( - name = "main", - srcs = ["main.py"], - deps = [ - ":lidar_endtoend_analyzer", - ":module_control_analyzer", - ":module_planning_analyzer", - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/control_msgs:control_cmd_py_pb2", - "//modules/common_msgs/sensor_msgs:pointcloud_py_pb2", - "//modules/common_msgs/perception_msgs:perception_obstacle_py_pb2", - "//modules/common_msgs/planning_msgs:planning_py_pb2", - "//modules/common_msgs/prediction_msgs:prediction_obstacle_py_pb2", - ], -) - -py_library( - name = "module_control_analyzer", - srcs = ["module_control_analyzer.py"], - deps = [ - "//modules/tools/record_analyzer/common:error_code_analyzer", - "//modules/tools/record_analyzer/common:error_msg_analyzer", - "//modules/tools/record_analyzer/common:statistical_analyzer", - ], -) - -py_library( - name = "module_planning_analyzer", - srcs = ["module_planning_analyzer.py"], - deps = [ - "//modules/common_msgs/planning_msgs:planning_py_pb2", - "//modules/tools/record_analyzer/common:distribution_analyzer", - "//modules/tools/record_analyzer/common:error_code_analyzer", - "//modules/tools/record_analyzer/common:error_msg_analyzer", - "//modules/tools/record_analyzer/common:frechet_distance", - "//modules/tools/record_analyzer/common:statistical_analyzer", - "//modules/tools/record_analyzer/metrics:curvature", - "//modules/tools/record_analyzer/metrics:frame_count", - "//modules/tools/record_analyzer/metrics:lat_acceleration", - "//modules/tools/record_analyzer/metrics:latency", - "//modules/tools/record_analyzer/metrics:lon_acceleration", - "//modules/tools/record_analyzer/metrics:reference_line", - ], -) - -install( - name = "install", - data = [":readme"], - data_dest = "tools/record_analyzer", - py_dest = "tools/record_analyzer", - targets = [ - ":main", - ], - deps = [ - "//modules/tools/record_analyzer/tools:install", - "//modules/tools/record_analyzer/common:install", - ] -) \ No newline at end of file diff --git a/modules/tools/record_analyzer/README.md b/modules/tools/record_analyzer/README.md deleted file mode 100644 index e684429e313..00000000000 --- a/modules/tools/record_analyzer/README.md +++ /dev/null @@ -1,41 +0,0 @@ -# Record Analyzer Tool - -## Offline Record files analysis -### Functions - -Record analyzer is a tool for analyzing the .record file created by cyber_recorder tool. - -It currently supports statistical analysis for - * Control module latency - * Planning module latency - * End to end system latency - - And distribution analysis for - * Control error code - * Control error message - * Planning trajectory type - * Planning estop - * Planning error code - * Planning error message - -### Usage - -```bash -python main.py -f record_file -``` - -## Simulation Score API - -### Functions -This API is used for simulation to grade planning trajectories. - -It currently supports following scores: - * frechet_dist: calculate the frechet_dist for two consecutive planning trajectories - * hard_brake_cycle_num: number of planning cycles that acceleration is less than -2.0 m/s^2 - * overall_score: aggregated score for above metrics - -### Usage - -```bash -python main.py -f record_file -s -``` \ No newline at end of file diff --git a/modules/tools/record_analyzer/common/BUILD b/modules/tools/record_analyzer/common/BUILD deleted file mode 100644 index e631cc34d4c..00000000000 --- a/modules/tools/record_analyzer/common/BUILD +++ /dev/null @@ -1,50 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -py_library( - name = "distribution_analyzer", - srcs = ["distribution_analyzer.py"], - deps = [ - ":statistical_analyzer", - ], -) - -py_library( - name = "error_code_analyzer", - srcs = ["error_code_analyzer.py"], - deps = [ - ":distribution_analyzer", - ":statistical_analyzer", - "//modules/common_msgs/basic_msgs:error_code_py_pb2", - ], -) - -py_library( - name = "error_msg_analyzer", - srcs = ["error_msg_analyzer.py"], - deps = [ - ":distribution_analyzer", - ":statistical_analyzer", - "//modules/common_msgs/basic_msgs:error_code_py_pb2", - ], -) - -py_binary( - name = "frechet_distance", - srcs = ["frechet_distance.py"], -) - -py_library( - name = "statistical_analyzer", - srcs = ["statistical_analyzer.py"], -) - -install( - name = "install", - py_dest = "tools/record_analyzer/common", - targets = [ - ":frechet_distance", - ] -) \ No newline at end of file diff --git a/modules/tools/record_analyzer/common/distribution_analyzer.py b/modules/tools/record_analyzer/common/distribution_analyzer.py deleted file mode 100644 index 243a4d007ce..00000000000 --- a/modules/tools/record_analyzer/common/distribution_analyzer.py +++ /dev/null @@ -1,38 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -from modules.tools.record_analyzer.common.statistical_analyzer import PrintColors - - -class DistributionAnalyzer: - """statistical analzer class""" - - def print_distribution_results(self, data): - """distribution analyzer""" - if len(data) == 0: - print(PrintColors.FAIL + "No Data Generated!" + PrintColors.ENDC) - return - - total = 0 - for k, v in data.items(): - total += v - - for k, v in data.items(): - percentage = "{0:.2f}".format((float(v) / total) * 100) - print(PrintColors.OKBLUE + k + " = " + str(v) + - "(" + percentage + "%)" + PrintColors.ENDC) diff --git a/modules/tools/record_analyzer/common/error_code_analyzer.py b/modules/tools/record_analyzer/common/error_code_analyzer.py deleted file mode 100644 index 37a697cf524..00000000000 --- a/modules/tools/record_analyzer/common/error_code_analyzer.py +++ /dev/null @@ -1,42 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -from modules.common_msgs.basic_msgs import error_code_pb2 -from modules.tools.record_analyzer.common.statistical_analyzer import PrintColors -from modules.tools.record_analyzer.common.distribution_analyzer import DistributionAnalyzer - - -class ErrorCodeAnalyzer: - """class""" - - def __init__(self): - """init""" - self.error_code_count = {} - - def put(self, error_code): - """put""" - error_code_name = \ - error_code_pb2.ErrorCode.Name(error_code) - if error_code_name not in self.error_code_count: - self.error_code_count[error_code_name] = 1 - else: - self.error_code_count[error_code_name] += 1 - - def print_results(self): - """print""" - DistributionAnalyzer().print_distribution_results(self.error_code_count) diff --git a/modules/tools/record_analyzer/common/error_msg_analyzer.py b/modules/tools/record_analyzer/common/error_msg_analyzer.py deleted file mode 100644 index 7337008556f..00000000000 --- a/modules/tools/record_analyzer/common/error_msg_analyzer.py +++ /dev/null @@ -1,42 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -from modules.common_msgs.basic_msgs import error_code_pb2 -from modules.tools.record_analyzer.common.statistical_analyzer import PrintColors -from modules.tools.record_analyzer.common.distribution_analyzer import DistributionAnalyzer - - -class ErrorMsgAnalyzer: - """class""" - - def __init__(self): - """init""" - self.error_msg_count = {} - - def put(self, error_msg): - """put""" - if len(error_msg) == 0: - return - if error_msg not in self.error_msg_count: - self.error_msg_count[error_msg] = 1 - else: - self.error_msg_count[error_msg] += 1 - - def print_results(self): - """print""" - DistributionAnalyzer().print_distribution_results(self.error_msg_count) diff --git a/modules/tools/record_analyzer/common/frechet_distance.py b/modules/tools/record_analyzer/common/frechet_distance.py deleted file mode 100644 index 916f683a310..00000000000 --- a/modules/tools/record_analyzer/common/frechet_distance.py +++ /dev/null @@ -1,67 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math - -import numpy as np - - -def euclidean_distance(pt1, pt2): - return math.sqrt((pt2[0] - pt1[0]) * (pt2[0]-pt1[0]) + - (pt2[1] - pt1[1]) * (pt2[1] - pt1[1])) - - -def _c(ca, i, j, P, Q): - if ca[i, j] > -1: - return ca[i, j] - elif i == 0 and j == 0: - ca[i, j] = euclidean_distance(P[0], Q[0]) - elif i > 0 and j == 0: - ca[i, j] = max(_c(ca, i-1, 0, P, Q), euclidean_distance(P[i], Q[0])) - elif i == 0 and j > 0: - ca[i, j] = max(_c(ca, 0, j-1, P, Q), euclidean_distance(P[0], Q[j])) - elif i > 0 and j > 0: - ca[i, j] = max(min(_c(ca, i-1, j, P, Q), - _c(ca, i-1, j-1, P, Q), - _c(ca, i, j-1, P, Q)), - euclidean_distance(P[i], Q[j])) - else: - ca[i, j] = float("inf") - return ca[i, j] - - -def frechet_distance(P, Q): - ca = np.ones((len(P), len(Q))) - ca = np.multiply(ca, -1) - dist = None - try: - dist = _c(ca, len(P)-1, len(Q)-1, P, Q) - except: - print("calculate frechet_distance exception.") - return dist - - -if __name__ == "__main__": - """test""" - P = [[1, 1], [2, 1], [2, 2]] - Q = [[2, 2], [0, 1], [2, 4]] - print(frechet_distance(P, Q)) # 2 - - P = [[1, 1], [2, 1], [2, 2]] - Q = [[1, 1], [2, 1], [2, 2]] - print(frechet_distance(P, Q)) # 0 diff --git a/modules/tools/record_analyzer/common/statistical_analyzer.py b/modules/tools/record_analyzer/common/statistical_analyzer.py deleted file mode 100644 index 948eb1e93ed..00000000000 --- a/modules/tools/record_analyzer/common/statistical_analyzer.py +++ /dev/null @@ -1,75 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import numpy as np - - -class PrintColors: - """ output color schema""" - HEADER = '\033[95m' - OKBLUE = '\033[94m' - OKGREEN = '\033[92m' - WARNING = '\033[93m' - FAIL = '\033[91m' - ENDC = '\033[0m' - BOLD = '\033[1m' - UNDERLINE = '\033[4m' - - -class StatisticalAnalyzer: - """statistical analzer class""" - - def print_statistical_results(self, data): - """ statistical analyzer""" - if len(data) == 0: - print(PrintColors.FAIL + "No Data Generated!" + PrintColors.ENDC) - return - - arr = np.array(data) - - v = np.average(arr) - print(PrintColors.OKBLUE + "Average: \t" + PrintColors.ENDC, - "{0:.2f}".format(v)) - - std = np.std(arr) - print(PrintColors.OKBLUE + "STD: \t\t" + PrintColors.ENDC, - "{0:.2f}".format(std)) - - p = np.percentile(arr, 10) - print(PrintColors.OKBLUE + "10 Percentile: \t" + PrintColors.ENDC, - "{0:.2f}".format(p)) - - p = np.percentile(arr, 50) - print(PrintColors.OKBLUE + "50 Percentile: \t" + PrintColors.ENDC, - "{0:.2f}".format(p)) - - p = np.percentile(arr, 90) - print(PrintColors.OKBLUE + "90 Percentile: \t" + PrintColors.ENDC, - "{0:.2f}".format(p)) - - p = np.percentile(arr, 99) - print(PrintColors.OKBLUE + "99 Percentile: \t" + PrintColors.ENDC, - "{0:.2f}".format(p)) - - p = np.min(arr) - print(PrintColors.OKBLUE + "min: \t" + PrintColors.ENDC, - "{0:.2f}".format(p)) - - p = np.max(arr) - print(PrintColors.OKBLUE + "max: \t" + PrintColors.ENDC, - "{0:.2f}".format(p)) diff --git a/modules/tools/record_analyzer/lidar_endtoend_analyzer.py b/modules/tools/record_analyzer/lidar_endtoend_analyzer.py deleted file mode 100644 index c484fea635f..00000000000 --- a/modules/tools/record_analyzer/lidar_endtoend_analyzer.py +++ /dev/null @@ -1,77 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -from modules.tools.record_analyzer.common.statistical_analyzer import PrintColors -from modules.tools.record_analyzer.common.statistical_analyzer import StatisticalAnalyzer - - -class LidarEndToEndAnalyzer(object): - """ - Control analyzer - """ - - def __init__(self): - """ - Init - """ - self.modules = ['control', 'planning', 'prediction', 'perception'] - self.endtoend_latency = {} - self.unprocessed_lidar_timestamps = {} - for m in self.modules: - self.endtoend_latency[m] = [] - self.unprocessed_lidar_timestamps[m] = [] - - def put_pb(self, module_name, pb_msg): - """ - Put data - """ - if module_name not in self.unprocessed_lidar_timestamps: - print(module_name, " is not supported") - return - - if pb_msg.header.lidar_timestamp in \ - self.unprocessed_lidar_timestamps[module_name]: - ind = self.unprocessed_lidar_timestamps[module_name].index( - pb_msg.header.lidar_timestamp) - del (self.unprocessed_lidar_timestamps[module_name][ind]) - self.endtoend_latency[module_name].append( - (pb_msg.header.timestamp_sec - - pb_msg.header.lidar_timestamp * 1.0e-9) * 1000.0) - - def put_lidar(self, point_cloud): - """ - Put lidar data - """ - for m in self.modules: - self.unprocessed_lidar_timestamps[m].append( - point_cloud.header.lidar_timestamp) - - def print_endtoend_latency(self): - """ - Print end to end latency - """ - print("\n\n") - for m in self.modules: - print(PrintColors.HEADER + "* End to End (" + m - + ") Latency (ms)" + PrintColors.ENDC) - analyzer = StatisticalAnalyzer() - analyzer.print_statistical_results(self.endtoend_latency[m]) - - print(PrintColors.FAIL + " - MISS # OF LIDAR: " + - str(len(self.unprocessed_lidar_timestamps[m])) + - PrintColors.ENDC) diff --git a/modules/tools/record_analyzer/main.py b/modules/tools/record_analyzer/main.py deleted file mode 100644 index 81f9333810a..00000000000 --- a/modules/tools/record_analyzer/main.py +++ /dev/null @@ -1,150 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import argparse -import sys - -import matplotlib.pyplot as plt - -from cyber.python.cyber_py3.record import RecordReader -from modules.tools.record_analyzer.lidar_endtoend_analyzer import LidarEndToEndAnalyzer -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.control_msgs import control_cmd_pb2 -from modules.common_msgs.sensor_msgs import pointcloud_pb2 -from modules.common_msgs.perception_msgs import perception_obstacle_pb2 -from modules.common_msgs.planning_msgs import planning_pb2 -from modules.common_msgs.prediction_msgs import prediction_obstacle_pb2 -from modules.tools.record_analyzer.module_control_analyzer import ControlAnalyzer -from modules.tools.record_analyzer.module_planning_analyzer import PlannigAnalyzer - - -def process(control_analyzer, planning_analyzer, lidar_endtoend_analyzer, - is_simulation, plot_planning_path, plot_planning_refpath, all_data): - is_auto_drive = False - - for msg in reader.read_messages(): - if msg.topic == "/apollo/canbus/chassis": - chassis = chassis_pb2.Chassis() - chassis.ParseFromString(msg.message) - if chassis.driving_mode == \ - chassis_pb2.Chassis.COMPLETE_AUTO_DRIVE: - is_auto_drive = True - else: - is_auto_drive = False - - if msg.topic == "/apollo/control": - if (not is_auto_drive and not all_data) or \ - is_simulation or plot_planning_path or plot_planning_refpath: - continue - control_cmd = control_cmd_pb2.ControlCommand() - control_cmd.ParseFromString(msg.message) - control_analyzer.put(control_cmd) - lidar_endtoend_analyzer.put_pb('control', control_cmd) - - if msg.topic == "/apollo/planning": - if (not is_auto_drive) and (not all_data): - continue - adc_trajectory = planning_pb2.ADCTrajectory() - adc_trajectory.ParseFromString(msg.message) - planning_analyzer.put(adc_trajectory) - lidar_endtoend_analyzer.put_pb('planning', adc_trajectory) - - if plot_planning_path: - planning_analyzer.plot_path(plt, adc_trajectory) - if plot_planning_refpath: - planning_analyzer.plot_refpath(plt, adc_trajectory) - - if msg.topic == "/apollo/sensor/velodyne64/compensator/PointCloud2" or \ - msg.topic == "/apollo/sensor/lidar128/compensator/PointCloud2": - if ((not is_auto_drive) and (not all_data)) or is_simulation or \ - plot_planning_path or plot_planning_refpath: - continue - point_cloud = pointcloud_pb2.PointCloud() - point_cloud.ParseFromString(msg.message) - lidar_endtoend_analyzer.put_lidar(point_cloud) - - if msg.topic == "/apollo/perception/obstacles": - if ((not is_auto_drive) and (not all_data)) or is_simulation or \ - plot_planning_path or plot_planning_refpath: - continue - perception = perception_obstacle_pb2.PerceptionObstacles() - perception.ParseFromString(msg.message) - lidar_endtoend_analyzer.put_pb('perception', perception) - - if msg.topic == "/apollo/prediction": - if ((not is_auto_drive) and (not all_data)) or is_simulation or \ - plot_planning_path or plot_planning_refpath: - continue - prediction = prediction_obstacle_pb2.PredictionObstacles() - prediction.ParseFromString(msg.message) - lidar_endtoend_analyzer.put_pb('prediction', prediction) - - -if __name__ == "__main__": - if len(sys.argv) < 2: - print("usage: python main.py record_file") - parser = argparse.ArgumentParser( - description="Recode Analyzer is a tool to analyze record files.", - prog="main.py") - - parser.add_argument( - "-f", "--file", action="store", type=str, required=True, - help="Specify the record file for analysis.") - - parser.add_argument( - "-sim", "--simulation", action="store_const", const=True, - help="For dreamland API call") - - parser.add_argument( - "-path", "--planningpath", action="store_const", const=True, - help="plot planing paths in cartesian coordinate.") - - parser.add_argument( - "-refpath", "--planningrefpath", action="store_const", const=True, - help="plot planing reference paths in cartesian coordinate.") - - parser.add_argument( - "-a", "--alldata", action="store_const", const=True, - help="Analyze all data (both auto and manual), otherwise auto data only without this option.") - - parser.add_argument( - "-acc", "--showacc", action="store_const", const=True, - help="Analyze all data (both auto and manual), otherwise auto data only without this option.") - - args = parser.parse_args() - - record_file = args.file - reader = RecordReader(record_file) - - control_analyzer = ControlAnalyzer() - planning_analyzer = PlannigAnalyzer(args) - lidar_endtoend_analyzer = LidarEndToEndAnalyzer() - - process(control_analyzer, planning_analyzer, - lidar_endtoend_analyzer, args.simulation, args.planningpath, - args.planningrefpath, args.alldata) - - if args.simulation: - planning_analyzer.print_sim_results() - elif args.planningpath or args.planningrefpath: - plt.axis('equal') - plt.show() - else: - control_analyzer.print_latency_statistics() - planning_analyzer.print_latency_statistics() - lidar_endtoend_analyzer.print_endtoend_latency() diff --git a/modules/tools/record_analyzer/metrics/BUILD b/modules/tools/record_analyzer/metrics/BUILD deleted file mode 100644 index bd6fa886bad..00000000000 --- a/modules/tools/record_analyzer/metrics/BUILD +++ /dev/null @@ -1,33 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_library") - -package(default_visibility = ["//visibility:public"]) - -py_library( - name = "curvature", - srcs = ["curvature.py"], -) - -py_library( - name = "frame_count", - srcs = ["frame_count.py"], -) - -py_library( - name = "lat_acceleration", - srcs = ["lat_acceleration.py"], -) - -py_library( - name = "latency", - srcs = ["latency.py"], -) - -py_library( - name = "lon_acceleration", - srcs = ["lon_acceleration.py"], -) - -py_library( - name = "reference_line", - srcs = ["reference_line.py"], -) diff --git a/modules/tools/record_analyzer/metrics/curvature.py b/modules/tools/record_analyzer/metrics/curvature.py deleted file mode 100644 index 75e4dbc6810..00000000000 --- a/modules/tools/record_analyzer/metrics/curvature.py +++ /dev/null @@ -1,53 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import numpy as np - - -class Curvature: - def __init__(self): - self.curvature_list = [] - self.curvature_derivative_list = [] - - def put(self, adc_trajectory): - init_point = adc_trajectory.debug.planning_data.init_point - self.curvature_list.append(abs(init_point.path_point.kappa)) - self.curvature_derivative_list.append(abs(init_point.path_point.dkappa)) - - def get_curvature(self): - curvature = {} - if len(self.curvature_list) == 0: - curvature["max"] = 0 - curvature["avg"] = 0 - return curvature - - curvature["max"] = max(self.curvature_list, key=abs) - curvature["avg"] = np.average(np.absolute(self.curvature_list)) - - return curvature - - def get_curvature_derivative(self): - curvature_derivative = {} - if len(self.curvature_derivative_list) == 0: - curvature_derivative["max"] = 0 - curvature_derivative["avg"] = 0 - - curvature_derivative["max"] = max(self.curvature_derivative_list, key=abs) - curvature_derivative["avg"] = np.average(np.absolute(self.curvature_derivative_list)) - - return curvature_derivative diff --git a/modules/tools/record_analyzer/metrics/frame_count.py b/modules/tools/record_analyzer/metrics/frame_count.py deleted file mode 100644 index 3dc661a6e27..00000000000 --- a/modules/tools/record_analyzer/metrics/frame_count.py +++ /dev/null @@ -1,30 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - - -class FrameCount: - def __init__(self): - self.count = 0 - - def put(self, adc_trajectory): - self.count += 1 - - def get(self): - frame_count = {} - frame_count["total"] = self.count - return frame_count diff --git a/modules/tools/record_analyzer/metrics/lat_acceleration.py b/modules/tools/record_analyzer/metrics/lat_acceleration.py deleted file mode 100644 index bdd3350e6cc..00000000000 --- a/modules/tools/record_analyzer/metrics/lat_acceleration.py +++ /dev/null @@ -1,113 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math - -import numpy as np - - -class LatAcceleration: - def __init__(self): - self.centripetal_accel_list = [] - self.centripetal_jerk_list = [] - - def put(self, adc_trajectory): - init_point = adc_trajectory.debug.planning_data.init_point - # centripetal_jerk - centripetal_jerk = 2 * init_point.v * init_point.a \ - * init_point.path_point.kappa + init_point.v \ - * init_point.v * init_point.path_point.dkappa - if not math.isnan(centripetal_jerk): - self.centripetal_jerk_list.append(centripetal_jerk) - - # centripetal_accel - centripetal_accel = init_point.v * init_point.v \ - * init_point.path_point.kappa - - if not math.isnan(centripetal_accel): - self.centripetal_accel_list.append(centripetal_accel) - - def get_acceleration(self): - # [1, 2) [-2, -1) - LAT_ACCEL_M_LB_P = 1 - LAT_ACCEL_M_UB_P = 2 - LAT_ACCEL_M_LB_N = -2 - LAT_ACCEL_M_UB_N = -1 - lat_accel_medium_cnt = 0 - - # [2, inf) [-inf,-2) - LAT_ACCEL_H_LB_P = 2 - LAT_ACCEL_H_UB_N = -2 - lat_accel_high_cnt = 0 - - for centripetal_accel in self.centripetal_accel_list: - if LAT_ACCEL_M_LB_P <= centripetal_accel < LAT_ACCEL_M_UB_P \ - or LAT_ACCEL_M_LB_N < centripetal_accel <= LAT_ACCEL_M_UB_N: - lat_accel_medium_cnt += 1 - if centripetal_accel >= LAT_ACCEL_H_LB_P \ - or centripetal_accel <= LAT_ACCEL_H_UB_N: - lat_accel_high_cnt += 1 - - # centripetal_accel - lat_accel = {} - if len(self.centripetal_accel_list) > 0: - lat_accel["max"] = abs(max(self.centripetal_accel_list, key=abs)) - accel_avg = np.average(np.absolute(self.centripetal_accel_list)) - lat_accel["avg"] = accel_avg - else: - lat_accel["max"] = 0 - lat_accel["avg"] = 0 - lat_accel["medium_cnt"] = lat_accel_medium_cnt - lat_accel["high_cnt"] = lat_accel_high_cnt - - return lat_accel - - def get_jerk(self): - # [0.5,1) [-1, -0.5) - LAT_JERK_M_LB_P = 0.5 - LAT_JERK_M_UB_P = 1 - LAT_JERK_M_LB_N = -1 - LAT_JERK_M_UB_N = -0.5 - lat_jerk_medium_cnt = 0 - - # [1, inf) [-inf,-1) - LAT_JERK_H_LB_P = 1 - LAT_JERK_H_UB_N = -1 - lat_jerk_high_cnt = 0 - - for centripetal_jerk in self.centripetal_jerk_list: - if LAT_JERK_M_LB_P <= centripetal_jerk < LAT_JERK_M_UB_P \ - or LAT_JERK_M_LB_N < centripetal_jerk <= LAT_JERK_M_UB_N: - lat_jerk_medium_cnt += 1 - if centripetal_jerk >= LAT_JERK_H_LB_P \ - or centripetal_jerk <= LAT_JERK_H_UB_N: - lat_jerk_high_cnt += 1 - - # centripetal_jerk - lat_jerk = {} - if len(self.centripetal_jerk_list) > 0: - lat_jerk["max"] = abs(max(self.centripetal_jerk_list, key=abs)) - jerk_avg = np.average(np.absolute(self.centripetal_jerk_list)) - lat_jerk["avg"] = jerk_avg - else: - lat_jerk["max"] = 0 - lat_jerk["avg"] = 0 - lat_jerk["medium_cnt"] = lat_jerk_medium_cnt - lat_jerk["high_cnt"] = lat_jerk_high_cnt - - return lat_jerk diff --git a/modules/tools/record_analyzer/metrics/latency.py b/modules/tools/record_analyzer/metrics/latency.py deleted file mode 100644 index 91b639108d0..00000000000 --- a/modules/tools/record_analyzer/metrics/latency.py +++ /dev/null @@ -1,42 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import numpy as np - - -class Latency: - def __init__(self): - self.latency_list = [] - - def put(self, adc_trajectory): - self.latency_list.append(adc_trajectory.latency_stats.total_time_ms) - - def get(self): - if len(self.latency_list) > 0: - planning_latency = { - "max": max(self.latency_list), - "min": min(self.latency_list), - "avg": np.average(self.latency_list) - } - else: - planning_latency = { - "max": 0.0, - "min": 0.0, - "avg": 0.0 - } - return planning_latency diff --git a/modules/tools/record_analyzer/metrics/lon_acceleration.py b/modules/tools/record_analyzer/metrics/lon_acceleration.py deleted file mode 100644 index 46a2cf2fae5..00000000000 --- a/modules/tools/record_analyzer/metrics/lon_acceleration.py +++ /dev/null @@ -1,189 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import math -import numpy as np - - -class LonAcceleration: - def __init__(self): - self.last_velocity = None - self.last_velocity_timestamp = None - self.last_acceleration = None - self.last_acceleration_timestamp = None - self.acceleration_list = [] - self.deceleration_list = [] - self.acc_jerk_list = [] - self.dec_jerk_list = [] - - def put(self, adc_trajectory): - init_point = adc_trajectory.debug.planning_data.init_point - current_velocity_timestamp = adc_trajectory.header.timestamp_sec + \ - init_point.relative_time - current_velocity = init_point.v - - if self.last_velocity_timestamp is not None and self.last_velocity is not None: - # acceleration - duration = current_velocity_timestamp - self.last_velocity_timestamp - if duration > 0.03: - current_acceleration = ( - current_velocity - self.last_velocity) / duration - if current_acceleration > 0 and not math.isnan(current_acceleration): - self.acceleration_list.append(current_acceleration) - elif current_acceleration < 0 and not math.isnan(current_acceleration): - self.deceleration_list.append(current_acceleration) - - if self.last_acceleration is not None and self.last_acceleration_timestamp is not None: - # jerk - acc_duration = current_velocity_timestamp - self.last_acceleration_timestamp - if acc_duration > 0.03: - current_jerk = (current_acceleration - - self.last_acceleration) / acc_duration - if current_acceleration > 0 and not math.isnan(current_jerk): - self.acc_jerk_list.append(current_jerk) - elif current_acceleration < 0 and not math.isnan(current_jerk): - self.dec_jerk_list.append(current_jerk) - - self.last_acceleration = current_acceleration - self.last_acceleration_timestamp = current_velocity_timestamp - - self.last_velocity_timestamp = current_velocity_timestamp - self.last_velocity = current_velocity - - def get_acceleration(self): - # [2, 4) unit m/s^2 - ACCEL_M_LB = 2 - ACCEL_M_UB = 4 - accel_medium_cnt = 0 - - # [4, ) unit m/s^2 - ACCEL_H_LB = 4 - accel_high_cnt = 0 - - lon_acceleration = {} - for accel in self.acceleration_list: - if ACCEL_M_LB <= accel < ACCEL_M_UB: - accel_medium_cnt += 1 - if ACCEL_H_LB <= accel: - accel_high_cnt += 1 - - if len(self.acceleration_list) > 0: - lon_acceleration["max"] = max(self.acceleration_list) - lon_acceleration["avg"] = np.average(self.acceleration_list) - else: - lon_acceleration["max"] = 0.0 - lon_acceleration["avg"] = 0.0 - lon_acceleration["medium_cnt"] = accel_medium_cnt - lon_acceleration["high_cnt"] = accel_high_cnt - - return lon_acceleration - - def get_deceleration(self): - # [-4, -2) - DECEL_M_LB = -4 - DECEL_M_UB = -2 - decel_medium_cnt = 0 - - # [-4, ) - DECEL_H_UB = -4 - decel_high_cnt = 0 - - for accel in self.deceleration_list: - if DECEL_M_LB < accel <= DECEL_M_UB: - decel_medium_cnt += 1 - if accel <= DECEL_H_UB: - decel_high_cnt += 1 - - lon_deceleration = {} - if len(self.deceleration_list) > 0: - lon_deceleration["max"] = abs(max(self.deceleration_list, key=abs)) - lon_deceleration["avg"] = np.average( - np.absolute(self.deceleration_list)) - else: - lon_deceleration["max"] = 0.0 - lon_deceleration["avg"] = 0.0 - lon_deceleration["medium_cnt"] = decel_medium_cnt - lon_deceleration["high_cnt"] = decel_high_cnt - - return lon_deceleration - - def get_acc_jerk(self): - # [1,2) (-2, -1] - JERK_M_LB_P = 1 - JERK_M_UB_P = 2 - JERK_M_LB_N = -2 - JERK_M_UB_N = -1 - jerk_medium_cnt = 0 - - # [2, inf) (-inf, -2] - JERK_H_LB_P = 2 - JERK_H_UB_N = -2 - jerk_high_cnt = 0 - - for jerk in self.acc_jerk_list: - if JERK_M_LB_P <= jerk < JERK_M_UB_P or \ - JERK_M_LB_N < jerk <= JERK_M_UB_N: - jerk_medium_cnt += 1 - if jerk >= JERK_H_LB_P or jerk <= JERK_H_UB_N: - jerk_high_cnt += 1 - - lon_acc_jerk = {} - if len(self.acc_jerk_list) > 0: - lon_acc_jerk["max"] = abs(max(self.acc_jerk_list, key=abs)) - jerk_avg = np.average(np.absolute(self.acc_jerk_list)) - lon_acc_jerk["avg"] = jerk_avg - else: - lon_acc_jerk["max"] = 0 - lon_acc_jerk["avg"] = 0 - lon_acc_jerk["medium_cnt"] = jerk_medium_cnt - lon_acc_jerk["high_cnt"] = jerk_high_cnt - - return lon_acc_jerk - - def get_dec_jerk(self): - # [1,2) (-2, -1] - JERK_M_LB_P = 1 - JERK_M_UB_P = 2 - JERK_M_LB_N = -2 - JERK_M_UB_N = -1 - jerk_medium_cnt = 0 - - # [2, inf) (-inf, -2] - JERK_H_LB_P = 2 - JERK_H_UB_N = -2 - jerk_high_cnt = 0 - - for jerk in self.dec_jerk_list: - if JERK_M_LB_P <= jerk < JERK_M_UB_P or \ - JERK_M_LB_N < jerk <= JERK_M_UB_N: - jerk_medium_cnt += 1 - if jerk >= JERK_H_LB_P or jerk <= JERK_H_UB_N: - jerk_high_cnt += 1 - - lon_dec_jerk = {} - if len(self.dec_jerk_list) > 0: - lon_dec_jerk["max"] = abs(max(self.dec_jerk_list, key=abs)) - jerk_avg = np.average(np.absolute(self.dec_jerk_list)) - lon_dec_jerk["avg"] = jerk_avg - else: - lon_dec_jerk["max"] = 0 - lon_dec_jerk["avg"] = 0 - lon_dec_jerk["medium_cnt"] = jerk_medium_cnt - lon_dec_jerk["high_cnt"] = jerk_high_cnt - - return lon_dec_jerk diff --git a/modules/tools/record_analyzer/metrics/reference_line.py b/modules/tools/record_analyzer/metrics/reference_line.py deleted file mode 100644 index a606d36f320..00000000000 --- a/modules/tools/record_analyzer/metrics/reference_line.py +++ /dev/null @@ -1,78 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import sys - -import numpy as np - - -class ReferenceLine: - - def __init__(self): - self.rl_is_offroad_cnt = 0 - self.rl_minimum_boundary = sys.float_info.max - self.rl_kappa_rms_list = [] - self.rl_dkappa_rms_list = [] - self.rl_kappa_max_abs_list = [] - self.rl_dkappa_max_abs_list = [] - - def put(self, adc_trajectory): - for ref_line_debug in adc_trajectory.debug.planning_data.reference_line: - if ref_line_debug.HasField("is_offroad") and ref_line_debug.is_offroad: - self.rl_is_offroad_cnt += 1 - if ref_line_debug.HasField("minimum_boundary") and \ - ref_line_debug.minimum_boundary < self.rl_minimum_boundary: - self.rl_minimum_boundary = ref_line_debug.minimum_boundary - if ref_line_debug.HasField("kappa_rms"): - self.rl_kappa_rms_list.append(ref_line_debug.kappa_rms) - if ref_line_debug.HasField("dkappa_rms"): - self.rl_dkappa_rms_list.append(ref_line_debug.dkappa_rms) - if ref_line_debug.HasField("kappa_max_abs"): - self.rl_kappa_max_abs_list.append(ref_line_debug.kappa_max_abs) - if ref_line_debug.HasField("dkappa_max_abs"): - self.rl_dkappa_max_abs_list.append(ref_line_debug.dkappa_max_abs) - - def get(self): - kappa_rms = 0 - if len(self.rl_kappa_rms_list) > 0: - kappa_rms = np.average(self.rl_kappa_rms_list) - - dkappa_rms = 0 - if len(self.rl_dkappa_rms_list) > 0: - dkappa_rms = np.average(self.rl_dkappa_rms_list) - - if self.rl_minimum_boundary > 999: - self.rl_minimum_boundary = 0 - - kappa_max_abs = 0 - if len(self.rl_kappa_max_abs_list) > 0: - kappa_max_abs = max(self.rl_kappa_max_abs_list) - - dkappa_max_abs = 0 - if len(self.rl_dkappa_max_abs_list) > 0: - dkappa_max_abs = max(self.rl_dkappa_max_abs_list) - - reference_line = { - "is_offroad": self.rl_is_offroad_cnt, - "minimum_boundary": self.rl_minimum_boundary, - "kappa_rms": kappa_rms, - "dkappa_rms": dkappa_rms, - "kappa_max_abs": kappa_max_abs, - "dkappa_max_abs": dkappa_max_abs - } - return reference_line diff --git a/modules/tools/record_analyzer/module_control_analyzer.py b/modules/tools/record_analyzer/module_control_analyzer.py deleted file mode 100644 index d8147418dc8..00000000000 --- a/modules/tools/record_analyzer/module_control_analyzer.py +++ /dev/null @@ -1,80 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -from modules.tools.record_analyzer.common.error_code_analyzer import ErrorCodeAnalyzer -from modules.tools.record_analyzer.common.error_msg_analyzer import ErrorMsgAnalyzer -from modules.tools.record_analyzer.common.statistical_analyzer import PrintColors -from modules.tools.record_analyzer.common.statistical_analyzer import StatisticalAnalyzer - -class ControlAnalyzer: - """control analyzer""" - - def __init__(self): - """init""" - self.module_latency = [] - self.error_code_analyzer = ErrorCodeAnalyzer() - self.error_msg_analyzer = ErrorMsgAnalyzer() - self.lon_station_error = [] - self.lon_speed_error = [] - self.lat_lateral_error = [] - self.lat_heading_error = [] - - def put(self, control_cmd): - """put data""" - latency = control_cmd.latency_stats.total_time_ms - self.module_latency.append(latency) - self.error_code_analyzer.put(control_cmd.header.status.error_code) - self.error_msg_analyzer.put(control_cmd.header.status.msg) - lon_debug = control_cmd.debug.simple_lon_debug - self.lon_station_error.append(lon_debug.station_error) - self.lon_speed_error.append(lon_debug.speed_error) - lat_debug = control_cmd.debug.simple_lat_debug - self.lat_lateral_error.append(lat_debug.lateral_error) - self.lat_heading_error.append(lat_debug.heading_error) - - def print_latency_statistics(self): - """print_latency_statistics""" - print("\n\n") - print(PrintColors.HEADER + "--- Control Latency (ms) ---" + - PrintColors.ENDC) - analyzer = StatisticalAnalyzer() - analyzer.print_statistical_results(self.module_latency) - - print(PrintColors.HEADER + "--- station error ---" + - PrintColors.ENDC) - analyzer.print_statistical_results(self.lon_station_error) - - print(PrintColors.HEADER + "--- speed error ---" + - PrintColors.ENDC) - analyzer.print_statistical_results(self.lon_speed_error) - - print(PrintColors.HEADER + "--- lateral error ---" + - PrintColors.ENDC) - analyzer.print_statistical_results(self.lat_lateral_error) - - print(PrintColors.HEADER + "--- heading error ---" + - PrintColors.ENDC) - analyzer.print_statistical_results(self.lat_heading_error) - - print(PrintColors.HEADER + "--- Control Error Code Distribution ---" + - PrintColors.ENDC) - self.error_code_analyzer.print_results() - - print(PrintColors.HEADER + "--- Control Error Msg Distribution ---" + - PrintColors.ENDC) - self.error_msg_analyzer.print_results() diff --git a/modules/tools/record_analyzer/module_planning_analyzer.py b/modules/tools/record_analyzer/module_planning_analyzer.py deleted file mode 100644 index 141f9be1aa3..00000000000 --- a/modules/tools/record_analyzer/module_planning_analyzer.py +++ /dev/null @@ -1,249 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import json -import sys - -import numpy as np - -from modules.tools.record_analyzer.common.distribution_analyzer import DistributionAnalyzer -from modules.tools.record_analyzer.common.error_code_analyzer import ErrorCodeAnalyzer -from modules.tools.record_analyzer.common.error_msg_analyzer import ErrorMsgAnalyzer -from modules.tools.record_analyzer.common.frechet_distance import frechet_distance -from modules.tools.record_analyzer.common.statistical_analyzer import PrintColors -from modules.tools.record_analyzer.common.statistical_analyzer import StatisticalAnalyzer -from modules.tools.record_analyzer.metrics.curvature import Curvature -from modules.tools.record_analyzer.metrics.frame_count import FrameCount -from modules.tools.record_analyzer.metrics.latency import Latency -from modules.tools.record_analyzer.metrics.lat_acceleration import LatAcceleration -from modules.tools.record_analyzer.metrics.lon_acceleration import LonAcceleration -from modules.tools.record_analyzer.metrics.reference_line import ReferenceLine -from modules.common_msgs.planning_msgs import planning_pb2 -from shapely.geometry import LineString, Point - - -class PlannigAnalyzer: - """planning analyzer""" - - def __init__(self, arguments): - """init""" - self.module_latency = [] - self.trajectory_type_dist = {} - self.estop_reason_dist = {} - self.error_code_analyzer = ErrorCodeAnalyzer() - self.error_msg_analyzer = ErrorMsgAnalyzer() - self.last_adc_trajectory = None - self.frechet_distance_list = [] - self.is_sim = arguments.simulation - self.hard_break_list = [] - self.total_cycle_num = 0 - - self.curvature_analyzer = Curvature() - self.frame_count_analyzer = FrameCount() - self.lat_acceleration_analyzer = LatAcceleration() - self.lon_acceleration_analyzer = LonAcceleration() - self.latency_analyzer = Latency() - self.reference_line = ReferenceLine() - - self.bag_start_time_t = None - self.print_acc = arguments.showacc - - def put(self, adc_trajectory): - self.total_cycle_num += 1 - if not self.is_sim: - latency = adc_trajectory.latency_stats.total_time_ms - self.module_latency.append(latency) - - self.error_code_analyzer.put( - adc_trajectory.header.status.error_code) - self.error_msg_analyzer.put(adc_trajectory.header.status.msg) - - traj_type = planning_pb2.ADCTrajectory.TrajectoryType.Name( - adc_trajectory.trajectory_type) - self.trajectory_type_dist[traj_type] = \ - self.trajectory_type_dist.get(traj_type, 0) + 1 - - if adc_trajectory.estop.is_estop: - self.estop_reason_dist[adc_trajectory.estop.reason] = \ - self.estop_reason_dist.get( - adc_trajectory.estop.reason, 0) + 1 - - else: - self.curvature_analyzer.put(adc_trajectory) - self.frame_count_analyzer.put(adc_trajectory) - self.lat_acceleration_analyzer.put(adc_trajectory) - self.lon_acceleration_analyzer.put(adc_trajectory) - self.latency_analyzer.put(adc_trajectory) - self.reference_line.put(adc_trajectory) - - def find_common_path(self, current_adc_trajectory, last_adc_trajectory): - current_path_points = current_adc_trajectory.trajectory_point - last_path_points = last_adc_trajectory.trajectory_point - - current_path = [] - for point in current_path_points: - current_path.append([point.path_point.x, point.path_point.y]) - if point.path_point.s > 5.0: - break - last_path = [] - for point in last_path_points: - last_path.append([point.path_point.x, point.path_point.y]) - if point.path_point.s > 5.0: - break - - if len(current_path) == 0 or len(last_path) == 0: - return [], [] - - current_ls = LineString(current_path) - last_ls = LineString(last_path) - current_start_point = Point(current_path[0]) - - dist = last_ls.project(current_start_point) - cut_lines = self.cut(last_ls, dist) - if len(cut_lines) == 1: - return [], [] - last_ls = cut_lines[1] - dist = current_ls.project(Point(last_path[-1])) - if dist <= current_ls.length: - current_ls = self.cut(current_ls, dist)[0] - else: - dist = last_ls.project(Point(current_path[-1])) - last_ls = self.cut(last_ls, dist)[0] - return current_ls.coords, last_ls.coords - - def cut(self, line, distance): - if distance <= 0.0 or distance >= line.length: - return [LineString(line)] - coords = list(line.coords) - for i, p in enumerate(coords): - pd = line.project(Point(p)) - if pd == distance: - return [ - LineString(coords[:i+1]), - LineString(coords[i:])] - if pd > distance: - cp = line.interpolate(distance) - return [ - LineString(coords[:i] + [(cp.x, cp.y)]), - LineString([(cp.x, cp.y)] + coords[i:])] - - def print_latency_statistics(self): - """print_latency_statistics""" - print("\n\n") - print(PrintColors.HEADER + "--- Planning Latency (ms) ---" + - PrintColors.ENDC) - StatisticalAnalyzer().print_statistical_results(self.module_latency) - - print(PrintColors.HEADER + "--- Planning Trajectroy Type Distribution" - " ---" + PrintColors.ENDC) - DistributionAnalyzer().print_distribution_results( - self.trajectory_type_dist) - - print(PrintColors.HEADER + "--- Planning Estop Distribution" - " ---" + PrintColors.ENDC) - DistributionAnalyzer().print_distribution_results( - self.estop_reason_dist) - - print(PrintColors.HEADER + "--- Planning Error Code Distribution---" + - PrintColors.ENDC) - self.error_code_analyzer.print_results() - print(PrintColors.HEADER + "--- Planning Error Msg Distribution ---" + - PrintColors.ENDC) - self.error_msg_analyzer.print_results() - - print(PrintColors.HEADER + "--- Planning Trajectory Frechet Distance (m) ---" + - PrintColors.ENDC) - StatisticalAnalyzer().print_statistical_results(self.frechet_distance_list) - - def print_sim_results(self): - """ - dreamland metrics for planning v2 - """ - v2_results = {} - - # acceleration - v2_results["accel"] = self.lon_acceleration_analyzer.get_acceleration() - - # deceleration - v2_results["decel"] = self.lon_acceleration_analyzer.get_deceleration() - - # jerk - v2_results["acc_jerk"] = self.lon_acceleration_analyzer.get_acc_jerk() - v2_results["dec_jerk"] = self.lon_acceleration_analyzer.get_dec_jerk() - - # centripetal_jerk - v2_results["lat_jerk"] = self.lat_acceleration_analyzer.get_jerk() - - # centripetal_accel - v2_results["lat_accel"] = self.lat_acceleration_analyzer.get_acceleration() - - # frame_count - v2_results["frame_count"] = self.frame_count_analyzer.get() - - # latency - v2_results["planning_latency"] = self.latency_analyzer.get() - - # reference line - v2_results["reference_line"] = self.reference_line.get() - - # output final reuslts - print(json.dumps(v2_results)) - - def plot_path(self, plt, adc_trajectory): - path_coords = self.trim_path_by_distance(adc_trajectory, 5.0) - x = [] - y = [] - for point in path_coords: - x.append(point[0]) - y.append(point[1]) - plt.plot(x, y, 'r-', alpha=0.5) - - def plot_refpath(self, plt, adc_trajectory): - for path in adc_trajectory.debug.planning_data.path: - if path.name != 'planning_reference_line': - continue - path_coords = self.trim_path_by_distance(adc_trajectory, 5.0) - - ref_path_coord = [] - for point in path.path_point: - ref_path_coord.append([point.x, point.y]) - ref_path = LineString(ref_path_coord) - - start_point = Point(path_coords[0]) - dist = ref_path.project(start_point) - ref_path = self.cut(ref_path, dist)[1] - - end_point = Point(path_coords[-1]) - dist = ref_path.project(end_point) - ref_path = self.cut(ref_path, dist)[0] - - x = [] - y = [] - for point in ref_path.coords: - x.append(point[0]) - y.append(point[1]) - - plt.plot(x, y, 'b--', alpha=0.5) - - def trim_path_by_distance(self, adc_trajectory, s): - path_coords = [] - path_points = adc_trajectory.trajectory_point - for point in path_points: - if point.path_point.s <= s: - path_coords.append([point.path_point.x, point.path_point.y]) - return path_coords diff --git a/modules/tools/record_analyzer/tools/BUILD b/modules/tools/record_analyzer/tools/BUILD deleted file mode 100644 index f0261937291..00000000000 --- a/modules/tools/record_analyzer/tools/BUILD +++ /dev/null @@ -1,36 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -py_binary( - name = "dump_message", - srcs = ["dump_message.py"], - deps = [ - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/control_msgs:control_cmd_py_pb2", - "//modules/common_msgs/sensor_msgs:pointcloud_py_pb2", - "//modules/common_msgs/perception_msgs:perception_obstacle_py_pb2", - "//modules/common_msgs/planning_msgs:planning_py_pb2", - ], -) - -py_binary( - name = "perception_obstacle_sender", - srcs = ["perception_obstacle_sender.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:cyber_time", - "//modules/common_msgs/perception_msgs:perception_obstacle_py_pb2", - ], -) - -install( - name = "install", - py_dest = "tools/record_analyzer/tools", - targets = [ - ":perception_obstacle_sender", - ":dump_message", - ] -) \ No newline at end of file diff --git a/modules/tools/record_analyzer/tools/dump_message.py b/modules/tools/record_analyzer/tools/dump_message.py deleted file mode 100644 index ef1aba26c67..00000000000 --- a/modules/tools/record_analyzer/tools/dump_message.py +++ /dev/null @@ -1,62 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import argparse -import sys - -from cyber.python.cyber_py3.record import RecordReader -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.control_msgs import control_cmd_pb2 -from modules.common_msgs.sensor_msgs import pointcloud_pb2 -from modules.common_msgs.perception_msgs import perception_obstacle_pb2 -from modules.common_msgs.planning_msgs import planning_pb2 - - -if __name__ == "__main__": - parser = argparse.ArgumentParser( - description="Recode Analyzer is a tool to analyze record files.", - prog="main.py") - - parser.add_argument( - "-f", "--file", action="store", type=str, required=True, - help="Specify the record file for message dumping.") - - parser.add_argument( - "-m", "--message", action="store", type=str, required=True, - help="Specify the message topic for dumping.") - - parser.add_argument( - "-t", "--timestamp", action="store", type=float, required=True, - help="Specify the timestamp for dumping.") - - args = parser.parse_args() - - record_file = args.file - reader = RecordReader(record_file) - - for msg in reader.read_messages(): - timestamp = msg.timestamp / float(1e9) - if msg.topic == args.message and abs(timestamp - args.timestamp) <= 1: - if msg.topic == "/apollo/perception/obstacles": - perception_obstacles = \ - perception_obstacle_pb2.PerceptionObstacles() - perception_obstacles.ParseFromString(msg.message) - with open('perception_obstacles.txt', 'w') as f: - f.write(str(perception_obstacles)) - print(str(perception_obstacles)) - break diff --git a/modules/tools/record_analyzer/tools/perception_obstacle_sender.py b/modules/tools/record_analyzer/tools/perception_obstacle_sender.py deleted file mode 100644 index 316431025a1..00000000000 --- a/modules/tools/record_analyzer/tools/perception_obstacle_sender.py +++ /dev/null @@ -1,70 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -import time -import argparse -import google.protobuf.text_format as text_format -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import cyber_time -from modules.common_msgs.perception_msgs import perception_obstacle_pb2 - - -def update(perception_obstacles): - """update perception obstacles timestamp""" - now = cyber_time.Time.now().to_sec() - perception_obstacles.header.timestamp_sec = now - perception_obstacles.header.lidar_timestamp = \ - (int(now) - int(0.5)) * int(1e9) - - for perception_obstacle in perception_obstacles.perception_obstacle: - perception_obstacle.timestamp = now - 0.5 - for measure in perception_obstacle.measurements: - measure.timestamp = now - 0.5 - return perception_obstacles - - -if __name__ == "__main__": - parser = argparse.ArgumentParser( - description="Recode Analyzer is a tool to analyze record files.", - prog="main.py") - - parser.add_argument( - "-f", "--file", action="store", type=str, required=True, - help="Specify the message file for sending.") - - args = parser.parse_args() - - cyber.init() - node = cyber.Node("perception_obstacle_sender") - perception_pub = node.create_writer( - "/apollo/perception/obstacles", - perception_obstacle_pb2.PerceptionObstacles) - - perception_obstacles = perception_obstacle_pb2.PerceptionObstacles() - with open(args.file, 'r') as f: - text_format.Merge(f.read(), perception_obstacles) - - while not cyber.is_shutdown(): - now = cyber_time.Time.now().to_sec() - perception_obstacles = update(perception_obstacles) - perception_pub.write(perception_obstacles) - sleep_time = 0.1 - (cyber_time.Time.now().to_sec() - now) - if sleep_time > 0: - time.sleep(sleep_time) - - cyber.shutdown() diff --git a/modules/tools/record_parse_save/BUILD b/modules/tools/record_parse_save/BUILD deleted file mode 100644 index 34b404ee6f4..00000000000 --- a/modules/tools/record_parse_save/BUILD +++ /dev/null @@ -1,62 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -filegroup( - name = "config", - srcs = glob(["*.yaml"]) + ["README.md"], -) - -py_library( - name = "parse_camera", - srcs = ["parse_camera.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/sensor_msgs:sensor_image_py_pb2", - ], -) - -py_library( - name = "parse_lidar", - srcs = ["parse_lidar.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/sensor_msgs:pointcloud_py_pb2", - ], -) - -py_library( - name = "parse_radar", - srcs = ["parse_radar.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/sensor_msgs:conti_radar_py_pb2", - ], -) - -py_binary( - name = "record_parse_save", - srcs = ["record_parse_save.py"], - data = [":config"], - deps = [ - ":parse_camera", - ":parse_lidar", - ":parse_radar", - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - ], -) - -install( - name = "install", - data = [":config"], - data_dest = "tools/record_parse_save", - py_dest = "tools/record_parse_save", - targets = [ - ":record_parse_save", - ], -) \ No newline at end of file diff --git a/modules/tools/record_parse_save/README.md b/modules/tools/record_parse_save/README.md deleted file mode 100644 index cab4898c3ea..00000000000 --- a/modules/tools/record_parse_save/README.md +++ /dev/null @@ -1,71 +0,0 @@ -## Apollo cyber-record file parser (Python based) - -#### Introduction - -This tool presents multiple examples of how to parse data from a record file and -save using predefined format. The tool has been built on example provided within -Apollo (`/apollo/cyber/python/examples/`). - -The samples provided here illustrate cases for, parsing data from: - -- lidar: based on - [Velodyne VLS-128](../../../docs/specs/Lidar/VLS_128_Installation_Guide.md) -- radar: based on - [Continental ARS-408-21](../../../docs/specs/Radar/Continental_ARS408-21_Radar_Installation_Guide.md) -- camera: based on - [Leopard Imaging Inc's Camera - LI-USB30-AZ023WDRB](../../../docs/specs/Camera/Leopard_Camera_LI-USB30-AZ023WDR__Installation_Guide.md) - -#### Files and functions: - -The files/functions provided are as follows: - -- [`record_parse_save.py`](./record_parse_save.py): main function that parses - record files from and saves extracted data to specified location -- [`parse_lidar.py`](./parse_lidar.py): function to parse lidar data -- [`parse_radar.py`](./parse_radar.py): function to parse radar data -- [`parse_camera.py`](./parse_camera.py): function to parse camera data -- [`parser_params.yaml`](./parser_params.yaml): YAML file with details of - record-file location, where the output files should be saved and what sensor - data should be parsed along with specific channel-names associated with - particular sensor, it's configuration and it's location. - - list of channels in a record-file can be obtained using - `cyber_recorder info`. For example, to get details on a sample record file - `20190422142705.record.00000` saved at: - `/apollo/data/record_files/2019-04-22-14-27-05/2019-04-22-14-27-05_records/` - enter following at command prompt: - - `cyber_recorder info /apollo/data/record_files/2019-04-22-14-27-05/2019-04-22-14-27-05_records/20190422142705.record.00000` - - The output on screen will look like that presented in the image below: - -![alt text](./images/sample_cyber_info.jpg) - -#### Dependency - -> sudo pip install pyyaml - -#### How-to-use: - -- It is assumed that the user is within Apollo docker environment and has - successfully built it. Please check documentation on - [Build Apollo](../../../docs/howto/how_to_launch_and_run_apollo.md) if - required. -- Modify parameters specified within `parser_params.yaml` to serve your purpose. -- After correct parameters are specified in the YAML file, run parser function - in `/apollo` using: - -`./bazel-bin/modules/tools/record_parse_save/record_parse_save` - -- parsed sensor data will be saved in new folder along with associated capture - or scan timestamps in a text file. - -#### NOTES - -- In the example setup here, parsed data is saved within the parent folder - containing the records-file's folder. Every saved file has associated - timestamp with it. -- All record-files within the folder are parsed. If any record file is corrupt, - the parser will display error message and continue to next record file. -- `radar` data is saved in text files in JSON format for each scan -- `lidar` point-cloud data is saved in text files for each scan -- `camera` images are saved in jpeg file for each capture -- All timestamps are saved in a separate file with `timestamp` suffix, in the - same order in which the parsed files are saved in corresponding folder. diff --git a/modules/tools/record_parse_save/images/sample_cyber_info.jpg b/modules/tools/record_parse_save/images/sample_cyber_info.jpg deleted file mode 100644 index fd3e162e230..00000000000 Binary files a/modules/tools/record_parse_save/images/sample_cyber_info.jpg and /dev/null differ diff --git a/modules/tools/record_parse_save/parse_camera.py b/modules/tools/record_parse_save/parse_camera.py deleted file mode 100644 index 7bc54347c93..00000000000 --- a/modules/tools/record_parse_save/parse_camera.py +++ /dev/null @@ -1,56 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -""" -function to parse camera images from *.record files, created using Apollo-Auto - -parsed data is saved to *.jpeg file, for each capture - -""" - -import os -import sys - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import record -from modules.common_msgs.sensor_msgs.sensor_image_pb2 import CompressedImage - - -def parse_data(channelname, msg, out_folder): - """ - parser images from Apollo record file - """ - msg_camera = CompressedImage() - msg_camera.ParseFromString(msg) - - tstamp = msg_camera.measurement_time - - temp_time = str(tstamp).split('.') - if len(temp_time[1]) == 1: - temp_time1_adj = temp_time[1] + '0' - else: - temp_time1_adj = temp_time[1] - image_time = temp_time[0] + '_' + temp_time1_adj - - image_filename = "image_" + image_time + ".jpeg" - f = open(out_folder + image_filename, 'w+b') - f.write(msg_camera.data) - f.close() - - return tstamp - diff --git a/modules/tools/record_parse_save/parse_lidar.py b/modules/tools/record_parse_save/parse_lidar.py deleted file mode 100644 index 37e48adaaf5..00000000000 --- a/modules/tools/record_parse_save/parse_lidar.py +++ /dev/null @@ -1,65 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -""" -function to parse lidar data from *.record files, created using Apollo-Auto - -parsed data is saved to *.txt file, for each scan - -current implementation for: -* Velodyne VLS-128 lidar - -""" - -import os -import sys - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import record -from modules.common_msgs.sensor_msgs.pointcloud_pb2 import PointCloud - - -def parse_data(channelname, msg, out_folder): - """ - """ - msg_lidar = PointCloud() - msg_lidar.ParseFromString(msg) - nPts = len(msg_lidar.point) - - pcd = [] - for j in range(nPts): - p = msg_lidar.point[j] - pcd.append([p.x, p.y, p.z, p.intensity]) - - tstamp = msg_lidar.measurement_time - temp_time = str(tstamp).split('.') - - if len(temp_time[1]) == 1: - temp_time1_adj = temp_time[1] + '0' - else: - temp_time1_adj = temp_time[1] - - pcd_time = temp_time[0] + '_' + temp_time1_adj - pcd_filename = "pcd_" + pcd_time + ".txt" - - with open(out_folder + pcd_filename, 'w') as outfile: - for item in pcd: - data = str(item)[1:-1] - outfile.write("%s\n" % data) - - return tstamp diff --git a/modules/tools/record_parse_save/parse_radar.py b/modules/tools/record_parse_save/parse_radar.py deleted file mode 100644 index b9a93d3a262..00000000000 --- a/modules/tools/record_parse_save/parse_radar.py +++ /dev/null @@ -1,146 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -""" -function to parse radar data from *.record files, created using Apollo-Auto - -parsed data is saved to *.txt file, for each scan - -currently implementation for: -* Continental ARS-408 radar - -""" - -import json -import os -import sys - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import record -from modules.common_msgs.sensor_msgs.conti_radar_pb2 import ContiRadar - - -class RadarMessageConti408(object): - def __init__(self): - self.radarDetectionList = [] - self.timestamp_sec = None - self.num_of_detections = None - self.radar_module = None - self.sequence_num = None - self.radar_channel = None - self.additional_notes = None - - def toJSON(self): - return json.dumps(self, default=lambda o: o.__dict__, - sort_keys=True, indent=4) - - -class ContiRadarARS408Detection(object): - def __init__(self): - self.clusterortrack = None - self.obstacle_id = None - self.longitude_dist = None - self.lateral_dist = None - self.longitude_vel = None - self.lateral_vel = None - self.rcs = None - self.dynprop = None - self.longitude_dist_rms = None - self.lateral_dist_rms = None - self.longitude_vel_rms = None - self.lateral_vel_rms = None - self.probexist = None - self.meas_state = None - self.longitude_accel = None - self.lateral_accel = None - self.oritation_angle = None - self.longitude_accel_rms = None - self.lateral_accel_rms = None - self.oritation_angle_rms = None - self.length = None - self.width = None - self.obstacle_class = None - - -def pull_conti_radar_detections(obs): - """ - file to convert structure from c++ to python format - """ - - dets = ContiRadarARS408Detection() - - dets.clusterortrack = obs.clusterortrack - dets.obstacle_id = obs.obstacle_id - dets.longitude_dist = obs.longitude_dist - dets.lateral_dist = obs.lateral_dist - dets.longitude_vel = obs.longitude_vel - dets.lateral_vel = obs.lateral_vel - dets.rcs = obs.rcs - dets.dynprop = obs.dynprop - dets.longitude_dist_rms = obs.longitude_dist_rms - dets.lateral_dist_rms = obs.lateral_dist_rms - dets.longitude_vel_rms = obs.longitude_vel_rms - dets.lateral_vel_rms = obs.lateral_vel_rms - dets.probexist = obs.probexist - dets.meas_state = obs.meas_state - dets.longitude_accel = obs.longitude_accel - dets.lateral_accel = obs.lateral_accel - dets.oritation_angle = obs.oritation_angle - dets.longitude_accel_rms = obs.longitude_accel_rms - dets.lateral_accel_rms = obs.lateral_accel_rms - dets.oritation_angle_rms = obs.oritation_angle_rms - dets.length = obs.length - dets.width = obs.width - dets.obstacle_class = obs.obstacle_class - - return dets - -def parse_data(channelname, msg, out_folder): - """ - parser for record-file data from continental ars-408 radar - """ - - msg_contiradar = ContiRadar() - msg_contiradar.ParseFromString(msg) - n = len(msg_contiradar.contiobs) - - detections = [] - radar_msg = RadarMessageConti408() - - head_msg = msg_contiradar.contiobs[0].header - radar_msg.timestamp_sec = head_msg.timestamp_sec - radar_msg.num_of_detections = n - radar_msg.radar_module = head_msg.module_name - radar_msg.sequence_num = head_msg.sequence_num - radar_msg.radar_channel = channelname - - for i in range(len(msg_contiradar.contiobs)): - detections.append(pull_conti_radar_detections(msg_contiradar.contiobs[i])) - - radar_msg.radarDetectionList = detections - - json_data = radar_msg.toJSON() - tstamp = json_data.split()[-2].ljust(20, '0') - - # write this scan to file - scan_filename = "radar_scan_" + tstamp.replace('.', '_') + ".txt" - with open(out_folder + scan_filename, 'w') as outfile: - outfile.write(json_data) - - return tstamp - diff --git a/modules/tools/record_parse_save/parser_params.yaml b/modules/tools/record_parse_save/parser_params.yaml deleted file mode 100644 index 9efa710a6ef..00000000000 --- a/modules/tools/record_parse_save/parser_params.yaml +++ /dev/null @@ -1,23 +0,0 @@ -records: - filepath: /apollo/data/record_files/2019-04-22-14-27-05/2019-04-22-14-27-05_records/ - -parse: radar -# use one of the following options or add more: - # lidar - # radar - # camera - -lidar: # for velodyne vls-128 lidar - channel_name: /apollo/sensor/lidar128/PointCloud2 - out_folder_extn: _lidar_vls128 - timestamp_file_extn: _lidar_vls128_timestamp.txt - -radar: # for ARS-408 radar mounted in front - channel_name: /apollo/sensor/radar/front - out_folder_extn: _radar_conti408_front - timestamp_file_extn: _radar_conti408_front_timestamp.txt - -camera: # for 6mm camera mounted in front - channel_name: /apollo/sensor/camera/front_6mm/image/compressed - out_folder_extn: _camera_6mm_front - timestamp_file_extn: _camera_6mm_front_timestamp.txt diff --git a/modules/tools/record_parse_save/record_parse_save.py b/modules/tools/record_parse_save/record_parse_save.py deleted file mode 100644 index c8274048a87..00000000000 --- a/modules/tools/record_parse_save/record_parse_save.py +++ /dev/null @@ -1,138 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -""" -function to parse data from *.record files, created using Apollo-Auto - -current implementation illustrates sample record file parsing for -* radar (Continental ars-408) -* camera (Leopard Imaging 6mm) -* lidar (Velodyne vls-128) - -* saves extracted images in separate folder using *.jpg format -* saves radar and lidar data in respective folders in *.txt format for each scan -* also saves timestamp in separate text files - -""" - -import os -import sys -import time - -from importlib import import_module -import yaml - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import record - - -os.system('clear') - -def read_parameters(yaml_file): - """ - function to read YAML parameter file and define output destinations - """ - with open(yaml_file, 'r') as f: - params = yaml.safe_load(f) - # record file params - RECORD_FOLDER = params['records']['filepath'] - parse_type = params['parse'] - - # define destinations - dest_path = os.path.split(RECORD_FOLDER) - if not dest_path[-1]: - dest_path = os.path.split(dest_path[0]) - - OUT_FOLDER = dest_path[0] + '/' - temp_path = os.path.split(dest_path[0]) - FOLDER_PREFIX = temp_path[1].replace("-", "") - - parse_dict = {"params": params, - "parse_type": parse_type, - "out_folder": OUT_FOLDER, - "prefix": FOLDER_PREFIX, - "record_folder": RECORD_FOLDER} - - return parse_dict - -def define_destinations(parse_dict): - """ - define destination for extracted files - """ - dest_dict = { - "channel_name": "", - "timestamp_file": "", - "destination_folder": "" - } - - parse_type = parse_dict["parse_type"] - params = parse_dict["params"] - dest_folder = parse_dict["out_folder"] - prefix = parse_dict["prefix"] - - parser_func = 'parse_' + parse_type - - dest_dict['channel_name'] = params[parse_type]['channel_name'] - dest_dict['timestamp_file'] = dest_folder + prefix + params[parse_type]['timestamp_file_extn'] - dest_dict['destination_folder'] = dest_folder + \ - prefix + params[parse_type]['out_folder_extn'] + '/' - - if not os.path.exists(dest_dict["destination_folder"]): - os.makedirs(dest_dict["destination_folder"]) - - return dest_dict, parser_func - -def parse_apollo_record(parse_dict, dest_dict, parser_func): - """ - """ - record_folder_path = parse_dict["record_folder"] - parse_type = parse_dict["parse_type"] - record_files = sorted(os.listdir(parse_dict["record_folder"])) - parse_timestamp = [] - parse_mod = import_module(parser_func) - - print("=" * 60) - print('--------- Parsing data for: ' + parse_type + ' ---------') - - for rfile in record_files: - print("=" * 60) - print("parsing record file: %s" % rfile) - freader = record.RecordReader(record_folder_path + rfile) - time.sleep(.025) - - for channelname, msg, datatype, timestamp in freader.read_messages(): - if channelname == dest_dict["channel_name"]: - tstamp = parse_mod.parse_data(channelname, msg, dest_dict['destination_folder']) - parse_timestamp.append(tstamp) - - # write radar-timestamp files - with open(dest_dict["timestamp_file"], 'w+') as f: - for item in parse_timestamp: - f.write("%s\n" % item) - - print("=" * 60) - print('DONE: records parsed and data saved to: \n ' + dest_dict['destination_folder']) - print("=" * 60) - -if __name__ == '__main__': - cyber.init() - parse_dict = read_parameters('./parser_params.yaml') - dest_dict, parser_func = define_destinations(parse_dict) - parse_apollo_record(parse_dict, dest_dict, parser_func) - - cyber.shutdown() diff --git a/modules/tools/record_play/BUILD b/modules/tools/record_play/BUILD deleted file mode 100644 index be852c90641..00000000000 --- a/modules/tools/record_play/BUILD +++ /dev/null @@ -1,52 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -filegroup( - name = "readme", - srcs = glob([ - "README.md", - ]), -) - -py_binary( - name = "rtk_player", - srcs = ["rtk_player.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:cyber_time", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/config_msgs:vehicle_config_py_pb2", - "//modules/common_msgs/basic_msgs:drive_state_py_pb2", - "//modules/common_msgs/basic_msgs:pnc_point_py_pb2", - "//modules/common_msgs/control_msgs:pad_msg_py_pb2", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - "//modules/common_msgs/planning_msgs:planning_py_pb2", - "//modules/tools/common:logger", - "//modules/tools/common:proto_utils", - ], -) - -py_binary( - name = "rtk_recorder", - srcs = ["rtk_recorder.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - "//modules/tools/common:logger", - "//modules/tools/common:proto_utils", - ], -) - -install( - name = "install", - data = [":readme"], - data_dest = "tools/record_play", - py_dest = "tools/record_play", - targets = [ - ":rtk_player", - ":rtk_recorder" - ], -) \ No newline at end of file diff --git a/modules/tools/record_play/README.md b/modules/tools/record_play/README.md deleted file mode 100644 index fa389a573db..00000000000 --- a/modules/tools/record_play/README.md +++ /dev/null @@ -1,34 +0,0 @@ -# Record and Play Tool - -## Prerequisite - -Run the following command from your Apollo root dir: - -```bash -bash apollo.sh build -source scripts/apollo_base.sh -``` - -## Recorder - -This tool records trajectory information from gateway into a csv file, the file -name is defined in filename_path. - -## Player - -This tool reads information from a csv file and publishes planning trajectory in -the same format as real planning node. - -Default enable recorder and play under `/apollo` utilizing: - -```bash -bash scripts/rtk_recorder.sh -``` - -and - -```bash -bash scripts/rtk_player.sh -``` - -Or using button on Dreamview diff --git a/modules/tools/record_play/rtk_player.py b/modules/tools/record_play/rtk_player.py deleted file mode 100755 index 475548ca773..00000000000 --- a/modules/tools/record_play/rtk_player.py +++ /dev/null @@ -1,386 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -Generate Planning Path -""" - -import argparse -import atexit -import logging -import math -import os -import sys -import time - -from numpy import genfromtxt -import scipy.signal as signal - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import cyber_time -from modules.tools.common.logger import Logger -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.config_msgs import vehicle_config_pb2 -from modules.common_msgs.basic_msgs import drive_state_pb2 -from modules.common_msgs.basic_msgs import pnc_point_pb2 -from modules.common_msgs.control_msgs import pad_msg_pb2 -from modules.common_msgs.localization_msgs import localization_pb2 -from modules.common_msgs.planning_msgs import planning_pb2 -import modules.tools.common.proto_utils as proto_utils - -# TODO(all): hard-coded path temporarily. Better approach needed. -APOLLO_ROOT = "/apollo" - -SEARCH_INTERVAL = 5000 -CHANGE_TO_COM = False - - -class RtkPlayer(object): - """ - rtk player class - """ - - def __init__(self, record_file, node, speedmultiplier, completepath, - replan): - """Init player.""" - self.firstvalid = False - self.logger = Logger.get_logger(tag="RtkPlayer") - self.logger.info("Load record file from: %s" % record_file) - try: - file_handler = open(record_file, 'r') - except (FileNotFoundError, IOError) as ex: - self.logger.error("Error opening {}: {}".format(record_file, ex)) - sys.exit(1) - - self.data = genfromtxt(file_handler, delimiter=',', names=True) - file_handler.close() - - self.localization = localization_pb2.LocalizationEstimate() - self.chassis = chassis_pb2.Chassis() - self.padmsg = pad_msg_pb2.PadMessage() - self.localization_received = False - self.chassis_received = False - - self.planning_pub = node.create_writer('/apollo/planning', - planning_pb2.ADCTrajectory) - - self.speedmultiplier = speedmultiplier / 100 - self.terminating = False - self.sequence_num = 0 - - b, a = signal.butter(6, 0.05, 'low') - self.data['acceleration'] = signal.filtfilt(b, a, - self.data['acceleration']) - - self.start = 0 - self.end = 0 - self.closestpoint = 0 - self.automode = False - - self.replan = (replan == 't') - self.completepath = (completepath == 't') - - self.estop = False - self.logger.info("Planning Ready") - - vehicle_config = vehicle_config_pb2.VehicleConfig() - proto_utils.get_pb_from_text_file( - "/apollo/modules/common/data/vehicle_param.pb.txt", vehicle_config) - self.vehicle_param = vehicle_config.vehicle_param - - def localization_callback(self, data): - """ - New localization Received - """ - self.localization.CopyFrom(data) - self.carx = self.localization.pose.position.x - self.cary = self.localization.pose.position.y - self.carz = self.localization.pose.position.z - self.localization_received = True - - def chassis_callback(self, data): - """ - New chassis Received - """ - self.chassis.CopyFrom(data) - self.automode = (self.chassis.driving_mode - == chassis_pb2.Chassis.COMPLETE_AUTO_DRIVE) - self.chassis_received = True - - def padmsg_callback(self, data): - """ - New message received - """ - if self.terminating is True: - self.logger.info("terminating when receive padmsg") - return - - self.padmsg.CopyFrom(data) - - def restart(self): - self.logger.info("before replan self.start=%s, self.closestpoint=%s" % - (self.start, self.closestpoint)) - self.logger.debug("replan!") - - self.closestpoint = self.closest_dist() - self.start = max(self.closestpoint - 1, 0) - self.logger.debug("replan_start: %s" % self.start) - self.starttime = cyber_time.Time.now().to_sec() - self.logger.debug("at time %s" % self.starttime) - self.end = self.next_gear_switch_time(self.start, len(self.data)) - self.logger.debug("replan_end: %s" % self.end) - self.logger.info("finish replan at time %s, self.closestpoint=%s" % - (self.starttime, self.closestpoint)) - - def closest_dist(self): - shortest_dist_sqr = float('inf') - self.logger.info("before closest self.start=%s" % (self.start)) - search_start = max(self.start - SEARCH_INTERVAL // 2, 0) - search_end = min(self.start + SEARCH_INTERVAL // 2, len(self.data)) - self.logger.debug("search_start: %s" % search_start) - self.logger.debug("search_end: %s" % search_end) - closest_dist_point = self.start - self.logger.debug("self.start: %s" % self.start) - for i in range(search_start, search_end): - dist_sqr = (self.carx - self.data['x'][i]) ** 2 + \ - (self.cary - self.data['y'][i]) ** 2 - if dist_sqr <= shortest_dist_sqr and self.data['gear'][i] == self.chassis.gear_location: - closest_dist_point = i - shortest_dist_sqr = dist_sqr - - # failed to find a trajectory matches current gear position - if shortest_dist_sqr == float('inf'): - self.logger.info( - 'no trajectory point matches current gear position, check gear position') - return closest_dist_point + 1 # remain current start point - - return closest_dist_point - - def closest_time(self): - time_elapsed = cyber_time.Time.now().to_sec() - self.starttime - closest_time = self.start - time_diff = self.data['time'][closest_time] - \ - self.data['time'][self.closestpoint] - - while time_diff < time_elapsed and closest_time < (len(self.data) - 1): - closest_time = closest_time + 1 - time_diff = self.data['time'][closest_time] - \ - self.data['time'][self.closestpoint] - - return closest_time - - def next_gear_switch_time(self, start, end): - for i in range(start, end): - # trajectory with gear switch - # include gear_neutral at the beginning of a trajectory - if (i < end - 1 - and self.data['gear'][i] in {1, 2} - and self.data['gear'][i + 1] != self.data['gear'][i]): - self.logger.debug("enter i in while loop: [ %s ]" % i) - self.logger.debug( - "self.data['gear'][i] != 1: %s" % self.data['gear'][i]) - self.logger.debug( - "self.data['gear'][i] != 2: %s" % self.data['gear'][i]) - # find next gear = 1 or 2 - i += 1 - while i < end and (self.data['gear'][i] != 1) and (self.data['gear'][i] != 2): - i += 1 - self.logger.debug("i in while loop: [ %s ]" % i) - return i - 1 - # trajectory without gear switch - self.logger.debug("i at end: [ %s ]" % i) - return min(i, end - 1) - - def publish_planningmsg(self): - """ - Generate New Path - """ - if not self.localization_received: - self.logger.warning( - "localization not received yet when publish_planningmsg") - return - - planningdata = planning_pb2.ADCTrajectory() - now = cyber_time.Time.now().to_sec() - planningdata.header.timestamp_sec = now - planningdata.header.module_name = "planning" - planningdata.header.sequence_num = self.sequence_num - self.sequence_num = self.sequence_num + 1 - - self.logger.debug( - "publish_planningmsg: before adjust start: self.start=%s, self.end=%s" - % (self.start, self.end)) - if self.replan or self.sequence_num <= 1 or not self.automode: - self.logger.info( - "trigger replan: self.replan=%s, self.sequence_num=%s, self.automode=%s" - % (self.replan, self.sequence_num, self.automode)) - self.restart() - else: - timepoint = self.closest_time() - distpoint = self.closest_dist() - - if self.data['gear'][timepoint] == self.data['gear'][distpoint]: - self.start = max(min(timepoint, distpoint), 0) - elif self.data['gear'][timepoint] == self.chassis.gear_location: - self.start = timepoint - else: - self.start = distpoint - - self.logger.debug("timepoint:[%s]" % timepoint) - self.logger.debug("distpoint:[%s]" % distpoint) - self.logger.debug( - "trajectory start point: [%s], gear is [%s]" % (self.start, self.data['gear'][self.start])) - - self.end = self.next_gear_switch_time(self.start, len(self.data)) - self.logger.debug("len of data: ", len(self.data)) - self.logger.debug("trajectory end point: [%s], gear is [%s]" % - (self.end, self.data['gear'][self.end])) - - xdiff_sqr = (self.data['x'][timepoint] - self.carx)**2 - ydiff_sqr = (self.data['y'][timepoint] - self.cary)**2 - if xdiff_sqr + ydiff_sqr > 4.0: - self.logger.info("trigger replan: distance larger than 2.0") - self.restart() - - if self.completepath: - self.start = 0 - self.end = len(self.data) - 1 - - self.logger.debug( - "publish_planningmsg: after adjust start: self.start=%s, self.end=%s" - % (self.start, self.end)) - - planningdata.total_path_length = self.data['s'][self.end] - \ - self.data['s'][self.start] - self.logger.info("total number of planning data point: %d" % - (self.end - self.start)) - planningdata.total_path_time = self.data['time'][self.end] - \ - self.data['time'][self.start] - planningdata.gear = int(self.data['gear'][self.closest_time()]) - planningdata.engage_advice.advice = \ - drive_state_pb2.EngageAdvice.READY_TO_ENGAGE - - for i in range(self.start, self.end): - adc_point = pnc_point_pb2.TrajectoryPoint() - adc_point.path_point.x = self.data['x'][i] - adc_point.path_point.y = self.data['y'][i] - adc_point.path_point.z = self.data['z'][i] - adc_point.v = self.data['speed'][i] * self.speedmultiplier - adc_point.a = self.data['acceleration'][i] * self.speedmultiplier - adc_point.path_point.kappa = self.data['curvature'][i] - adc_point.path_point.dkappa = self.data['curvature_change_rate'][i] - adc_point.path_point.theta = self.data['theta'][i] - adc_point.path_point.s = self.data['s'][i] - - if CHANGE_TO_COM: - # translation vector length(length / 2 - back edge to center) - adc_point.path_point.x = adc_point.path_point.x + \ - (self.vehicle_param.length // 2 - self.vehicle_param.back_edge_to_center) * \ - math.cos(adc_point.path_point.theta) - adc_point.path_point.y = adc_point.path_point.y + \ - (self.vehicle_param.length // 2 - self.vehicle_param.back_edge_to_center) * \ - math.sin(adc_point.path_point.theta) - - if planningdata.gear == chassis_pb2.Chassis.GEAR_REVERSE: - adc_point.v = -adc_point.v - adc_point.path_point.s = -adc_point.path_point.s - - time_diff = self.data['time'][i] - \ - self.data['time'][self.closestpoint] - - adc_point.relative_time = time_diff / self.speedmultiplier - ( - now - self.starttime) - - planningdata.trajectory_point.extend([adc_point]) - - planningdata.estop.is_estop = self.estop - - self.planning_pub.write(planningdata) - self.logger.debug("Generated Planning Sequence: " - + str(self.sequence_num - 1)) - - def shutdown(self): - """ - shutdown cyber - """ - self.terminating = True - self.logger.info("Shutting Down...") - time.sleep(0.2) - - def quit(self, signum, frame): - """ - shutdown the keypress thread - """ - sys.exit(0) - - -def main(): - """ - Main cyber - """ - parser = argparse.ArgumentParser( - description='Generate Planning Trajectory from Data File') - parser.add_argument( - '-s', - '--speedmulti', - help='Speed multiplier in percentage (Default is 100) ', - type=float, - default='100') - parser.add_argument( - '-c', '--complete', help='Generate complete path (t/F)', default='F') - parser.add_argument( - '-r', - '--replan', - help='Always replan based on current position(t/F)', - default='F') - args = vars(parser.parse_args()) - - node = cyber.Node("rtk_player") - - Logger.config( - log_file=os.path.join(APOLLO_ROOT, 'data/log/rtk_player.log'), - use_stdout=True, - log_level=logging.DEBUG) - - record_file = os.path.join(APOLLO_ROOT, 'data/log/garage.csv') - - player = RtkPlayer(record_file, node, args['speedmulti'], - args['complete'].lower(), args['replan'].lower()) - atexit.register(player.shutdown) - - node.create_reader('/apollo/canbus/chassis', chassis_pb2.Chassis, - player.chassis_callback) - - node.create_reader('/apollo/localization/pose', - localization_pb2.LocalizationEstimate, - player.localization_callback) - - node.create_reader('/apollo/control/pad', pad_msg_pb2.PadMessage, - player.padmsg_callback) - - while not cyber.is_shutdown(): - now = cyber_time.Time.now().to_sec() - player.publish_planningmsg() - sleep_time = 0.1 - (cyber_time.Time.now().to_sec() - now) - if sleep_time > 0: - time.sleep(sleep_time) - - -if __name__ == '__main__': - cyber.init() - main() - cyber.shutdown() diff --git a/modules/tools/record_play/rtk_recorder.py b/modules/tools/record_play/rtk_recorder.py deleted file mode 100755 index 01ca6dac87b..00000000000 --- a/modules/tools/record_play/rtk_recorder.py +++ /dev/null @@ -1,219 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -Record GPS and IMU data -""" - -import atexit -import logging -import math -import os -import sys -import time - -from cyber.python.cyber_py3 import cyber -from gflags import FLAGS - -from modules.tools.common.logger import Logger -import modules.tools.common.proto_utils as proto_utils -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.config_msgs import vehicle_config_pb2 -from modules.common_msgs.localization_msgs import localization_pb2 - -APOLLO_ROOT = "/apollo" - -class RtkRecord(object): - """ - rtk recording class - """ - - def write(self, data): - """Wrap file write function to flush data to disk""" - self.file_handler.write(data) - self.file_handler.flush() - - def __init__(self, record_file): - self.firstvalid = False - self.logger = Logger.get_logger("RtkRecord") - self.record_file = record_file - self.logger.info("Record file to: " + record_file) - - try: - self.file_handler = open(record_file, 'w') - except IOError: - self.logger.error("Open file %s failed" % (record_file)) - self.file_handler.close() - sys.exit(1) - - self.write("x,y,z,speed,acceleration,curvature," - "curvature_change_rate,time,theta,gear,s,throttle,brake,steering\n") - - self.localization = localization_pb2.LocalizationEstimate() - self.chassis = chassis_pb2.Chassis() - self.chassis_received = False - - self.cars = 0.0 - self.startmoving = False - - self.terminating = False - self.carcurvature = 0.0 - - self.prev_carspeed = 0.0 - - vehicle_config = vehicle_config_pb2.VehicleConfig() - proto_utils.get_pb_from_text_file( - "/apollo/modules/common/data/vehicle_param.pb.txt", vehicle_config) - self.vehicle_param = vehicle_config.vehicle_param - - def chassis_callback(self, data): - """ - New message received - """ - if self.terminating is True: - self.logger.info("terminating when receive chassis msg") - return - - self.chassis.CopyFrom(data) - #self.chassis = data - if math.isnan(self.chassis.speed_mps): - self.logger.warning("find nan speed_mps: %s" % str(self.chassis)) - if math.isnan(self.chassis.steering_percentage): - self.logger.warning( - "find nan steering_percentage: %s" % str(self.chassis)) - self.chassis_received = True - - def localization_callback(self, data): - """ - New message received - """ - if self.terminating is True: - self.logger.info("terminating when receive localization msg") - return - - if not self.chassis_received: - self.logger.info( - "chassis not received when localization is received") - return - - self.localization.CopyFrom(data) - #self.localization = data - carx = self.localization.pose.position.x - cary = self.localization.pose.position.y - carz = self.localization.pose.position.z - cartheta = self.localization.pose.heading - if math.isnan(self.chassis.speed_mps): - self.logger.warning("find nan speed_mps: %s" % str(self.chassis)) - return - if math.isnan(self.chassis.steering_percentage): - self.logger.warning( - "find nan steering_percentage: %s" % str(self.chassis)) - return - carspeed = self.chassis.speed_mps - caracceleration = self.localization.pose.linear_acceleration_vrf.y - - speed_epsilon = 1e-9 - if abs(self.prev_carspeed) < speed_epsilon \ - and abs(carspeed) < speed_epsilon: - caracceleration = 0.0 - - carsteer = self.chassis.steering_percentage - carmax_steer_angle = self.vehicle_param.max_steer_angle - carsteer_ratio = self.vehicle_param.steer_ratio - carwheel_base = self.vehicle_param.wheel_base - curvature = math.tan(math.radians(carsteer / 100 - * math.degrees(carmax_steer_angle)) / carsteer_ratio) / carwheel_base - if abs(carspeed) >= speed_epsilon: - carcurvature_change_rate = (curvature - self.carcurvature) / ( - carspeed * 0.01) - else: - carcurvature_change_rate = 0.0 - self.carcurvature = curvature - cartime = self.localization.header.timestamp_sec - cargear = self.chassis.gear_location - - if abs(carspeed) >= speed_epsilon: - if self.startmoving is False: - self.logger.info( - "carspeed !=0 and startmoving is False, Start Recording") - self.startmoving = True - - if self.startmoving: - self.cars += carspeed * 0.01 - self.write( - "%s, %s, %s, %s, %s, %s, %s, %.4f, %s, %s, %s, %s, %s, %s\n" % - (carx, cary, carz, carspeed, caracceleration, self.carcurvature, - carcurvature_change_rate, cartime, cartheta, cargear, - self.cars, self.chassis.throttle_percentage, - self.chassis.brake_percentage, - self.chassis.steering_percentage)) - self.logger.debug( - "started moving and write data at time %s" % cartime) - else: - self.logger.debug("not start moving, do not write data to file") - - self.prev_carspeed = carspeed - - def shutdown(self): - """ - shutdown node - """ - self.terminating = True - self.logger.info("Shutting Down...") - self.logger.info("File is written into %s" % self.record_file) - self.file_handler.close() - - -def main(argv): - """ - Main node - """ - node = cyber.Node("rtk_recorder") - argv = FLAGS(argv) - - log_dir = "/apollo/data/log" - if len(argv) > 1: - log_dir = argv[1] - - if not os.path.exists(log_dir): - os.makedirs(log_dir) - - Logger.config( - log_file=os.path.join(APOLLO_ROOT, 'data/log/rtk_recorder.log'), - use_stdout=True, - log_level=logging.DEBUG) - print("runtime log is in %s%s" % (log_dir, "rtk_recorder.log")) - - record_file = log_dir + "/garage.csv" - recorder = RtkRecord(record_file) - atexit.register(recorder.shutdown) - node.create_reader('/apollo/canbus/chassis', - chassis_pb2.Chassis, - recorder.chassis_callback) - - node.create_reader('/apollo/localization/pose', - localization_pb2.LocalizationEstimate, - recorder.localization_callback) - - while not cyber.is_shutdown(): - time.sleep(0.002) - - -if __name__ == '__main__': - cyber.init() - main(sys.argv) - cyber.shutdown() diff --git a/modules/tools/replay/BUILD b/modules/tools/replay/BUILD deleted file mode 100644 index 7d38f32745e..00000000000 --- a/modules/tools/replay/BUILD +++ /dev/null @@ -1,22 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -py_binary( - name = "replay_file", - srcs = ["replay_file.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//modules/tools/common:message_manager", - "//modules/tools/common:proto_utils", - ], -) - -install( - name = "install", - py_dest = "tools/replay", - targets = [ - ":replay_file", - ], -) \ No newline at end of file diff --git a/modules/tools/replay/replay_file.py b/modules/tools/replay/replay_file.py deleted file mode 100644 index 23f6b70f092..00000000000 --- a/modules/tools/replay/replay_file.py +++ /dev/null @@ -1,112 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -This program can replay a message pb file -""" -import os.path -import sys -import argparse -import glob -import time - -from google.protobuf import text_format - -from cyber.python.cyber_py3 import cyber - -import modules.tools.common.proto_utils as proto_utils -from modules.tools.common.message_manager import PbMessageManager - -g_message_manager = PbMessageManager() - - -def topic_publisher(topic, filename, period): - """publisher""" - cyber.init() - node = cyber.Node("replay_file") - meta_msg = None - msg = None - if not topic: - print("Topic not specified, start to guess") - meta_msg, msg = g_message_manager.parse_file(filename) - topic = meta_msg.topic() - else: - meta_msg = g_message_manager.get_msg_meta_by_topic(topic) - if not meta_msg: - print("Failed to find meta info for topic: %s" % (topic)) - return False - msg = meta_msg.parse_file(filename) - if not msg: - print("Failed to parse file[%s] with topic[%s]" % (filename, - topic)) - return False - - if not msg or not meta_msg: - print("Unknown topic: %s" % topic) - return False - - writer = node.create_writer(topic, meta_msg.msg_type) - - if period == 0: - while not cyber.is_shutdown(): - input("Press any key to publish one message...") - writer.write(msg) - print("Topic[%s] message published" % topic) - else: - print("started to publish topic[%s] message with rate period %s" % - (topic, period)) - while not cyber.is_shutdown(): - writer.write(msg) - time.sleep(period) - - -if __name__ == '__main__': - parser = argparse.ArgumentParser( - description="replay a planning result pb file") - parser.add_argument( - "filename", action="store", type=str, help="planning result files") - parser.add_argument( - "--topic", action="store", type=str, help="set the planning topic") - parser.add_argument( - "--period", - action="store", - type=float, - default=0.1, - help="set the topic publish time duration") - args = parser.parse_args() - period = 0.0 # use step by step mode - if args.period: # play with a given period, (1.0 / frequency) - period = args.period - to_replay = args.filename - files = [] - if os.path.isdir(args.filename): - files = glob.glob(args.filename + "/*") - i = 0 - for f in files: - print("%d %s" % (i, f)) - i += 1 - str_input = input("Select message by number: ") - try: - selected_file = int(str_input) - if selected_file < 0 or selected_file > len(files): - print("%d is an invalid number" % selected_file) - except: - print("%s is not a number" % str_input) - print("Will publish file[%d]: %s" % (selected_file, - files[selected_file])) - to_replay = files[selected_file] - topic_publisher(args.topic, to_replay, period) diff --git a/modules/tools/restore_video_record/BUILD b/modules/tools/restore_video_record/BUILD deleted file mode 100644 index 7aa1411fdfc..00000000000 --- a/modules/tools/restore_video_record/BUILD +++ /dev/null @@ -1,31 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - - -filegroup( - name = "readme", - srcs = glob([ - "README.md", - ]), -) - -py_binary( - name = "restore_video_record", - srcs = ["restore_video_record.py"], - deps = [ - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/sensor_msgs:sensor_image_py_pb2", - ], -) - -install( - name = "install", - data = [":readme"], - data_dest = "tools/restore_video_record", - py_dest = "tools/restore_video_record", - targets = [ - ":restore_video_record", - ], -) \ No newline at end of file diff --git a/modules/tools/restore_video_record/README.md b/modules/tools/restore_video_record/README.md deleted file mode 100644 index a6e202cc9b7..00000000000 --- a/modules/tools/restore_video_record/README.md +++ /dev/null @@ -1,9 +0,0 @@ -# Video Records Restoring Tool - -## Restore - -This tool converts video frames from source record file into images and then restores them to the generated record file. - -```bash -python restore_video_record.py --from_record= --to_record= -``` diff --git a/modules/tools/restore_video_record/restore_video_record.py b/modules/tools/restore_video_record/restore_video_record.py deleted file mode 100644 index 345dbb98f85..00000000000 --- a/modules/tools/restore_video_record/restore_video_record.py +++ /dev/null @@ -1,243 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -""" Restore record file by replacing its video frames with image frames. """ - -import datetime -import errno -import glob -import os -import shutil -import time - -from absl import app -from absl import flags -from absl import logging -import cv2 - -from cyber.python.cyber_py3.record import RecordReader, RecordWriter -from modules.common_msgs.sensor_msgs.sensor_image_pb2 import CompressedImage - - -flags.DEFINE_string('from_record', None, 'The source record file that needs to be restored.') -flags.DEFINE_string('to_record', None, 'The restored record file.') - -# The compressed channels that have videos we need to decode -IMAGE_FRONT_6MM_CHANNEL = '/apollo/sensor/camera/front_6mm/image/compressed' -IMAGE_FRONT_12MM_CHANNEL = '/apollo/sensor/camera/front_12mm/image/compressed' -IMAGE_REAR_6MM_CHANNEL = '/apollo/sensor/camera/rear_6mm/image/compressed' -IMAGE_LEFT_FISHEYE_CHANNEL = '/apollo/sensor/camera/left_fisheye/image/compressed' -IMAGE_RIGHT_FISHEYE_CHANNEL = '/apollo/sensor/camera/right_fisheye/image/compressed' - -VIDEO_FRONT_6MM_CHANNEL = '/apollo/sensor/camera/front_6mm/video/compressed' -VIDEO_FRONT_12MM_CHANNEL = '/apollo/sensor/camera/front_12mm/video/compressed' -VIDEO_REAR_6MM_CHANNEL = '/apollo/sensor/camera/rear_6mm/video/compressed' -VIDEO_LEFT_FISHEYE_CHANNEL = '/apollo/sensor/camera/left_fisheye/video/compressed' -VIDEO_RIGHT_FISHEYE_CHANNEL = '/apollo/sensor/camera/right_fisheye/video/compressed' - -VIDEO_CHANNELS = [ - IMAGE_FRONT_6MM_CHANNEL, - IMAGE_FRONT_12MM_CHANNEL, - IMAGE_REAR_6MM_CHANNEL, - IMAGE_LEFT_FISHEYE_CHANNEL, - IMAGE_RIGHT_FISHEYE_CHANNEL, - VIDEO_FRONT_6MM_CHANNEL, - VIDEO_FRONT_12MM_CHANNEL, - VIDEO_REAR_6MM_CHANNEL, - VIDEO_LEFT_FISHEYE_CHANNEL, - VIDEO_RIGHT_FISHEYE_CHANNEL, -] - -VIDEO_IMAGE_MAP = { - IMAGE_FRONT_6MM_CHANNEL: IMAGE_FRONT_6MM_CHANNEL, - IMAGE_FRONT_12MM_CHANNEL: IMAGE_FRONT_12MM_CHANNEL, - IMAGE_REAR_6MM_CHANNEL: IMAGE_REAR_6MM_CHANNEL, - IMAGE_LEFT_FISHEYE_CHANNEL: IMAGE_LEFT_FISHEYE_CHANNEL, - IMAGE_RIGHT_FISHEYE_CHANNEL: IMAGE_RIGHT_FISHEYE_CHANNEL, - VIDEO_FRONT_6MM_CHANNEL: IMAGE_FRONT_6MM_CHANNEL, - VIDEO_FRONT_12MM_CHANNEL: IMAGE_FRONT_12MM_CHANNEL, - VIDEO_REAR_6MM_CHANNEL: IMAGE_REAR_6MM_CHANNEL, - VIDEO_LEFT_FISHEYE_CHANNEL: IMAGE_LEFT_FISHEYE_CHANNEL, - VIDEO_RIGHT_FISHEYE_CHANNEL: IMAGE_RIGHT_FISHEYE_CHANNEL, -} - - -class VideoConverter(object): - """Convert video into images.""" - - def __init__(self, work_dir, topic): - # Initial type of video frames that defined in apollo video drive proto - # The initial frame has meta data information shared by the following tens of frames - self.initial_frame_type = 1 - self.image_ids = [] - self.first_initial_found = False - video_dir = os.path.join(work_dir, 'videos') - self.video_file = os.path.join(video_dir, '{}.h265'.format(topic)) - self.image_dir = '{}_images'.format(self.video_file) - makedirs(video_dir) - makedirs(self.image_dir) - self.frame_writer = open(self.video_file, 'wb+') - - def close_writer(self): - """Close the video frames writer""" - self.frame_writer.close() - - def write_frame(self, py_message): - """Write video frames into binary format file""" - if not self.first_initial_found: - proto = image_message_to_proto(py_message) - if proto.frame_type != self.initial_frame_type: - return - self.first_initial_found = True - self.frame_writer.write(py_message.message) - self.image_ids.append(get_message_id(py_message.timestamp, py_message.topic)) - - def decode(self): - """Decode video file into images""" - video_decoder_exe = '/apollo/bazel-bin/modules/drivers/video/tools/decode_video/video2jpg' - return_code = os.system('{} --input_video={} --output_dir={}'.format( - video_decoder_exe, self.video_file, self.image_dir)) - if return_code != 0: - logging.error('Failed to execute video2jpg for video {}'.format(self.video_file)) - return False - generated_images = sorted(glob.glob('{}/*.jpg'.format(self.image_dir))) - if len(generated_images) != len(self.image_ids): - logging.error('Mismatch between original {} and generated frames {}'.format( - len(self.image_ids), len(generated_images))) - return False - for idx in range(len(generated_images)): - os.rename(generated_images[idx], os.path.join(self.image_dir, self.image_ids[idx])) - return True - - def move_images(self, overall_image_dir): - """Move self's images to overall image dir""" - for image_file in os.listdir(self.image_dir): - shutil.move(os.path.join(self.image_dir, image_file), - os.path.join(overall_image_dir, image_file)) - - -def restore_record(input_record, output_record): - """Entrance of processing.""" - # Define working dirs that store intermediate results in the middle of processing - work_dir = 'restore_video_work_dir_{}'.format( - datetime.datetime.fromtimestamp(time.time()).strftime('%Y-%m-%d-%H-%M-%S')) - - # Decode videos - converters = {} - for topic in VIDEO_CHANNELS: - converters[topic] = VideoConverter(work_dir, topic) - - reader = RecordReader(input_record) - for message in reader.read_messages(): - if message.topic in VIDEO_CHANNELS: - converters[message.topic].write_frame(message) - - image_dir = os.path.join(work_dir, 'images') - makedirs(image_dir) - for topic in VIDEO_CHANNELS: - converters[topic].close_writer() - converters[topic].decode() - converters[topic].move_images(image_dir) - - # Restore target record file - writer = RecordWriter(0, 0) - writer.open(output_record) - topic_descs = {} - counter = 0 - reader = RecordReader(input_record) - for message in reader.read_messages(): - message_content = message.message - message_topic = message.topic - if message.topic in VIDEO_CHANNELS: - message_content = retrieve_image(image_dir, message) - message_topic = VIDEO_IMAGE_MAP[message.topic] - if not message_content: - continue - counter += 1 - if counter % 1000 == 0: - logging.info('rewriting {} th message to record {}'.format(counter, output_record)) - writer.write_message(message_topic, message_content, message.timestamp) - if message_topic not in topic_descs: - topic_descs[message_topic] = reader.get_protodesc(message_topic) - writer.write_channel(message_topic, message.data_type, topic_descs[message_topic]) - writer.close() - - logging.info('All Done, converted record: {}'.format(output_record)) - - -def retrieve_image(image_dir, message): - """Actually change the content of message from video bytes to image bytes""" - message_id = get_message_id(message.timestamp, message.topic) - message_path = os.path.join(image_dir, message_id) - if not os.path.exists(message_path): - logging.error('message {} not found in image dir'.format(message_id)) - return None - img_bin = cv2.imread(message_path) - # Check by using NoneType explicitly to avoid ambitiousness - if img_bin is None: - logging.error('failed to read original message: {}'.format(message_path)) - return None - encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 95] - result, encode_img = cv2.imencode('.jpg', img_bin, encode_param) - if not result: - logging.error('failed to encode message {}'.format(message_id)) - return None - message_proto = image_message_to_proto(message) - message_proto.format = '; jpeg compressed bgr8' - message_proto.data = message_proto.data.replace(message_proto.data[:], bytearray(encode_img)) - return message_proto.SerializeToString() - - -def get_message_id(timestamp, topic): - """Unify the way to get a unique identifier for the given message""" - return '{}{}'.format(timestamp, topic.replace('/', '_')) - - -def image_message_to_proto(py_message): - """Message to prototype""" - message_proto = CompressedImage() - message_proto.ParseFromString(py_message.message) - return message_proto - - -def makedirs(dir_path): - """Make directories recursively.""" - if os.path.exists(dir_path): - return - try: - os.makedirs(dir_path) - except OSError as error: - if error.errno != errno.EEXIST: - logging.error('Failed to makedir ' + dir_path) - raise - - -def main(argv): - """Main process.""" - if not flags.FLAGS.from_record or not os.path.exists(flags.FLAGS.from_record): - logging.error('Please provide valid source record file.') - return - to_record = flags.FLAGS.to_record - if not to_record: - to_record = '{}_restored'.format(flags.FLAGS.from_record) - logging.warn('The default restored record file is set as {}'.format(to_record)) - restore_record(flags.FLAGS.from_record, to_record) - - -if __name__ == '__main__': - app.run(main) diff --git a/modules/tools/rosbag/BUILD b/modules/tools/rosbag/BUILD deleted file mode 100644 index 7292c2496a3..00000000000 --- a/modules/tools/rosbag/BUILD +++ /dev/null @@ -1,168 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -install( - name = "install", - py_dest = "tools/rosbag", - targets = [ - ":audio_event_record", - ":body_sensation_evaluation", - ":channel_size_stats", - ":drive_event", - ":dump_gpsbin", - ":dump_planning", - ":dump_record", - ":dump_road_test_log", - ":extract_trajectory", - ":sample_pnc_topics", - ":stat_mileage", - ":stat_static_info", - ":tf_stats", - ":transcribe", - ], -) - -py_binary( - name = "audio_event_record", - srcs = ["audio_event_record.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:cyber_time", - "//modules/tools/common:message_manager", - "//modules/tools/common:proto_utils", - ], -) - -py_binary( - name = "body_sensation_evaluation", - srcs = ["body_sensation_evaluation.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - ], -) - -py_binary( - name = "channel_size_stats", - srcs = ["channel_size_stats.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/planning_msgs:planning_py_pb2", - ], -) - -py_binary( - name = "drive_event", - srcs = ["drive_event.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:cyber_time", - "//modules/tools/common:message_manager", - "//modules/tools/common:proto_utils", - ], -) - -py_binary( - name = "dump_gpsbin", - srcs = ["dump_gpsbin.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/sensor_msgs:gnss_py_pb2", - ], -) - -py_binary( - name = "dump_planning", - srcs = ["dump_planning.py"], - deps = [ - "//cyber/python/cyber_py3:record", - ], -) - -py_binary( - name = "dump_record", - srcs = ["dump_record.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - "//modules/tools/common:message_manager", - ], -) - -py_binary( - name = "dump_road_test_log", - srcs = ["dump_road_test_log.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/basic_msgs:drive_event_py_pb2", - ], -) - -py_binary( - name = "extract_trajectory", - srcs = ["extract_trajectory.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - "//modules/tools/common:message_manager", - ], -) - -py_binary( - name = "sample_pnc_topics", - srcs = ["sample_pnc_topics.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - ], -) - -py_binary( - name = "stat_mileage", - srcs = ["stat_mileage.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - ], -) - -py_binary( - name = "stat_static_info", - srcs = ["stat_static_info.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/dreamview_msgs:hmi_status_py_pb2", - ], -) - -py_binary( - name = "tf_stats", - srcs = ["tf_stats.py"], - deps = [ - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/transform_msgs:transform_py_pb2", - ], -) - -py_binary( - name = "transcribe", - srcs = ["transcribe.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//modules/tools/common:message_manager", - "//modules/tools/common:proto_utils", - ], -) diff --git a/modules/tools/rosbag/audio_event_record.py b/modules/tools/rosbag/audio_event_record.py deleted file mode 100644 index 63a1766ebb3..00000000000 --- a/modules/tools/rosbag/audio_event_record.py +++ /dev/null @@ -1,132 +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. -############################################################################### -""" -This program can publish audio event message -""" - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import cyber_time - -import argparse -import datetime -import shutil -import time -import os -import sys - -from modules.tools.common.message_manager import PbMessageManager -from modules.tools.common import proto_utils - -g_message_manager = PbMessageManager() - -g_args = None - -g_localization = None - - -def OnReceiveLocalization(localization_msg): - global g_localization - g_localization = localization_msg - - -def main(args): - audio_event_meta_msg = g_message_manager.get_msg_meta_by_topic( - args.audio_event_topic) - if not audio_event_meta_msg: - print('Unknown audio_event topic name: %s' % args.audio_event_topic) - sys.exit(1) - - localization_meta_msg = g_message_manager.get_msg_meta_by_topic( - args.localization_topic) - if not localization_meta_msg: - print('Unknown localization topic name: %s' % args.localization_topic) - sys.exit(1) - - cyber.init() - node = cyber.Node("audio_event_node") - node.create_reader(localization_meta_msg.topic, - localization_meta_msg.msg_type, OnReceiveLocalization) - - writer = node.create_writer(audio_event_meta_msg.topic, - audio_event_meta_msg.msg_type) - seq_num = 0 - while not cyber.is_shutdown(): - obstacle_id = input( - "Type in obstacle ID and press Enter (current time: " + - str(datetime.datetime.now()) + ")\n>") - obstacle_id = obstacle_id.strip() - # TODO(QiL) add obstacle id sanity check. - current_time = cyber_time.Time.now().to_sec() - moving_result = None - audio_type = None - siren_is_on = None - audio_direction = None - while not moving_result: - moving_result = input("Type MovingResult:>") - moving_result = moving_result.strip() - while not audio_type: - audio_type = input("Type AudioType:>") - audio_type = audio_type.strip() - while not siren_is_on: - siren_is_on = input("Type SirenOnOffStatus:>") - siren_is_on = siren_is_on.strip() - while not audio_direction: - audio_direction = input("Type AudioDirection:>") - audio_direction = audio_direction.strip() - event_msg = audio_event_meta_msg.msg_type() - event_msg.header.timestamp_sec = current_time - event_msg.header.module_name = 'audio_event' - seq_num += 1 - event_msg.header.sequence_num = seq_num - event_msg.header.version = 1 - event_msg.id = obstacle_id - event_msg.moving_result = moving_result - event_msg.audio_type = audio_type - event_msg.siren_is_on = siren_is_on - event_msg.audio_direction = audio_direction - if g_localization: - event_msg.location.CopyFrom(g_localization.pose) - writer.write(event_msg) - time_str = datetime.datetime.fromtimestamp(current_time).strftime( - "%Y%m%d%H%M%S") - filename = os.path.join(args.dir, "%s_audio_event.pb.txt" % time_str) - proto_utils.write_pb_to_text_file(event_msg, filename) - print('Logged to rosbag and written to file %s' % filename) - time.sleep(0.1) - - -if __name__ == '__main__': - parser = argparse.ArgumentParser( - description="A tool to write audio events when recording rosbag") - parser.add_argument( - "--audio_event_topic", - action="store", - default="/apollo/audio_event", - help="""the audio event topic""") - parser.add_argument( - "--localization_topic", - action="store", - default="/apollo/localization/pose", - help="""the drive event topic""") - parser.add_argument( - "--dir", - action="store", - default="data/bag", - help="""The log export directory.""") - g_args = parser.parse_args() - main(g_args) diff --git a/modules/tools/rosbag/body_sensation_evaluation.py b/modules/tools/rosbag/body_sensation_evaluation.py deleted file mode 100644 index c0fe8336859..00000000000 --- a/modules/tools/rosbag/body_sensation_evaluation.py +++ /dev/null @@ -1,246 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### -""" -Usage: - python body_sensation_evalution.py bag1 bag2 ... -""" - -import argparse -import collections -import math -import sys -import time - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3.record import RecordReader -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.chassis_msgs.chassis_pb2 import Chassis -from modules.common_msgs.localization_msgs import localization_pb2 - -BUMP_TIME_THRESHOLD = 3 -ACCELERATE_TIME_THRESHOLD = 1 -SPEED_UP_THRESHOLD_2 = 2 -SPEED_UP_THRESHOLD_4 = 4 -SPEED_DOWN_THRESHOLD_2 = -2 -SPEED_DOWN_THRESHOLD_4 = -4 - -kChassisTopic = '/apollo/canbus/chassis' -kLocalizationTopic = '/apollo/localization/pose' - - -class BodySensationCalculator(object): - """The class to dispose body sensation from rosbag""" - - def __init__(self): - self.driving_mode = [] - self._timestamp = 0.0 - self._last_bump_time = 0.0 - self._last_speed_down_2_time = 0.0 - self._last_speed_down_4_time = 0.0 - self._last_speed_up_2_time = 0.0 - self._last_speed_up_4_time = 0.0 - self._last_turning_time = 0.0 - self._speed_down_2_flag = 0 - self._speed_down_4_flag = 0 - self._speed_up_2_flag = 0 - self._speed_up_4_flag = 0 - self._turning_flag = 0 - self.auto_counts = {} - self.auto_counts["speed_down_2"] = 0 - self.auto_counts["speed_down_4"] = 0 - self.auto_counts["speed_up_2"] = 0 - self.auto_counts["speed_up_4"] = 0 - self.auto_counts["turning"] = 0 - self.auto_counts["bumps"] = 0 - self.manual_counts = {} - self.manual_counts["speed_down_2"] = 0 - self.manual_counts["speed_down_4"] = 0 - self.manual_counts["speed_up_2"] = 0 - self.manual_counts["speed_up_4"] = 0 - self.manual_counts["turning"] = 0 - self.manual_counts["bumps"] = 0 - - def get_driving_mode(self, bag_file): - """get driving mode, which is stored in a dict""" - mode = {} - mode["status"] = 'UNKNOW' - mode["start_time"] = 0.0 - mode["end_time"] = 0.0 - chassis = chassis_pb2.Chassis() - reader = RecordReader(bag_file) - - for msg in reader.read_messages(): - if msg.topic == kChassisTopic: - chassis.ParseFromString(msg.message) - _t = msg.timestamp - t = int(str(_t)) * pow(10, -9) - cur_status = chassis.driving_mode - if mode["status"] != cur_status: - if mode["status"] != 'UNKNOW': - self.driving_mode.append(mode) - mode["status"] = cur_status - mode["start_time"] = t - mode["end_time"] = t - self.driving_mode.append(mode) - - def _check_status(self, timestamp): - """check driving mode according to timestamp""" - for mode in self.driving_mode: - if timestamp >= mode["start_time"] and timestamp <= mode["end_time"]: - if mode["status"] == Chassis.COMPLETE_AUTO_DRIVE: - return True - else: - return False - return False - - def _bumps_rollback(self, bump_time): - """rollback 1 second when passing bumps""" - if bump_time - self._last_speed_down_2_time <= ACCELERATE_TIME_THRESHOLD: - if self._check_status(self._last_speed_down_2_time): - self.auto_counts["speed_down_2"] -= 1 - else: - self.manual_counts["speed_down_2"] -= 1 - - if bump_time - self._last_speed_up_2_time <= ACCELERATE_TIME_THRESHOLD: - if self._check_status(self._last_speed_up_2_time): - self.auto_counts["speed_up_2"] -= 1 - else: - self.manual_counts["speed_up_2"] -= 1 - - if bump_time - self._last_speed_down_4_time <= ACCELERATE_TIME_THRESHOLD: - if self._check_status(self._last_speed_down_4_time): - self.auto_counts["speed_down_4"] -= 1 - else: - self.manual_counts["speed_down_4"] -= 1 - - if bump_time - self._last_speed_up_4_time <= ACCELERATE_TIME_THRESHOLD: - if self._check_status(self._last_speed_up_4_time): - self.auto_counts["speed_up_4"] -= 1 - else: - self.manual_counts["speed_up_4"] -= 1 - - if bump_time - self._last_turning_time <= ACCELERATE_TIME_THRESHOLD: - if self._check_status(self._last_turning_time): - self.auto_counts["turning"] -= 1 - else: - self.manual_counts["turning"] -= 1 - - def calculate(self, bag_file): - """calculate body sensation, it should be after get driving mode""" - localization = localization_pb2.LocalizationEstimate() - reader = RecordReader(bag_file) - for msg in reader.read_messages(): - if msg.topic == kLocalizationTopic: - localization.ParseFromString(msg.message) - _t = msg.timestamp - t = int(str(_t)) * pow(10, -9) - self.timestamp = t - diff_bump_time = t - self._last_bump_time - if diff_bump_time <= BUMP_TIME_THRESHOLD: - continue - acc_x = localization.pose.linear_acceleration.x - acc_y = localization.pose.linear_acceleration.y - acc_z = localization.pose.linear_acceleration.z - - if abs(acc_z) >= SPEED_UP_THRESHOLD_2 and diff_bump_time >= BUMP_TIME_THRESHOLD: - self._bumps_rollback(t) - self._last_bump_time = t - - if self._check_status(t): - self.auto_counts["bumps"] += 1 - else: - self.manual_counts["bumps"] += 1 - else: - if self._speed_down_2_flag: - if acc_y <= SPEED_DOWN_THRESHOLD_4: - self._speed_down_4_flag = 1 - continue - if acc_y <= SPEED_DOWN_THRESHOLD_2: - continue - if self._speed_down_4_flag == 1 \ - and t - self._last_speed_down_4_time >= ACCELERATE_TIME_THRESHOLD: - self._last_speed_down_4_time = t - if self._check_status(t): - self.auto_counts["speed_down_4"] += 1 - else: - self.manual_counts["speed_down_4"] += 1 - elif t - self._last_speed_down_2_time >= ACCELERATE_TIME_THRESHOLD: - self._last_speed_down_2_time = t - if self._check_status(t): - self.auto_counts["speed_down_2"] += 1 - else: - self.manual_counts["speed_down_2"] += 1 - self._speed_down_2_flag = 0 - self._speed_down_4_flag = 0 - elif acc_y <= SPEED_DOWN_THRESHOLD_2: - self._speed_down_2_flag = 1 - - if self._speed_up_2_flag: - if acc_y >= SPEED_UP_THRESHOLD_4: - self._speed_up_4_flag = 1 - continue - if acc_y >= SPEED_UP_THRESHOLD_2: - continue - if self._speed_up_4_flag == 1 \ - and t - self._last_speed_up_4_time >= ACCELERATE_TIME_THRESHOLD: - self._last_speed_up_4_time = t - if self._check_status(t): - self.auto_counts["speed_up_4"] += 1 - else: - self.manual_counts["speed_up_4"] += 1 - elif t - self._last_speed_up_2_time >= ACCELERATE_TIME_THRESHOLD: - self._last_speed_up_2_time = t - if self._check_status(t): - self.auto_counts["speed_up_2"] += 1 - else: - self.manual_counts["speed_up_2"] += 1 - self._speed_up_2_flag = 0 - self._speed_up_4_flag = 0 - elif acc_y >= SPEED_UP_THRESHOLD_2: - self._speed_up_2_flag = 1 - - if self._turning_flag: - if abs(acc_x) >= SPEED_UP_THRESHOLD_2: - continue - if t - self._last_turning_time >= ACCELERATE_TIME_THRESHOLD: - self._last_turning_time = t - if self._check_status(t): - self.auto_counts["turning"] += 1 - else: - self.manual_counts["turning"] += 1 - self._turning_flag = 0 - elif abs(acc_x) >= SPEED_UP_THRESHOLD_2: - self._turning_flag = 1 - - -if __name__ == '__main__': - parser = argparse.ArgumentParser( - description="A tool to evaluate the body sensation. \ - It should be used like 'python body_sensation_evalution.py bag1 bag2 ...' ") - parser.add_argument( - "in_rosbag", action="store", nargs='+', type=str, help="the input rosbag") - args = parser.parse_args() - bsc = BodySensationCalculator() - for bag_file in args.in_rosbag: - bsc.get_driving_mode(bag_file) - for bag_file in args.in_rosbag: - bsc.calculate(bag_file) - counts = {} - counts["auto"] = sorted(bsc.auto_counts.items()) - counts["manual"] = sorted(bsc.manual_counts.items()) - print(counts) diff --git a/modules/tools/rosbag/channel_size_stats.py b/modules/tools/rosbag/channel_size_stats.py deleted file mode 100755 index 16333706666..00000000000 --- a/modules/tools/rosbag/channel_size_stats.py +++ /dev/null @@ -1,99 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### -""" -Collect some channel average size info. - -Usage: - ./channel_size_stats.py - Support * and ?. -Example: - ./channel_size_stats.py a.record -""" - -import argparse -import glob -import os -import sys - -import glog - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3.record import RecordReader -from cyber.python.cyber_py3.record import RecordWriter -from modules.common_msgs.planning_msgs import planning_pb2 - - -class ChannelSizeStats(object): - """Sample bags to contain PNC related topics only.""" - TOPICS = [ - '/apollo/canbus/chassis', - '/apollo/control', - '/apollo/perception/obstacles', - '/apollo/perception/traffic_light', - # '/apollo/planning', - '/apollo/prediction', - '/apollo/routing_request', - '/apollo/routing_response', - '/apollo/localization/pose', - '/apollo/sensor/camera/front_6mm/image/compressed', - '/apollo/sensor/lidar128/compensator/PointCloud2' - ] - - @classmethod - def process_record(cls, input_record): - channel_size_stats = {} - freader = RecordReader(input_record) - print('----- Begin to process record -----') - for channelname, msg, datatype, timestamp in freader.read_messages(): - if channelname in ChannelSizeStats.TOPICS: - if channelname in channel_size_stats: - channel_size_stats[channelname]['total'] += len(msg) - channel_size_stats[channelname]['num'] += 1 - else: - channel_size_stats[channelname] = {} - channel_size_stats[channelname]['total'] = len(msg) - channel_size_stats[channelname]['num'] = 1.0 - elif channelname == "/apollo/planning": - adc_trajectory = planning_pb2.ADCTrajectory() - adc_trajectory.ParseFromString(msg) - name = "planning_no_debug" - adc_trajectory.ClearField("debug") - planning_str = adc_trajectory.SerializeToString() - if name in channel_size_stats: - channel_size_stats[name]['total'] += len(planning_str) - channel_size_stats[name]['num'] += 1 - else: - channel_size_stats[name] = {} - channel_size_stats[name]['total'] = len(planning_str) - channel_size_stats[name]['num'] = 1.0 - - for channelname in channel_size_stats.keys(): - print(channelname, " num:", channel_size_stats[channelname]['num'], - " avg size:", channel_size_stats[channelname]['total'] / channel_size_stats[channelname]['num']) - print('----- Finish processing record -----') - - -if __name__ == '__main__': - cyber.init() - parser = argparse.ArgumentParser( - description="Calculate channel average size. \ - Usage: 'python channel_size_stats.py input_record '") - parser.add_argument('input', type=str, help="the input record") - args = parser.parse_args() - ChannelSizeStats.process_record(args.input) - cyber.shutdown() diff --git a/modules/tools/rosbag/drive_event.py b/modules/tools/rosbag/drive_event.py deleted file mode 100755 index d52d0b2ca6f..00000000000 --- a/modules/tools/rosbag/drive_event.py +++ /dev/null @@ -1,117 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -This program can publish drive event message -""" - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import cyber_time - -import argparse -import datetime -import shutil -import time -import os -import sys - -from modules.tools.common.message_manager import PbMessageManager -from modules.tools.common import proto_utils - -g_message_manager = PbMessageManager() - -g_args = None - -g_localization = None - - -def OnReceiveLocalization(localization_msg): - global g_localization - g_localization = localization_msg - - -def main(args): - drive_event_meta_msg = g_message_manager.get_msg_meta_by_topic( - args.drive_event_topic) - if not drive_event_meta_msg: - print('Unknown drive_event topic name: %s' % args.drive_event_topic) - sys.exit(1) - - localization_meta_msg = g_message_manager.get_msg_meta_by_topic( - args.localization_topic) - if not localization_meta_msg: - print('Unknown localization topic name: %s' % args.localization_topic) - sys.exit(1) - - cyber.init() - node = cyber.Node("derive_event_node") - node.create_reader(localization_meta_msg.topic, - localization_meta_msg.msg_type, OnReceiveLocalization) - - writer = node.create_writer(drive_event_meta_msg.topic, - drive_event_meta_msg.msg_type) - seq_num = 0 - while not cyber.is_shutdown(): - event_type = input( - "Type in Event Type('d') and press Enter (current time: " + - str(datetime.datetime.now()) + ")\n>") - event_type = event_type.strip() - if len(event_type) != 1 or event_type[0].lower() != 'd': - continue - current_time = cyber_time.Time.now().to_sec() - event_str = None - while not event_str: - event_str = input("Type Event:>") - event_str = event_str.strip() - event_msg = drive_event_meta_msg.msg_type() - event_msg.header.timestamp_sec = current_time - event_msg.header.module_name = 'drive_event' - seq_num += 1 - event_msg.header.sequence_num = seq_num - event_msg.header.version = 1 - event_msg.event = event_str - if g_localization: - event_msg.location.CopyFrom(g_localization.pose) - writer.write(event_msg) - time_str = datetime.datetime.fromtimestamp(current_time).strftime( - "%Y%m%d%H%M%S") - filename = os.path.join(args.dir, "%s_drive_event.pb.txt" % time_str) - proto_utils.write_pb_to_text_file(event_msg, filename) - print('Logged to rosbag and written to file %s' % filename) - time.sleep(0.1) - - -if __name__ == '__main__': - parser = argparse.ArgumentParser( - description="A tool to write events when recording rosbag") - parser.add_argument( - "--drive_event_topic", - action="store", - default="/apollo/drive_event", - help="""the drive event topic""") - parser.add_argument( - "--localization_topic", - action="store", - default="/apollo/localization/pose", - help="""the drive event topic""") - parser.add_argument( - "--dir", - action="store", - default="data/bag", - help="""The log export directory.""") - g_args = parser.parse_args() - main(g_args) diff --git a/modules/tools/rosbag/dump_gpsbin.py b/modules/tools/rosbag/dump_gpsbin.py deleted file mode 100755 index 428a50c07dc..00000000000 --- a/modules/tools/rosbag/dump_gpsbin.py +++ /dev/null @@ -1,68 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### -""" -This program can extract raw gpsbin from rosbag directory into /tmp/gpsimu.bin. - -dump_gpsbin.py rosbag_input_directory output_file - -""" - -import argparse -import glob -import os -import shutil - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3.record import RecordReader -from modules.common_msgs.sensor_msgs import gnss_pb2 - - -g_args = None -kRawDataTopic = '/apollo/sensor/gnss/raw_data' - - -def dump_bag(in_dir, out_file): - """ - out_bag = in_bag - """ - print('Begin') - gnss = gnss_pb2.RawData() - global g_args - bag_files = glob.glob(in_dir + "/*.record.*") - with open(out_file, 'w') as fp: - for bag_file in sorted(bag_files): - print('Processing bag_file: %s' % bag_file) - reader = RecordReader(bag_file) - for msg in reader.read_messages(): - if msg.topic == kRawDataTopic: - gnss.ParseFromString(msg.message) - f.write(str(gnss)) - - -if __name__ == '__main__': - parser = argparse.ArgumentParser( - description="A tool to dump gpsimu raw data") - parser.add_argument( - "in_dir", action="store", type=str, help="the input bag directory") - parser.add_argument( - "out_file", action="store", type=str, help="the output file") - - g_args = parser.parse_args() - - dump_bag(g_args.in_dir, g_args.out_file) - print("{} is generated".format(g_args.out_file)) diff --git a/modules/tools/rosbag/dump_planning.py b/modules/tools/rosbag/dump_planning.py deleted file mode 100755 index bae1b23f4ce..00000000000 --- a/modules/tools/rosbag/dump_planning.py +++ /dev/null @@ -1,120 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -This program can dump a rosbag into separate text files that contains the pb messages -""" - -import argparse -from datetime import datetime -import os -import shutil - -from cyber.python.cyber_py3.record import RecordReader - - -g_args = None - -g_delta_t = 0.5 # 1 second approximate time match region. - - -def write_to_file(file_path, topic_pb): - """ - write pb message to file - """ - with open(file_path, 'w') as fp: - fp.write(str(topic_pb)) - - -def dump_bag(in_bag, out_dir): - """ - out_bag = in_bag + routing_bag - """ - reader = RecordReader(in_bag) - seq = 0 - global g_args - topic_name_map = { - "/apollo/localization/pose": ["localization", None], - "/apollo/canbus/chassis": ["chassis", None], - "/apollo/routing_response": ["routing", None], - "/apollo/routing_resquest": ["routing_request", None], - "/apollo/perception/obstacles": ["perception", None], - "/apollo/prediction": ["prediction", None], - "/apollo/planning": ["planning", None], - "/apollo/control": ["control", None] - } - first_time = None - record_num = 0 - for channel, message, _type, _timestamp in reader.read_messages(): - t = _timestamp - msg = message - record_num += 1 - if record_num % 1000 == 0: - print('Processing record_num: %d' % record_num) - if first_time is None: - first_time = t - if channel not in topic_name_map: - continue - dt1 = datetime.utcfromtimestamp(t/1000000000) - dt2 = datetime.utcfromtimestamp(first_time/1000000000) - relative_time = (dt1 - dt2).seconds - g_args.start_time - print ("relative_time", relative_time) - if ((g_args.time_duration > 0) and - (relative_time < 0 or relative_time > g_args.time_duration)): - continue - if channel == '/apollo/planning': - seq += 1 - topic_name_map[channel][1] = msg - print('Generating seq: %d' % seq) - for t, name_pb in topic_name_map.items(): - if name_pb[1] is None: - continue - file_path = os.path.join(out_dir, - str(seq) + "_" + name_pb[0] + ".pb.txt") - write_to_file(file_path, name_pb[1]) - topic_name_map[channel][1] = msg - - -if __name__ == '__main__': - parser = argparse.ArgumentParser( - description="A tool to dump the protobuf messages according to the planning message" - "Usage: python dump_planning.py bag_file save_directory") - parser.add_argument( - "in_rosbag", action="store", type=str, help="the input ros bag") - parser.add_argument( - "out_dir", - action="store", - help="the output directory for the dumped file") - parser.add_argument( - "--start_time", - type=float, - action="store", - default=0.0, - help="""The time range to extract in second""") - parser.add_argument( - "--time_duration", - type=float, - action="store", - default=-1, - help="""time duration to extract in second, negative to extract all""") - - g_args = parser.parse_args() - - if os.path.exists(g_args.out_dir): - shutil.rmtree(g_args.out_dir) - os.makedirs(g_args.out_dir) - dump_bag(g_args.in_rosbag, g_args.out_dir) diff --git a/modules/tools/rosbag/dump_record.py b/modules/tools/rosbag/dump_record.py deleted file mode 100755 index e8598f59d97..00000000000 --- a/modules/tools/rosbag/dump_record.py +++ /dev/null @@ -1,119 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -This program can dump a cyber record into separate text files that contains -the pb messages -""" - -import argparse -import os -import shutil -import sys -import time - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import record -from modules.tools.common.message_manager import PbMessageManager - - -g_message_manager = PbMessageManager() - - -def write_to_file(file_path, topic_pb): - """ - Write pb message to file - """ - with open(file_path, 'w') as fp: - fp.write(str(topic_pb)) - - -def dump_record(in_record, out_dir, start_time, duration, filter_topic): - freader = record.RecordReader() - if not freader.open(in_record): - print('Failed to open: %s' % in_record) - return - time.sleep(1) - seq = 0 - while not freader.endoffile(): - read_msg_succ = freader.read_message() - if not read_msg_succ: - print('Read failed') - return - t_sec = freader.currentmessage_time() - if start_time and t_sec < start_time: - print('Not yet reached the start time') - continue - if start_time and t_sec >= start_time + duration: - print('Done') - break - topic = freader.currentmessage_channelname() - msg_type = freader.get_messagetype(topic) - if topic == '/apollo/sensor/mobileye': - continue - if not filter_topic or topic == filter_topic: - message_file = topic.replace("/", "_") - file_path = os.path.join(out_dir, - str(seq) + message_file + ".pb.txt") - meta_msg = g_message_manager.get_msg_meta_by_topic(topic) - if meta_msg is None: - print('Unknown topic: %s' % topic) - continue - msg = meta_msg.msg_type() - msg.ParseFromString(freader.current_rawmessage()) - write_to_file(file_path, msg) - seq += 1 - freader.close() - - -if __name__ == '__main__': - parser = argparse.ArgumentParser( - description="A tool to dump the protobuf messages in a cyber record into text files" - ) - parser.add_argument( - "in_record", - action="store", - type=str, - help="the input cyber record") - parser.add_argument( - "--start_time", - action="store", - type=float, - help="the input cyber record") - parser.add_argument( - "--duration", - action="store", - type=float, - default=1.0, - help="the input cyber record") - parser.add_argument( - "out_dir", - action="store", - help="the output directory for the dumped file") - parser.add_argument( - "--topic", - action="store", - help="""the topic that you want to dump. If this option is not provided, - the tool will dump all the messages regardless of the message topic.""" - ) - args = parser.parse_args() - if not os.path.exists(args.out_dir): - print('%s does not exist' % args.out_dir) - sys.exit(1) - - dump_record(args.in_record, args.out_dir, args.start_time, args.duration, - args.topic) diff --git a/modules/tools/rosbag/dump_road_test_log.py b/modules/tools/rosbag/dump_road_test_log.py deleted file mode 100755 index 644c4ffbf98..00000000000 --- a/modules/tools/rosbag/dump_road_test_log.py +++ /dev/null @@ -1,76 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### -""" -dump road test log. -Usage: - ./dump_road_test_log.py bag1 bag2 ... -""" - -import sys -import time - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3.record import RecordReader -from modules.common_msgs.basic_msgs import drive_event_pb2 - - -kEventTopic = '/apollo/drive_event' - - -class EventDumper(object): - """ - Dump event - """ - - def __init__(self): - """ - Init - """ - - def calculate(self, bag_file): - """ - Calculate mileage - """ - try: - drive_event = drive_event_pb2.DriveEvent() - reader = RecordReader(bag_file) - except Exception: - print('Cannot open bag file %s' % bag_file) - else: - with open('/apollo/test.txt', 'a') as fp: - for msg in reader.read_messages(): - if msg.topic == kEventTopic: - drive_event.ParseFromString(msg.message) - msg_time = time.localtime(drive_event.header.timestamp_sec) - fp.write(time.strftime("%Y-%m-%d %H:%M:%S", msg_time)) - fp.write(str(drive_event.type) + ':') - fp.write(drive_event.event.encode('utf-8') + '\n') - - -def main(): - if len(sys.argv) < 2: - print('Usage: %s ...' % sys.argv[0]) - sys.exit(0) - - ed = EventDumper() - for bag_file in sys.argv[1:]: - ed.calculate(bag_file) - - -if __name__ == '__main__': - main() diff --git a/modules/tools/rosbag/extract_trajectory.py b/modules/tools/rosbag/extract_trajectory.py deleted file mode 100755 index 10172aa3af1..00000000000 --- a/modules/tools/rosbag/extract_trajectory.py +++ /dev/null @@ -1,90 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### -""" -This program can extract driving trajectory from a record -""" - -import argparse -import os -import shutil -import sys -import time - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import record -from modules.tools.common.message_manager import PbMessageManager - - -g_message_manager = PbMessageManager() - - -def write_to_file(file_path, topic_pb): - """ - write pb message to file - """ - with open(file_path, 'w') as fp: - fp.write(str(topic_pb)) - - -def extract_record(in_record, output): - freader = record.RecordReader(in_record) - print("begin to extract from record {}".format(in_record)) - time.sleep(1) - seq = 0 - localization_topic = '/apollo/localization/pose' - meta_msg = g_message_manager.get_msg_meta_by_topic(localization_topic) - localization_type = meta_msg.msg_type - for channelname, msg_data, datatype, timestamp in freader.read_messages(): - topic = channelname - if topic != localization_topic: - continue - msg = localization_type() - msg.ParseFromString(msg_data) - pose = msg.pose - output.write("%s %s %s %s %s %s %s %s\n" % - (msg.measurement_time, pose.position.x, pose.position.y, - pose.position.z, pose.orientation.qx, - pose.orientation.qy, pose.orientation.qz, - pose.orientation.qw)) - print("Finished extracting from record {}".format(in_record)) - - -def main(args): - out = open(args.output, 'w') if args.output or sys.stdout - for record_file in args.in_record: - extract_record(record_file, out) - out.close() - - -if __name__ == '__main__': - parser = argparse.ArgumentParser( - description="A tool to dump the localization messages for map team" - "Usage: python extract_trajectory.py bag1 bag2 --output output.txt") - parser.add_argument( - "in_record", - action="store", - nargs='+', - type=str, - help="the input cyber record(s)") - parser.add_argument( - "--output", - action="store", - type=str, - help="the output file, default is stdout") - args = parser.parse_args() - main(args) diff --git a/modules/tools/rosbag/sample_pnc_topics.py b/modules/tools/rosbag/sample_pnc_topics.py deleted file mode 100755 index 3922a774cd5..00000000000 --- a/modules/tools/rosbag/sample_pnc_topics.py +++ /dev/null @@ -1,104 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### -""" -Sample PNC topics. For each /path/to/a.record, will generate -/path/to/pnc_sample/a.record. - -Usage: - ./sample_pnc_topics.py - Support * and ?. -Example: - ./sample_pnc_topics.py '/mnt/nfs/public_test/2018-04-??/*/mkz8/*/*.record' -""" - -import argparse -import glob -import os -import sys - -import glog - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3.record import RecordReader -from cyber.python.cyber_py3.record import RecordWriter - - -class SamplePNC(object): - """Sample bags to contain PNC related topics only.""" - TOPICS = [ - '/apollo/sensor/conti_radar', - '/apollo/sensor/delphi_esr', - '/apollo/sensor/gnss/best_pose', - '/apollo/sensor/gnss/corrected_imu', - '/apollo/sensor/gnss/gnss_status', - '/apollo/sensor/gnss/imu', - '/apollo/sensor/gnss/ins_stat', - '/apollo/sensor/gnss/odometry', - '/apollo/sensor/gnss/rtk_eph', - '/apollo/sensor/gnss/rtk_obs', - '/apollo/sensor/mobileye', - '/apollo/canbus/chassis', - '/apollo/canbus/chassis_detail', - '/apollo/control', - '/apollo/control/pad', - '/apollo/navigation', - '/apollo/perception/obstacles', - '/apollo/perception/traffic_light', - '/apollo/planning', - '/apollo/prediction', - '/apollo/routing_request', - '/apollo/routing_response', - '/apollo/localization/pose', - '/apollo/drive_event', - '/tf', - '/tf_static', - '/apollo/monitor', - '/apollo/monitor/system_status', - '/apollo/monitor/static_info', - ] - - @classmethod - def process_record(cls, input_record, output_record): - print("filtering: {} -> {}".format(input_record, output_record)) - output_dir = os.path.dirname(output_record) - if output_dir != "" and not os.path.exists(output_dir): - os.makedirs(output_dir) - freader = RecordReader(input_record) - fwriter = RecordWriter() - if not fwriter.open(output_record): - print('writer open failed!') - return - print('----- Begin to process record -----') - for channelname, msg, datatype, timestamp in freader.read_messages(): - if channelname in SamplePNC.TOPICS: - desc = freader.get_protodesc(channelname) - fwriter.write_channel(channelname, datatype, desc) - fwriter.write_message(channelname, msg, timestamp) - print('----- Finish processing record -----') - - -if __name__ == '__main__': - cyber.init() - parser = argparse.ArgumentParser( - description="Filter pnc record. \ - Usage: 'python sample_pnc_topic.py input_record output_record'") - parser.add_argument('input', type=str, help="the input record") - parser.add_argument('output', type=str, help="the output record") - args = parser.parse_args() - SamplePNC.process_record(args.input, args.output) - cyber.shutdown() diff --git a/modules/tools/rosbag/stat_mileage.py b/modules/tools/rosbag/stat_mileage.py deleted file mode 100755 index 09b45729242..00000000000 --- a/modules/tools/rosbag/stat_mileage.py +++ /dev/null @@ -1,102 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -Stat disengagements and auto/manual driving mileage. -Usage: - ./stat_mileage.py bag1 bag2 ... -""" - -import collections -import math -import sys - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3.record import RecordReader -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.chassis_msgs.chassis_pb2 import Chassis -from modules.common_msgs.localization_msgs import localization_pb2 - - -kChassisTopic = '/apollo/canbus/chassis' -kLocalizationTopic = '/apollo/localization/pose' - - -class MileageCalculator(object): - """ - Calculate mileage - """ - - def __init__(self): - """Init.""" - self.auto_mileage = 0.0 - self.manual_mileage = 0.0 - self.disengagements = 0 - - def calculate(self, bag_file): - """ - Calculate mileage - """ - last_pos = None - last_mode = 'Unknown' - mileage = collections.defaultdict(lambda: 0.0) - chassis = chassis_pb2.Chassis() - localization = localization_pb2.LocalizationEstimate() - reader = RecordReader(bag_file) - for msg in reader.read_messages(): - if msg.topic == kChassisTopic: - chassis.ParseFromString(msg.message) - # Mode changed - if last_mode != chassis.driving_mode: - if (last_mode == Chassis.COMPLETE_AUTO_DRIVE and - chassis.driving_mode == Chassis.EMERGENCY_MODE): - self.disengagements += 1 - last_mode = chassis.driving_mode - # Reset start position. - last_pos = None - elif msg.topic == kLocalizationTopic: - localization.ParseFromString(msg.message) - cur_pos = localization.pose.position - if last_pos: - # Accumulate mileage, from xyz-distance to miles. - mileage[last_mode] += 0.000621371 * math.sqrt( - (cur_pos.x - last_pos.x) ** 2 + - (cur_pos.y - last_pos.y) ** 2 + - (cur_pos.z - last_pos.z) ** 2) - last_pos = cur_pos - self.auto_mileage += mileage[Chassis.COMPLETE_AUTO_DRIVE] - self.manual_mileage += (mileage[Chassis.COMPLETE_MANUAL] + - mileage[Chassis.EMERGENCY_MODE]) - - -def main(): - if len(sys.argv) < 2: - print('Usage: %s [Bag_file1] [Bag_file2] ...' % sys.argv[0]) - sys.exit(0) - - mc = MileageCalculator() - for bag_file in sys.argv[1:]: - mc.calculate(bag_file) - print('Disengagements: %d' % mc.disengagements) - print('Auto mileage: %.3f km / %.3f miles' % - (mc.auto_mileage * 1.60934, mc.auto_mileage)) - print('Manual mileage: %.3f km / %.3f miles' % - (mc.manual_mileage * 1.60934, mc.manual_mileage)) - - -if __name__ == '__main__': - main() diff --git a/modules/tools/rosbag/stat_static_info.py b/modules/tools/rosbag/stat_static_info.py deleted file mode 100755 index cd167145f5a..00000000000 --- a/modules/tools/rosbag/stat_static_info.py +++ /dev/null @@ -1,127 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -Stat static info. -Usage: - ./stat_static_info.py - ./stat_static_info.py # contains a list of records. -""" - -import os -import sys - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3.record import RecordReader -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.dreamview_msgs import hmi_status_pb2 - - -kChassisInfoTopic = '/apollo/canbus/chassis' -kHMIInfoTopic = '/apollo/hmi/status' - - -class StaticInfoCalculator(object): - """ - Stat static information - """ - - def __init__(self): - self.vehicle_name = None - self.vehicle_vin = None - - def process_file(self, record_file): - """ - Extract information from record file. - Return True if we are done collecting all information. - """ - try: - reader = RecordReader(record_file) - print("Begin to process record file {}".format(record_file)) - for msg in reader.read_messages(): - print(msg.topic) - if msg.topic == kChassisInfoTopic and self.vehicle_vin is None: - chassis = chassis_pb2.Chassis() - chassis.ParseFromString(msg.message) - if chassis.license.vin: - self.vehicle_vin = chassis.license.vin - elif msg.topic == kHMIInfoTopic and self.vehicle_name is None: - hmistatus = hmi_status_pb2.HMIStatus() - hmistatus.ParseFromString(msg.message) - if hmistatus.current_map: - self.vehicle_name = hmistatus.current_map - print(self.vehicle_name) - if self.done(): - return True - except: - return False - print("Finished processing record file {}".format(record_file)) - return self.done() - - def process_dir(self, record_dir): - """ - Process a directory - """ - files = [] - dirs = [] - for f in os.listdir(record_dir): - f_path = os.path.join(record_dir, f) - if os.path.isfile(f_path): - files.append(f_path) - elif os.path.isdir(f_path): - dirs.append(f_path) - # Ignore links. - - # Reverse sort the records or dirs, trying to get info from the latest. - for record in sorted(files, reverse=True): - if self.process_file(record): - return True - for subdir in sorted(dirs, reverse=True): - if self.process_dir(subdir): - return True - return False - - def done(self): - """ - Check if all info are collected - """ - # Currently we only care about vehicle name. - return bool(self.vehicle_name) - - -def main(): - """ - Process a path - """ - if len(sys.argv) < 2: - print("Usage: %s " % sys.argv[0]) - sys.exit(0) - - path = sys.argv[1] - calc = StaticInfoCalculator() - if os.path.isfile(path): - calc.process_file(path) - else: - calc.process_dir(path) - - # Output result, which might be None - print('vehicle_name: %s' % calc.vehicle_name) - print('vehicle_vin: %s' % calc.vehicle_vin) - - -if __name__ == '__main__': - main() diff --git a/modules/tools/rosbag/tf_stats.py b/modules/tools/rosbag/tf_stats.py deleted file mode 100755 index 253003bd5ea..00000000000 --- a/modules/tools/rosbag/tf_stats.py +++ /dev/null @@ -1,62 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### -""" -This program can dump tf2 stats - -usage: - tf_stats -f record_file -""" - -import argparse - -from cyber.python.cyber_py3.record import RecordReader -from modules.common_msgs.transform_msgs import transform_pb2 - - -g_args = None - - -def tf_stats(in_bag): - """ - """ - reader = RecordReader(in_bag) - global g_args - stats = {} - - for channel, message, _type, _timestamp in reader.read_messages(): - if channel != '/tf': - continue - tf_pb = transform_pb2.TransformStampeds() - tf_pb.ParseFromString(message) - for transform in tf_pb.transforms: - key = transform.header.frame_id + "=>" + transform.child_frame_id - if key in stats.keys(): - stats[key] += 1 - else: - stats[key] = 1 - print('tf stats: {}'.format(stats)) - - -if __name__ == '__main__': - parser = argparse.ArgumentParser( - description="A tool to print tf stats") - parser.add_argument( - "-f", action="store", type=str, help="the input data file") - g_args = parser.parse_args() - - tf_stats(g_args.f) diff --git a/modules/tools/rosbag/transcribe.py b/modules/tools/rosbag/transcribe.py deleted file mode 100755 index b75f629147c..00000000000 --- a/modules/tools/rosbag/transcribe.py +++ /dev/null @@ -1,72 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -This program can transcribe a protobuf message to file -""" - -import argparse -import shutil -import os -import sys -import time - -from cyber.python.cyber_py3 import cyber -from modules.tools.common.message_manager import PbMessageManager -import modules.tools.common.proto_utils as proto_utils - - -g_message_manager = PbMessageManager() -g_args = None - - -def transcribe(proto_msg): - header = proto_msg.header - seq = "%05d" % header.sequence_num - name = header.module_name - file_path = os.path.join(g_args.out_dir, seq + "_" + name + ".pb.txt") - print('Write proto buffer message to file: %s' % file_path) - proto_utils.write_pb_to_text_file(proto_msg, file_path) - - -def main(args): - if not os.path.exists(args.out_dir): - os.makedirs(args.out_dir) - meta_msg = g_message_manager.get_msg_meta_by_topic(args.topic) - if not meta_msg: - print('Unknown topic name: %s' % args.topic) - sys.exit(1) - cyber.init() - node = cyber.Node("transcribe_node") - node.create_reader(args.topic, meta_msg.msg_type, transcribe) - while not cyber.is_shutdown(): - time.sleep(0.005) - - -if __name__ == '__main__': - parser = argparse.ArgumentParser( - description="A tool to transcribe received protobuf messages into text files") - parser.add_argument( - "topic", action="store", help="the topic that you want to transcribe.") - parser.add_argument( - "--out_dir", - action="store", - default='.', - help="the output directory for the dumped file, the default value is current directory" - ) - g_args = parser.parse_args() - main(g_args) diff --git a/modules/tools/routing/BUILD b/modules/tools/routing/BUILD deleted file mode 100644 index e91d684cd90..00000000000 --- a/modules/tools/routing/BUILD +++ /dev/null @@ -1,66 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -install( - name = "install", - py_dest = "tools/routing", - targets = [ - ":debug_passage_region", - ":debug_route", - ":road_show", - ], -) - -py_binary( - name = "debug_passage_region", - srcs = ["debug_passage_region.py"], - deps = [ - ":debug_topo", - "//modules/common_msgs/routing_msgs:routing_py_pb2", - "//modules/routing/proto:topo_graph_py_pb2", - "//modules/tools/common:proto_utils", - ], -) - -py_binary( - name = "debug_route", - srcs = ["debug_route.py"], - deps = [ - ":debug_topo", - ":util", - "//modules/routing/proto:topo_graph_py_pb2", - "//modules/tools/common:proto_utils", - ], -) - -py_library( - name = "debug_topo", - srcs = ["debug_topo.py"], - deps = [ - ":util", - "//modules/routing/proto:topo_graph_py_pb2", - "//modules/tools/common:proto_utils", - ], -) - -py_binary( - name = "road_show", - srcs = ["road_show.py"], - deps = [ - ":util", - "//modules/tools/common:proto_utils", - ], -) - -py_library( - name = "util", - srcs = ["util.py"], - deps = [ - "//modules/common_msgs/map_msgs:map_py_pb2", - "//modules/common_msgs/routing_msgs:routing_py_pb2", - "//modules/routing/proto:topo_graph_py_pb2", - "//modules/tools/common:proto_utils", - ], -) diff --git a/modules/tools/routing/debug_passage_region.py b/modules/tools/routing/debug_passage_region.py deleted file mode 100644 index d888ebc4198..00000000000 --- a/modules/tools/routing/debug_passage_region.py +++ /dev/null @@ -1,155 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import itertools -import sys - -import matplotlib.pyplot as plt - -import modules.tools.common.proto_utils as proto_utils -import modules.tools.routing.debug_topo as debug_topo -from modules.common_msgs.routing_msgs.routing_pb2 import RoutingResponse -from modules.routing.proto.topo_graph_pb2 import Graph - - -color_iter = itertools.cycle( - ['navy', 'c', 'cornflowerblue', 'gold', 'darkorange']) -g_central_curve_dict = {} -g_center_point_dict = {} - - -def get_center_of_passage_region(region): - """Get center of passage region center curve""" - center_points = [g_center_point_dict[seg.id] for seg in region.segment] - return center_points[len(center_points) // 2] - - -def plot_region(region, color): - "Plot passage region" - for seg in region.segment: - center_pt = debug_topo.plot_central_curve_with_s_range( - g_central_curve_dict[seg.id], seg.start_s, seg.end_s, color=color) - debug_topo.draw_id(center_pt, seg.id, 'r') - g_center_point_dict[seg.id] = center_pt - print('Plot lane id: %s, start s: %f, end s: %f' % (seg.id, seg.start_s, - seg.end_s)) - - -def plot_lane_change(lane_change, passage_regions): - """Plot lane change information""" - st_idx = lane_change.start_passage_region_index - ed_idx = lane_change.end_passage_region_index - from_pt = get_center_of_passage_region(passage_regions[st_idx]) - to_pt = get_center_of_passage_region(passage_regions[ed_idx]) - plt.gca().annotate( - "", - xy=(to_pt[0], to_pt[1]), - xytext=(from_pt[0], from_pt[1]), - arrowprops=dict( - facecolor='blue', edgecolor='none', alpha=0.7, shrink=0.05)) - - -def plot_road(road): - """Plot road""" - for region in road.passage_region: - plot_region(region, 'green') - for lane_change in road.lane_change_info: - plot_lane_change(lane_change, road.passage_region) - - -def plot_junction(junction): - """Plot junction""" - plot_region(junction.passage_region, 'red') - - -def plot_result(routing_result, central_curve_dict): - """Plot routing result""" - plt.close() - plt.figure() - for way in routing_result.route: - if way.HasField("road_info"): - plot_road(way.road_info) - else: - plot_junction(way.junction_info) - - plt.gca().set_aspect(1) - plt.title('Passage region') - plt.xlabel('x') - plt.ylabel('y') - plt.legend() - - plt.draw() - - -def print_help(): - """Print help information. - - Print help information of usage. - - Args: - - """ - print('usage:') - print(' python debug_topo.py file_path, then', end=' ') - print_help_command() - - -def print_help_command(): - """Print command help information. - - Print help information of command. - - Args: - - """ - print('type in command: [q] [r]') - print(' q exit') - print(' p plot passage region') - - -if __name__ == '__main__': - if len(sys.argv) != 3: - print_help() - sys.exit(0) - print('Please wait for loading data...') - - topo_graph_file = sys.argv[1] - graph = proto_utils.get_pb_from_bin_file(topo_graph_file, Graph()) - g_central_curve_dict = {nd.lane_id: nd.central_curve for nd in graph.node} - - plt.ion() - while 1: - print_help_command() - print('cmd>', end=' ') - instruction = raw_input() - argv = instruction.strip(' ').split(' ') - if len(argv) == 1: - if argv[0] == 'q': - sys.exit(0) - elif argv[0] == 'p': - routing_result_file = sys.argv[2] - result = proto_utils.get_pb_from_bin_file(routing_result_file, - RoutingResponse()) - plot_result(result, g_central_curve_dict) - else: - print('[ERROR] wrong command') - continue - - else: - print('[ERROR] wrong arguments') - continue diff --git a/modules/tools/routing/debug_route.py b/modules/tools/routing/debug_route.py deleted file mode 100644 index 9c2e6bb8950..00000000000 --- a/modules/tools/routing/debug_route.py +++ /dev/null @@ -1,118 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import itertools -import os -import sys - -import gflags -import matplotlib.pyplot as plt - -import modules.tools.routing.debug_topo as debug_topo -import modules.routing.proto.topo_graph_pb2 as topo_graph_pb2 -import modules.tools.routing.util as util - -color_iter = itertools.cycle( - ['navy', 'c', 'cornflowerblue', 'gold', 'darkorange']) - - -def read_route(route_file_name): - """Read route result text file""" - fin = open(route_file_name) - route = [] - for line in fin: - lane = {} - items = line.strip().split(',') - lane['id'] = items[0] - lane['is virtual'] = int(items[1]) - lane['start s'] = float(items[2]) - lane['end s'] = float(items[3]) - route.append(lane) - return route - - -def plot_route(lanes, central_curve_dict): - """Plot route result""" - plt.close() - plt.figure() - for lane in lanes: - lane_id = lane['id'] - if lane['is virtual']: - color = 'red' - else: - color = 'green' - mid_pt = debug_topo.plot_central_curve_with_s_range( - central_curve_dict[lane_id], - lane['start s'], - lane['end s'], - color=color) - debug_topo.draw_id(mid_pt, lane_id, 'y') - plt.gca().set_aspect(1) - plt.title('Routing result') - plt.xlabel('x') - plt.ylabel('y') - plt.legend() - - plt.draw() - - -def print_help_command(): - """Print command help information. - - Print help information of command. - - Args: - - """ - print('type in command: [q] [r]') - print(' q exit') - print(' r plot route result') - print(' r_map plot route result with map') - - -if __name__ == '__main__': - map_dir = util.get_map_dir(sys.argv) - graph = util.get_topodata(map_dir) - base_map = util.get_mapdata(map_dir) - route = util.get_routingdata() - - central_curves = {} - for nd in graph.node: - central_curves[nd.lane_id] = nd.central_curve - - plt.ion() - while 1: - print_help_command() - print('cmd>', end=' ') - instruction = raw_input() - argv = instruction.strip(' ').split(' ') - if len(argv) == 1: - if argv[0] == 'q': - sys.exit(0) - elif argv[0] == 'r': - plot_route(route, central_curves) - elif argv[0] == 'r_map': - plot_route(route, central_curves) - util.draw_map(plt.gca(), base_map) - else: - print('[ERROR] wrong command') - continue - - else: - print('[ERROR] wrong arguments') - continue diff --git a/modules/tools/routing/debug_topo.py b/modules/tools/routing/debug_topo.py deleted file mode 100644 index 238a3d62001..00000000000 --- a/modules/tools/routing/debug_topo.py +++ /dev/null @@ -1,257 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import itertools -import math -import sys - -import matplotlib.pyplot as plt - -import modules.tools.common.proto_utils as proto_utils -import modules.routing.proto.topo_graph_pb2 as topo_graph_pb2 -import modules.tools.routing.util as util - - -color_iter = itertools.cycle( - ['navy', 'c', 'cornflowerblue', 'gold', 'darkorange']) - - -def calculate_s(px, py): - """Calculate s array based on x and y arrays""" - dis = 0.0 - ps = [dis] - for i in range(len(px) - 1): - gap = math.sqrt(pow(px[i + 1] - px[i], 2) + pow(py[i + 1] - py[i], 2)) - dis = dis + gap - ps.append(dis) - return ps - - -def draw_line(line, color): - """draw line, return x array and y array""" - px, py = proto_utils.flatten(line.point, ['x', 'y']) - px, py = util.downsample_array(px), util.downsample_array(py) - plt.gca().plot(px, py, color=color, lw=3, alpha=0.8) - return px, py - - -def draw_arc(arc): - """draw arc""" - xy = (arc.center.x, arc.center.y) - start = 0 - end = 0 - if arc.start_angle < arc.end_angle: - start = arc.start_angle / math.pi * 180 - end = arc.end_angle / math.pi * 180 - else: - end = arc.start_angle / math.pi * 180 - start = arc.end_angle / math.pi * 180 - - pac = mpatches.Arc( - xy, arc.radius * 2, arc.radius * 2, angle=0, theta1=start, theta2=end) - - plt.gca().add_patch(pac) - - -def draw_id(coordinate, id_string, color): - """draw id""" - x = coordinate[0] - y = coordinate[1] - plt.annotate( - id_string, - xy=(x, y), - xytext=(30, 30), - textcoords='offset points', - bbox=dict(boxstyle='round,pad=0.5', fc=color, alpha=0.5), - arrowprops=dict(arrowstyle='->', connectionstyle='arc3,rad=0'), - horizontalalignment='right', - verticalalignment='bottom') - - -def plot_central_curve_with_s_range(central_curve, start_s, end_s, color): - """plot topology graph node with given start and end s, return middle point""" - node_x = [] - node_y = [] - for curve in central_curve.segment: - px, py = proto_utils.flatten(curve.line_segment.point, ['x', 'y']) - node_x.extend(px) - node_y.extend(py) - start_plot_index = 0 - end_plot_index = len(node_x) - node_s = calculate_s(node_x, node_y) - for i in range(len(node_s)): - if node_s[i] >= start_s: - start_plot_index = i - break - for i in range(len(node_s) - 1, -1, -1): - if node_s[i] <= end_s: - end_plot_index = i + 1 - break - plt.gca().plot( - node_x[start_plot_index:end_plot_index], - node_y[start_plot_index:end_plot_index], - color=color, - lw=3, - alpha=0.8) - mid_index = (start_plot_index + end_plot_index) // 2 - return [node_x[mid_index], node_y[mid_index]] - - -def plot_central_curve(central_curve, color): - """plot topology graph node, return node middle point""" - node_x = [] - node_y = [] - for curve in central_curve.segment: - if curve.HasField('line_segment'): - px, py = draw_line(curve.line_segment, color) - node_x = node_x + px - node_y = node_y + py - # if curve.HasField('arc'): - # draw_arc(curve.arc) - return [node_x[len(node_x) // 2], node_y[len(node_y) // 2]] - - -def plot_node(node, plot_id, color): - """plot topology graph node""" - print('length of %s: %f' % (node.lane_id, node.length)) - mid_pt = plot_central_curve(node.central_curve, color) - if 'l' in plot_id: - draw_id(mid_pt, node.lane_id, 'green') - if 'r' in plot_id: - draw_id(mid_pt, node.road_id, 'red') - return mid_pt - - -def plot_edge(edge, midddle_point_map): - """plot topology graph edge""" - if edge.direction_type == topo_graph_pb2.Edge.FORWARD: - return - # if lane change is allowed, draw an arrow from lane with from_id to lane with to_id - from_id = edge.from_lane_id - from_pt = midddle_point_map[from_id] - to_id = edge.to_lane_id - to_pt = midddle_point_map[to_id] - plt.gca().annotate( - "", - xy=(to_pt[0], to_pt[1]), - xytext=(from_pt[0], from_pt[1]), - arrowprops=dict(arrowstyle="->", connectionstyle="arc3")) - - -def plot_all(graph, plot_id=''): - """plot topology graph""" - plt.close() - fig = plt.figure() - fig.canvas.mpl_connect('button_press_event', util.onclick) - lane_middle_point_map = {} - for i, (nd, color) in enumerate(zip(graph.node, color_iter)): - nd_mid_pt = plot_node(nd, plot_id, color) - lane_middle_point_map[nd.lane_id] = nd_mid_pt - for i, eg in enumerate(graph.edge): - plot_edge(eg, lane_middle_point_map) - plt.gca().set_aspect(1) - plt.title('Routing topology graph') - plt.xlabel('x') - plt.ylabel('y') - plt.legend() - - plt.draw() - - -def plot_id(graph, lane_id): - """plot topology graph""" - plt.close() - fig = plt.figure() - fig.canvas.mpl_connect('button_press_event', util.onclick) - lane_middle_point_map = {} - plot_ids = [lane_id] - for eg in graph.edge: - if eg.from_lane_id == lane_id: - plot_ids.append(eg.to_lane_id) - for i, (nd, color) in enumerate(zip(graph.node, color_iter)): - if nd.lane_id in plot_ids: - nd_mid_pt = plot_node(nd, 'l', color) - lane_middle_point_map[nd.lane_id] = nd_mid_pt - for i, eg in enumerate(graph.edge): - if eg.from_lane_id == lane_id: - plot_edge(eg, lane_middle_point_map) - plt.gca().set_aspect(1) - plt.title('Routing topology graph') - plt.xlabel('x') - plt.ylabel('y') - plt.legend() - - plt.draw() - - -def print_help_command(): - """Print command help information. - - Print help information of command. - - Args: - - """ - print('type in command: [q] [a] [i lane_id]') - print(' q exit') - print(' a plot all topology') - print(' a_id plot all topology with lane id') - print(' a_rid plot all topology with road id') - print(' i lane_id plot lanes could be reached from lane with lane_id') - print(' i_map lane_id plot lanes could be reached from lane with lane_id, with map') - - -if __name__ == '__main__': - map_dir = util.get_map_dir(sys.argv) - graph = util.get_topodata(map_dir) - base_map = util.get_mapdata(map_dir) - print("district: %s" % graph.hdmap_district) - print("version: %s" % graph.hdmap_version) - - plt.ion() - while 1: - print_help_command() - print('cmd>', end=' ') - instruction = raw_input() - argv = instruction.strip(' ').split(' ') - if len(argv) == 1: - if argv[0] == 'q': - sys.exit(0) - elif argv[0] == 'a': - plot_all(graph) - elif argv[0] == 'a_id': - plot_all(graph, 'l') - elif argv[0] == 'a_rid': - plot_all(graph, 'r') - else: - print('[ERROR] wrong command') - continue - - if len(argv) == 2: - if argv[0] == 'i': - plot_id(graph, argv[1]) - elif argv[0] == 'i_map': - plot_id(graph, argv[1]) - util.draw_map(plt.gca(), base_map) - else: - print('[ERROR] wrong command') - continue - - else: - print('[ERROR] wrong arguments') - continue diff --git a/modules/tools/routing/road_show.py b/modules/tools/routing/road_show.py deleted file mode 100644 index a374ee39704..00000000000 --- a/modules/tools/routing/road_show.py +++ /dev/null @@ -1,156 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -"""Show road.""" - -import sys - -import matplotlib.pyplot as plt - -import modules.tools.common.proto_utils as proto_utils -import modules.tools.routing.util as util - - -g_color = [ - 'navy', 'c', 'cornflowerblue', 'gold', 'darkorange', 'darkviolet', - 'aquamarine', 'firebrick', 'limegreen' -] - - -def draw_line(line_segment, color): - """ - :param line_segment: - :return: none - """ - px, py = proto_utils.flatten(line_segment.point, ['x', 'y']) - px, py = downsample_array(px), downsample_array(py) - plt.gca().plot(px, py, lw=10, alpha=0.8, color=color) - return px[len(px) // 2], py[len(py) // 2] - - -def draw_arc(arc): - """ - :param arc: proto obj - :return: none - """ - xy = (arc.center.x, arc.center.y) - start = 0 - end = 0 - if arc.start_angle < arc.end_angle: - start = arc.start_angle / math.pi * 180 - end = arc.end_angle / math.pi * 180 - else: - end = arc.start_angle / math.pi * 180 - start = arc.end_angle / math.pi * 180 - - pac = mpatches.Arc( - xy, arc.radius * 2, arc.radius * 2, angle=0, theta1=start, theta2=end) - - plt.gca().add_patch(pac) - - -def downsample_array(array): - """down sample given array""" - skip = 5 - result = array[::skip] - result.append(array[-1]) - return result - - -def draw_boundary(line_segment): - """ - :param line_segment: - :return: - """ - px, py = proto_utils.flatten(line_segment.point, ['x', 'y']) - px, py = downsample_array(px), downsample_array(py) - plt.gca().plot(px, py, 'k') - - -def draw_id(x, y, id_string): - """Draw id_string on (x, y)""" - plt.annotate( - id_string, - xy=(x, y), - xytext=(40, -40), - textcoords='offset points', - ha='right', - va='bottom', - bbox=dict(boxstyle='round,pad=0.5', fc='green', alpha=0.5), - arrowprops=dict(arrowstyle='->', connectionstyle='arc3,rad=0')) - - -def get_road_index_of_lane(lane_id, road_lane_set): - """Get road index of lane""" - for i, lane_set in enumerate(road_lane_set): - if lane_id in lane_set: - return i - return -1 - - -def draw_map(drivemap): - """ draw map from mapfile""" - print('Map info:') - print('\tVersion:\t', end=' ') - print(drivemap.header.version) - print('\tDate:\t', end=' ') - print(drivemap.header.date) - print('\tDistrict:\t', end=' ') - print(drivemap.header.district) - - road_lane_set = [] - for road in drivemap.road: - lanes = [] - for sec in road.section: - lanes.extend(proto_utils.flatten(sec.lane_id, 'id')) - road_lane_set.append(lanes) - - for lane in drivemap.lane: - for curve in lane.central_curve.segment: - if curve.HasField('line_segment'): - road_idx = get_road_index_of_lane(lane.id.id, road_lane_set) - if road_idx == -1: - print('Failed to get road index of lane') - sys.exit(-1) - center_x, center_y = draw_line(curve.line_segment, - g_color[road_idx % len(g_color)]) - draw_id(center_x, center_y, str(road_idx)) - # break - # if curve.HasField('arc'): - # draw_arc(curve.arc) - - for curve in lane.left_boundary.curve.segment: - if curve.HasField('line_segment'): - draw_boundary(curve.line_segment) - - for curve in lane.right_boundary.curve.segment: - if curve.HasField('line_segment'): - draw_boundary(curve.line_segment) - # break - - return drivemap - - -if __name__ == "__main__": - print("Reading map data") - map_dir = util.get_map_dir(sys.argv) - base_map = util.get_mapdata(map_dir) - print("Done reading map data") - plt.subplots() - draw_map(base_map) - plt.axis('equal') - plt.show() diff --git a/modules/tools/routing/util.py b/modules/tools/routing/util.py deleted file mode 100644 index bd53881acc2..00000000000 --- a/modules/tools/routing/util.py +++ /dev/null @@ -1,122 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import os -import sys - -import gflags -import matplotlib.pyplot as plt - -import modules.tools.common.proto_utils as proto_utils -import modules.common_msgs.map_msgs.map_pb2 as map_pb2 -import modules.routing.proto.topo_graph_pb2 as topo_graph_pb2 -import modules.common_msgs.routing_msgs.routing_pb2 as routing_pb2 -from pathlib import Path - -FLAGS = gflags.FLAGS -gflags.DEFINE_string('map_dir', 'modules/map/data/demo', 'map directory') - -def check_file(file_path, origin_apollo_path): - file_wrapper = Path(file_path) - if not file_wrapper.exists(): - file_wrapper = Path(origin_apollo_path) - if not file_wrapper.exists(): - print("Can not find {}, exit".format(str(file_wrapper))) - exit(-1) - return str(file_wrapper) - - -def get_map_dir(argv): - sys.argv.insert(1, '--undefok') - flagfile = os.path.normpath( - os.path.join( - os.path.dirname(__file__), '../../common/data', - 'global_flagfile.txt')) - flagfile = check_file(flagfile, "/apollo/modules/common/data/global_flagfile.txt") - sys.argv.insert(2, '--flagfile=' + flagfile) - argv = FLAGS(sys.argv) - mapdir = os.path.normpath( - os.path.join(os.path.dirname(__file__), '../../../', FLAGS.map_dir)) - print("Map dir: %s " % FLAGS.map_dir) - return mapdir - - -def get_mapdata(map_dir): - print('Please wait for loading map data...') - map_data_path = os.path.join(map_dir, 'base_map.bin') - print('File: %s' % map_data_path) - return proto_utils.get_pb_from_bin_file(map_data_path, map_pb2.Map()) - - -def get_topodata(map_dir): - print('Please wait for loading routing topo data...') - topo_data_path = os.path.join(map_dir, 'routing_map.bin') - print("File: %s" % topo_data_path) - return proto_utils.get_pb_from_bin_file(topo_data_path, topo_graph_pb2.Graph()) - - -def get_routingdata(): - print('Please wait for loading route response data...') - log_dir = os.path.normpath( - os.path.join('/apollo/data/log')) - route_data_path = os.path.join(log_dir, 'passage_region_debug.bin') - print("File: %s" % route_data_path) - return proto_utils.get_pb_from_text_file(route_data_path, routing_pb2.RoutingResponse()) - - -def onclick(event): - """Event function when mouse left button is clicked""" - - print('\nClick captured! x=%f\ty=%f' % (event.xdata, event.ydata)) - print('cmd>') - - -def downsample_array(array, step=5): - """Down sample given array""" - - result = array[::step] - result.append(array[-1]) - return result - - -def draw_boundary(ax, line_segment): - """ - :param line_segment: - :return: - """ - - px = [float(p.x) for p in line_segment.point] - py = [float(p.y) for p in line_segment.point] - - px = downsample_array(px) - py = downsample_array(py) - ax.plot(px, py, 'k', lw=0.4) - - -def draw_map(ax, mapfile): - """Draw map from mapfile""" - - for lane in mapfile.lane: - for curve in lane.left_boundary.curve.segment: - if curve.HasField('line_segment'): - draw_boundary(ax, curve.line_segment) - - for curve in lane.right_boundary.curve.segment: - if curve.HasField('line_segment'): - draw_boundary(ax, curve.line_segment) - plt.draw() diff --git a/modules/tools/sensor_calibration/BUILD b/modules/tools/sensor_calibration/BUILD deleted file mode 100644 index 19ccef0b3a7..00000000000 --- a/modules/tools/sensor_calibration/BUILD +++ /dev/null @@ -1,117 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -install( - name = "install", - data = ["runtime_files"], - data_dest = "tools/sensor_calibration", - py_dest = "tools/sensor_calibration", - targets = [ - ":extract_data", - ":extract_static_data", - ":ins_stat_publisher", - ":odom_publisher", - ":sanity_check", - ], - deps = ["//modules/tools/sensor_calibration/config:install"] - -) - -filegroup( - name = "runtime_files", - srcs = glob([ - #"config/**", - "template/**", - "*.py", - "*.sh", - ]), -) - -py_library( - name = "configuration_yaml_generator", - srcs = ["configuration_yaml_generator.py"], - deps = [ - "//modules/dreamview/proto:preprocess_table_py_pb2", - "//modules/tools/common:proto_utils", - ], -) - -py_library( - name = "data_file_object", - srcs = ["data_file_object.py"], -) - -py_binary( - name = "extract_data", - srcs = ["extract_data.py"], - data = [":runtime_files"], - deps = [ - ":configuration_yaml_generator", - ":extract_static_data", - ":sanity_check", - ":sensor_msg_extractor", - "//cyber/proto:record_py_pb2", - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - "//modules/dreamview/proto:preprocess_table_py_pb2", - "//modules/tools/common:proto_utils", - "//modules/tools/sensor_calibration/proto:extractor_config_py_pb2", - ], -) - -py_binary( - name = "extract_static_data", - srcs = ["extract_static_data.py"], - data = [":runtime_files"], - deps = [ - ":configuration_yaml_generator", - ":data_file_object", - "//cyber/proto:record_py_pb2", - "//cyber/python/cyber_py3:record", - "//modules/tools/sensor_calibration/proto:extractor_config_py_pb2", - ], -) - -py_binary( - name = "ins_stat_publisher", - srcs = ["ins_stat_publisher.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:cyber_time", - "//modules/common_msgs/sensor_msgs:ins_py_pb2", - ], -) - -py_binary( - name = "odom_publisher", - srcs = ["odom_publisher.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:cyber_time", - "//modules/common_msgs/localization_msgs:gps_py_pb2", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - ], -) - -py_library( - name = "sensor_msg_extractor", - srcs = ["sensor_msg_extractor.py"], - deps = [ - ":data_file_object", - "//modules/common_msgs/sensor_msgs:conti_radar_py_pb2", - "//modules/common_msgs/sensor_msgs:pointcloud_py_pb2", - "//modules/common_msgs/sensor_msgs:sensor_image_py_pb2", - "//modules/common_msgs/localization_msgs:gps_py_pb2", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - ], -) - -py_binary( - name = "sanity_check", - srcs = ["sanity_check.py"], - deps = [ - "//modules/tools/common:file_utils", - ], -) diff --git a/modules/tools/sensor_calibration/config/BUILD b/modules/tools/sensor_calibration/config/BUILD deleted file mode 100644 index 26c87163645..00000000000 --- a/modules/tools/sensor_calibration/config/BUILD +++ /dev/null @@ -1,19 +0,0 @@ -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -filegroup( - name = "runtime_files", - srcs = glob([ - "*.yaml", - "*.config", - "init_params/*" - ]), -) - -install( - name = "install", - data = [":runtime_files"], - data_dest = "tools/sensor_calibration/config", - deps = ["//modules/tools/sensor_calibration/config/init_params:install"] -) \ No newline at end of file diff --git a/modules/tools/sensor_calibration/config/camera_to_lidar_calibration.config b/modules/tools/sensor_calibration/config/camera_to_lidar_calibration.config deleted file mode 100644 index 44ef16fa333..00000000000 --- a/modules/tools/sensor_calibration/config/camera_to_lidar_calibration.config +++ /dev/null @@ -1,70 +0,0 @@ -# data extraction configuration for multi-camera to lidar calibration -# must includes: -# at least 1 camera image channel -# lidar 128 point cloud channel -# GNSS Gps/odometry channel - -io_config: { - # task name now only support "camera_to_lidar, lidar_to_gnss" - task_name: "camera_to_lidar" - output_path: "/apollo/data/extracted_data" - # start_timestamp: "FLOAT_MIN" - # end_timestamp: "FLOAT_MAX" - # start_timestamp: "1553901009.071362291" - # end_timestamp: "1553901012.01" -} - -records: { - # records can be specified as a list - record_path: "/apollo/data/bag/test/20190325185008.record.00001" - record_path: "/apollo/data/bag/test/20190325185008.record.00002" - record_path: "/apollo/data/bag/test/20190325185008.record.00003" - # or, records can be loaded from a directory - #record_path: "/apollo/data/bag/test/" -} - -channels: { - # channel of camera image channels - channel: { - description: "front camera 6mm" - name: "/apollo/sensor/camera/front_6mm/image" - extraction_rate: 5 - } - channel: { - description: "front camera 12mm" - name: "/apollo/sensor/camera/front_12mm/image" - extraction_rate: 5 - } - channel: { - description: "front camera fisheye" - name: "/apollo/sensor/camera/front_fisheye/image" - extraction_rate: 5 - } -# channel: { -# description: "left camera fisheye" -# name: "/apollo/sensor/camera/left_fisheye/image" -# extraction_rate: 5 -# } -# channel: { -# description: "right camera fisheye" -# name: "/apollo/sensor/camera/right_fisheye/image" -# extraction_rate: 5 -# } -# channel: { -# description: "rear camera 6mm" -# name: "/apollo/sensor/camera/rear_6mm_fisheye/image" -# extraction_rate: 5 -# } - # channel of 128-beam lidar - channel: { - description: "lidar 128 point cloud" - name: "/apollo/sensor/lidar128/PointCloud2" - extraction_rate: 5 - } - # channel of GNSS odometry - channel: { - description: "GNSS odometry" - name: "/apollo/sensor/gnss/odometry" - extraction_rate: 1 - } -} diff --git a/modules/tools/sensor_calibration/config/camera_to_lidar_sample_config.yaml b/modules/tools/sensor_calibration/config/camera_to_lidar_sample_config.yaml deleted file mode 100644 index 480b029dd26..00000000000 --- a/modules/tools/sensor_calibration/config/camera_to_lidar_sample_config.yaml +++ /dev/null @@ -1,13 +0,0 @@ -# calibration from camera to lidar. -calibration_task: "camera_to_lidar" -source_sensor: camera_head_left -destination_sensor: velodyne64 -# beam number of the lidar sensor. For example, Velodyne-128 has 128 beams, Velodyne-16 has 16 beams -beams: 64 # will change to velodyne lidar model later -# relative path of camera intrinsic and initial extrinsic YAML files. -intrinsic: "./init_params/camera_head_left_intrinsics.yaml" -extrinsic: "./init_params/camera_head_left_to_velodyne64_extrinsics.yaml" -# relative path of camera-lidar data pair for calibrations. -data_path: "./camera-lidar-pairs" - -#save result params: diff --git a/modules/tools/sensor_calibration/config/init_params/BUILD b/modules/tools/sensor_calibration/config/init_params/BUILD deleted file mode 100644 index cd1f5d91381..00000000000 --- a/modules/tools/sensor_calibration/config/init_params/BUILD +++ /dev/null @@ -1,16 +0,0 @@ -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -filegroup( - name = "runtime_files", - srcs = glob([ - "*", - ]), -) - -install( - name = "install", - data = [":runtime_files"], - data_dest = "tools/sensor_calibration/config/init_params" -) \ No newline at end of file diff --git a/modules/tools/sensor_calibration/config/init_params/sample_extrinsics.yaml b/modules/tools/sensor_calibration/config/init_params/sample_extrinsics.yaml deleted file mode 100644 index cb46584b79e..00000000000 --- a/modules/tools/sensor_calibration/config/init_params/sample_extrinsics.yaml +++ /dev/null @@ -1,17 +0,0 @@ -header: - frame_id: velodyne64 - stamp: - nsecs: 0 - secs: 0 - seq: 0 -child_frame_id: camera_head_left -transform: - rotation: - x: -0.5 - y: 0.5 - z: -0.5 - w: 0.5 - translation: - x: 0 - y: 0 - z: 0 \ No newline at end of file diff --git a/modules/tools/sensor_calibration/config/init_params/sample_intrinsics.yaml b/modules/tools/sensor_calibration/config/init_params/sample_intrinsics.yaml deleted file mode 100644 index 0b7f2543c77..00000000000 --- a/modules/tools/sensor_calibration/config/init_params/sample_intrinsics.yaml +++ /dev/null @@ -1,23 +0,0 @@ -header: - seq: 0 - stamp: - secs: 0 - nsecs: 0 - frame_id: '' -#change image resolution if needs -height: 1080 -width: 1920 -# change the distortion_model and R if needs. -# change D and K for sure. -distortion_model: plumb_bob -D: [-0.5467789805057404, 0.2729182152572299, -0.0019514549064445735, -0.0004166085741949163, 0.0] -K: [1998.5484365316602, 0.0, 917.7422426747606, 0.0, 1990.2872857509276, 567.1297837900606, 0.0, 0.0, 1.0] -R: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] -binning_x: 0 -binning_y: 0 -roi: - x_offset: 0 - y_offset: 0 - height: 0 - width: 0 - do_rectify: False diff --git a/modules/tools/sensor_calibration/config/lidar_to_GNSS_calibration.config b/modules/tools/sensor_calibration/config/lidar_to_GNSS_calibration.config deleted file mode 100644 index 718cf22831f..00000000000 --- a/modules/tools/sensor_calibration/config/lidar_to_GNSS_calibration.config +++ /dev/null @@ -1,58 +0,0 @@ -# data extraction configuration for multi-lidar to GNSS Gps calibration -# must includes: -# at least 1 lidar pointcloud2 channel -# GNSS Gps/odometry channel - -io_config: { - # task name now only support "camera_to_lidar, lidar_to_gnss" - task_name: "lidar_to_gnss" - output_path: "/apollo/data/extracted_data" - # start_timestamp: "FLOAT_MIN" - # end_timestamp: "FLOAT_MAX" - # start_timestamp: "1553901009.071362291" - # end_timestamp: "1553901012.01" -} - -records: { - # records can be specified as a list - record_path: "/apollo/data/bag/test/20190325185008.record.00001" - record_path: "/apollo/data/bag/test/20190325185008.record.00002" - record_path: "/apollo/data/bag/test/20190325185008.record.00003" - # or, records can be loaded from a directory - #record_path: "/apollo/data/bag/test/" -} - -channels: { - # channel of mulitple lidars - channel: { - description: "lidar 128 point cloud" - name: "/apollo/sensor/lidar128/PointCloud2" - extraction_rate: 5 - } - channel: { - description: "lidar 16 rear left point cloud" - name: "/apollo/sensor/lidar16/rear/left/PointCloud2" - extraction_rate: 5 - } - channel: { - description: "lidar 16 rear right point cloud" - name: "/apollo/sensor/lidar16/rear/right/PointCloud2" - extraction_rate: 5 - } - channel: { - description: "lidar 16 front center point cloud" - name: "/apollo/sensor/lidar16/front/center/PointCloud2" - extraction_rate: 5 - } -# channel: { -# description: "lidar 16 front up point cloud" -# name: "/apollo/sensor/lidar16/front/up/PointCloud2" -# extraction_rate: 5 -# } - # channel of GNSS odometry - channel: { - description: "GNSS odometry" - name: "/apollo/sensor/gnss/odometry" - extraction_rate: 1 - } -} diff --git a/modules/tools/sensor_calibration/config/lidar_to_gnss_sample_config.yaml b/modules/tools/sensor_calibration/config/lidar_to_gnss_sample_config.yaml deleted file mode 100644 index 034774f9bb9..00000000000 --- a/modules/tools/sensor_calibration/config/lidar_to_gnss_sample_config.yaml +++ /dev/null @@ -1,22 +0,0 @@ -#LiDAR-to-GNSS calibration data service configurations -#Sensor names: calibrate the source_sensor in destination_sensor coordinate -calibration_task: "lidar_to_gnss" -source_sensor: "velodyne128" -destination_sensor: "novatel" - -#for lidar-gnss. use odometry message and lidar message. -#provide the local file directory( relevant to this config file), for the sensor message storage. -odometry_file: "./_sensor_novatel_Odometry/odometry" -sensor_files_directory: "./_sensor_velodyne64_VelodyneScan/" -#initial calibration paramters, including translation and raotation, to project a point in source -#source_sensor coordinate to destination_sensor coordinate. translation is in meter. rotation is in quaternion -transform: - translation: - x: 0.0 - y: 0.0 - z: 0.0 - rotation: - x: 0.0 - y: 0.0 - z: 0.7071 - w: 0.7071 diff --git a/modules/tools/sensor_calibration/configuration_yaml_generator.py b/modules/tools/sensor_calibration/configuration_yaml_generator.py deleted file mode 100644 index 38463b92c28..00000000000 --- a/modules/tools/sensor_calibration/configuration_yaml_generator.py +++ /dev/null @@ -1,180 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import os -import shutil - -import yaml - -from google.protobuf import text_format - -from modules.dreamview.proto import preprocess_table_pb2 -from modules.tools.common.proto_utils import get_pb_from_text_file - -ROOT_DIR = '/apollo/modules/tools/sensor_calibration' - -class ConfigYaml(object): - """generate yaml configuration for next-step calibration service. - automatically generate calibration configuration yaml file. help user to - input the initial extrinsics values or path(lidar, camera), intrinsics path(camera), - sensor name if needs changes. - """ - - def __init__(self, supported_calibrations=['lidar_to_gnss', 'camera_to_lidar']): - self._task_name = 'unknown' - self._supported_tasks = supported_calibrations - self._source_sensor = '' - self._table_info = preprocess_table_pb2.PreprocessTable() - print('calibration service now support: {}'.format(self._supported_tasks)) - - def load_sample_yaml_file(self, task_name, sample_file=None): - if sample_file is None: - sample_file = os.path.join(ROOT_DIR, 'config', task_name + '_sample_config.yaml') - try: - with open(sample_file, 'r') as f: - data = yaml.safe_load(f) - except IOError: - raise ValueError( - 'cannot open the sample configure yaml file at {}'.format(sample_file)) - return data - - def _generate_lidar_to_gnss_calibration_yaml(self, in_data, lidar_folder_name, gnss_folder_name): - in_data['sensor_files_directory'] = os.path.join( - '.', lidar_folder_name, "") - in_data['odometry_file'] = os.path.join( - '.', gnss_folder_name, 'odometry') - for lidar_config in self._table_info.lidar_config: - if lidar_config.sensor_name == self._source_sensor: - in_data['transform']['translation']['x'] = round( - lidar_config.translation.x, 4) - in_data['transform']["translation"]["y"] = round( - lidar_config.translation.y, 4) - in_data['transform']["translation"]["z"] = round( - lidar_config.translation.z, 4) - return in_data - - def _generate_camera_init_param_yaml(self, root_path, in_data): - init_param_folder = os.path.join( - ROOT_DIR, 'config/init_params') - out_param_folder = os.path.join(root_path, 'init_params') - if os.path.exists(out_param_folder): - print('folder: %s exists' % out_param_folder) - else: - print('create folder: %s' % out_param_folder) - os.makedirs(out_param_folder) - camera_config = self._table_info.camera_config - # copy sample intrinsic yaml file to correct location - # wait for user input about intrinsics - sample_intrinsic_yaml = os.path.join( - init_param_folder, 'sample_intrinsics.yaml') - intrinsic_data = self.load_sample_yaml_file(self._task_name, - sample_file=sample_intrinsic_yaml) - for iter, data in enumerate(camera_config.D): - intrinsic_data['D'][iter] = data - for iter, data in enumerate(camera_config.K): - intrinsic_data['K'][iter] = data - # dump the intrinsic yaml data - out_intrinsic_yaml = os.path.join(out_param_folder, - in_data['source_sensor'] + '_intrinsics.yaml') - try: - with open(out_intrinsic_yaml, 'w') as f: - yaml.safe_dump(intrinsic_data, f) - except IOError: - raise ValueError('cannot generate the task config yaml ' - 'file at {}'.format(out_intrinsic_yaml)) - - - # load extrinsics sample yaml, rename source sensor and destination sensor - sample_extrinsic_yaml = os.path.join( - init_param_folder, 'sample_extrinsics.yaml') - extrinsic_data = self.load_sample_yaml_file(self._task_name, - sample_file=sample_extrinsic_yaml) - # set up the source_sensor(camera name) to dest sensor(lidar name) - extrinsic_data['header']['frame_id'] = in_data['destination_sensor'] - extrinsic_data['child_frame_id'] = in_data['source_sensor'] - extrinsic_data['transform']['translation']['x'] = round( - camera_config.translation.x, 4) - extrinsic_data['transform']["translation"]["y"] = round( - camera_config.translation.y, 4) - extrinsic_data['transform']["translation"]["z"] = round( - camera_config.translation.z, 4) - # dump the extrinsic yaml data - out_extrinsic_yaml = os.path.join(out_param_folder, in_data['source_sensor'] - + '_' + in_data['destination_sensor'] + '_extrinsics.yaml') - try: - with open(out_extrinsic_yaml, 'w') as f: - yaml.safe_dump(extrinsic_data, f) - except IOError: - raise ValueError('cannot generate the task config yaml ' - 'file at {}'.format(out_extrinsic_yaml)) - - def _generate_camera_to_lidar_calibration_yaml(self, in_data): - in_data['intrinsic'] = os.path.join('.', 'init_params', - in_data['source_sensor'] + '_intrinsics.yaml') - in_data['extrinsic'] = os.path.join('.', 'init_params', in_data['source_sensor'] - + '_' + in_data['destination_sensor'] + '_extrinsics.yaml') - - return in_data - - def get_task_name(self): - if self._task_name == 'unknown': - raise ValueError('have not set the task name, the valid task names' - 'are: {}'.format(self._supported_tasks)) - return self._task_name - - def generate_task_config_yaml(self, task_name, source_sensor, dest_sensor, - source_folder, dest_folder, out_config_file, - in_config_file=None): - self._task_name = task_name - self._source_sensor = source_sensor - out_data = self.load_sample_yaml_file( - task_name=task_name, sample_file=in_config_file) - out_data['source_sensor'] = source_sensor - out_data['destination_sensor'] = dest_sensor - if task_name not in self._supported_tasks: - raise ValueError('does not support the calibration task: {}'.format( - task_name)) - user_config = os.path.join(ROOT_DIR, 'config', - task_name + '_user.config') - if os.path.exists(user_config): - try: - get_pb_from_text_file(user_config, self._table_info) - except text_format.ParseError: - print(f'Error: Cannot parse {user_config} as text proto') - - if self._task_name == 'lidar_to_gnss': - out_data = self._generate_lidar_to_gnss_calibration_yaml( - out_data, source_folder, dest_folder) - - elif self._task_name == 'camera_to_lidar': - if source_folder != dest_folder: - raise ValueError( - 'camera frame and lidar frame should be in same folder') - out_root_path = os.path.dirname(out_config_file) - self._generate_camera_init_param_yaml(out_root_path, out_data) - out_data = self._generate_camera_to_lidar_calibration_yaml( - out_data) - - print(out_data) - try: - with open(out_config_file, 'w') as f: - yaml.safe_dump(out_data, f) - except IOError: - raise ValueError( - 'cannot generate the task config yaml file at {}'.format(out_config_file)) - return True diff --git a/modules/tools/sensor_calibration/data_file_object.py b/modules/tools/sensor_calibration/data_file_object.py deleted file mode 100644 index 60b5236c225..00000000000 --- a/modules/tools/sensor_calibration/data_file_object.py +++ /dev/null @@ -1,118 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -""" -This is a bunch of classes to manage cyber record channel FileIO. -""" - -import os -import sys -import struct - -import numpy as np - - -class FileObject(object): - """Wrapper for file object""" - - # Initializing file object - def __init__(self, file_path, operation='write', file_type='binary'): - if operation != 'write' and operation != 'read': - raise ValueError("Unsupported file operation: %s" % operation) - - if file_type != 'binary' and file_type != 'txt': - raise ValueError("Unsupported file type: %s" % file_type) - - operator = 'w' if operation == 'write' else 'r' - operator += 'b' if file_type == 'binary' else '' - - try: - self._file_object = open(file_path, operator) - except IOError: - raise ValueError("Cannot open file: {}".format(file_path)) - - # Safely close file - def __del__(self): - self._file_object.close() - - def file_object(self): - return self._file_object - - def save_to_file(self, data): - raise NotImplementedError - - -class TimestampFileObject(FileObject): - """class to handle sensor timestamp for each Apollo sensor channel""" - - def __init__(self, file_path, operation='write', file_type='txt'): - super(TimestampFileObject, self).__init__(file_path, - operation, file_type) - - def save_to_file(self, data): - if not isinstance(data, list) and not isinstance(data, np.ndarray): - raise ValueError("timestamps must be in a list") - - for i, ts in enumerate(data): - self._file_object.write("%05d %.6f\n" % (i + 1, ts)) - - -class OdometryFileObject(FileObject): - """class to handle gnss/odometry topic""" - - def load_file(self): - struct_len = struct.calcsize('i') - data_size = struct.Struct('i').unpack(self._file_object.read(struct.calcsize('i')))[0] - s0 = struct.Struct('d') - s1 = struct.Struct('I') - s2 = struct.Struct('7d') - data = np.zeros((data_size, 9), dtype='float64') - # , int32, float64, float64, float64, float64, float64, float64, float64') - for d in data: - #d[0] = s0.unpack_from(self._file_object.read(s0.size))[0] - d[0] = s0.unpack(self._file_object.read(s0.size))[0] - d[1] = s1.unpack_from(self._file_object.read(s1.size))[0] - d[2:] = np.array(s2.unpack_from(self._file_object.read(s2.size))) - return data.tolist() - - def save_to_file(self, data): - """ - odometry data: total 9 elements - [ - double timestamp - int32 postion_type - double qw, qx, qy, qz - double x, y, z - ] - """ - if not isinstance(data, list): - raise ValueError("Odometry data must be in a list") - data_size = len(data) - self._file_object.write(struct.pack('I', data_size)) - # have to pack separate, to avoid struct padding, now 8+4+7*8 = 68 bytes - # TODO (yuanfan / gchen-Apollo): follow protobuf across tools. - - s0 = struct.Struct('d') - s1 = struct.Struct('I') - s2 = struct.Struct('7d') - for d in data: - # print(d[0]) - self._file_object.write(s0.pack(d[0])) - self._file_object.write(s1.pack(d[1])) - pack_d = s2.pack(d[2], d[3], d[4], d[5], d[6], d[7], d[8]) - self._file_object.write(pack_d) diff --git a/modules/tools/sensor_calibration/extract_data.py b/modules/tools/sensor_calibration/extract_data.py deleted file mode 100755 index 59a06e5e7d3..00000000000 --- a/modules/tools/sensor_calibration/extract_data.py +++ /dev/null @@ -1,685 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### -""" -This is a tool to extract useful information from given record files. It does -self-check the validity of the uploaded data and able to inform developer's when -the data is not qualified, and reduce the size of uploaded data significantly. -""" -from datetime import datetime -import os -import shutil -import six -import sys -import time -import yaml - -from absl import app -from absl import flags -from google.protobuf import text_format -import numpy as np - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3.record import RecordReader -from cyber.proto import record_pb2 -from modules.dreamview.proto import preprocess_table_pb2 -from modules.tools.common.proto_utils import get_pb_from_text_file -from modules.tools.sensor_calibration.configuration_yaml_generator import ConfigYaml -from modules.tools.sensor_calibration.extract_static_data import get_subfolder_list, select_static_image_pcd -from modules.tools.sensor_calibration.proto import extractor_config_pb2 -from modules.tools.sensor_calibration.sanity_check import sanity_check -from modules.tools.sensor_calibration.sensor_msg_extractor import GpsParser, ImageParser, PointCloudParser, PoseParser, ContiRadarParser - -SMALL_TOPICS = [ - '/apollo/canbus/chassis', - '/apollo/canbus/chassis_detail', - '/apollo/control', - '/apollo/control/pad', - '/apollo/drive_event', - '/apollo/guardian', - '/apollo/hmi/status', - '/apollo/localization/pose', - '/apollo/localization/msf_gnss', - '/apollo/localization/msf_lidar', - '/apollo/localization/msf_status', - '/apollo/monitor', - '/apollo/monitor/system_status', - '/apollo/navigation', - '/apollo/perception/obstacles', - '/apollo/perception/traffic_light', - '/apollo/planning', - '/apollo/prediction', - '/apollo/relative_map', - '/apollo/routing_request', - '/apollo/routing_response', - '/apollo/routing_response_history', - '/apollo/sensor/conti_radar', - '/apollo/sensor/delphi_esr', - '/apollo/sensor/gnss/best_pose', - '/apollo/sensor/gnss/corrected_imu', - '/apollo/sensor/gnss/gnss_status', - '/apollo/sensor/gnss/imu', - '/apollo/sensor/gnss/ins_stat', - '/apollo/sensor/gnss/odometry', - '/apollo/sensor/gnss/raw_data', - '/apollo/sensor/gnss/rtk_eph', - '/apollo/sensor/gnss/rtk_obs', - '/apollo/sensor/gnss/heading', - '/apollo/sensor/mobileye', - '/tf', - '/tf_static', -] - -flags.DEFINE_string('config', '', - 'protobuf text format configuration file abosolute path') -flags.DEFINE_string('root_dir', '/apollo/modules/tools/sensor_calibration', - 'program root dir') - -FLAGS = flags.FLAGS - - -class Extractor(object): - def __init__(self): - self.node = cyber.Node("sendor_calibration_preprocessor") - self.writer = self.node.create_writer("/apollo/dreamview/progress", - preprocess_table_pb2.Progress, 6) - self.config = extractor_config_pb2.DataExtractionConfig() - self.progress = preprocess_table_pb2.Progress() - self.progress.percentage = 0.0 - self.progress.log_string = "Preprocessing in progress..." - self.progress.status = preprocess_table_pb2.Status.UNKNOWN - try: - get_pb_from_text_file(FLAGS.config, self.config) - except text_format.ParseError: - print(f'Error: Cannot parse {FLAGS.config} as text proto') - self.records = [] - for r in self.config.records.record_path: - self.records.append(str(r)) - self.start_timestamp = -1 - self.end_timestamp = -1 - if self.config.io_config.start_timestamp == "FLOAT_MIN": - self.start_timestamp = np.finfo(np.float32).min - else: - self.start_timestamp = np.float32( - self.config.io_config.start_timestamp) - - if self.config.io_config.end_timestamp == "FLOAT_MAX": - self.end_timestamp = np.finfo(np.float32).max - else: - self.end_timestamp = np.float32( - self.config.io_config.end_timestamp) - - @staticmethod - def process_dir(path, operation): - """Create or remove directory.""" - try: - if operation == 'create': - if os.path.exists(path): - print(f'folder: {path} exists') - else: - print(f'create folder: {path}') - os.makedirs(path) - elif operation == 'remove': - os.remove(path) - else: - print( - f'Error! Unsupported operation {operation} for directory.') - return False - except OSError as e: - print(f'Failed to {operation} directory: {path}. ' - f'Error: {six.text_type(e)}') - return False - - return True - - @staticmethod - def get_sensor_channel_list(record_file): - """Get the channel list of sensors for calibration.""" - record_reader = RecordReader(record_file) - return set(channel_name - for channel_name in record_reader.get_channellist() - if 'sensor' in channel_name - or '/localization/pose' in channel_name) - - @staticmethod - def validate_channel_list(channels, dictionary): - ret = True - for channel in channels: - if channel not in dictionary: - print(f'ERROR: channel {channel} does not exist in ' - 'record sensor channels') - ret = False - return ret - - @staticmethod - def in_range(v, s, e): - return True if v >= s and v <= e else False - - @staticmethod - def build_parser(channel, output_path): - parser = None - if channel.endswith("/image"): - parser = ImageParser(output_path=output_path, instance_saving=True) - elif channel.endswith("/PointCloud2"): - parser = PointCloudParser(output_path=output_path, - instance_saving=True) - elif channel.endswith("/gnss/odometry"): - parser = GpsParser(output_path=output_path, instance_saving=False) - elif channel.endswith("/localization/pose"): - parser = PoseParser(output_path=output_path, instance_saving=False) - elif channel.startswith("/apollo/sensor/radar"): - parser = ContiRadarParser(output_path=output_path, - instance_saving=True) - else: - raise ValueError(f"Not Support this channel type: {channel}") - return parser - - def print_and_publish(self, - str, - status=preprocess_table_pb2.Status.UNKNOWN): - """status: 0 for success, 1 for fail, 2 for unknown""" - print(str) - self.progress.log_string = str - self.progress.status = status - self.writer.write(self.progress) - time.sleep(0.5) - - def extract_data(self, record_files, output_path, channels, - extraction_rates): - """ - Extract the desired channel messages if channel_list is specified. - Otherwise extract all sensor calibration messages according to - extraction rate, 10% by default. - """ - # all records have identical sensor channels. - sensor_channels = self.get_sensor_channel_list(record_files[0]) - - if (len(channels) > 0 - and not self.validate_channel_list(channels, sensor_channels)): - print('The input channel list is invalid.') - return False - - # Extract all the sensor channels if channel_list is empty(no input arguments). - print(sensor_channels) - if len(channels) == 0: - channels = sensor_channels - - # Declare logging variables - process_channel_success_num = len(channels) - process_channel_failure_num = 0 - process_msg_failure_num = 0 - - channel_success = {} - channel_occur_time = {} - channel_output_path = {} - # channel_messages = {} - channel_parsers = {} - channel_message_number = {} - channel_processed_msg_num = {} - - for channel in channels: - channel_success[channel] = True - channel_occur_time[channel] = -1 - topic_name = channel.replace('/', '_') - channel_output_path[channel] = os.path.join( - output_path, topic_name) - self.process_dir(channel_output_path[channel], operation='create') - channel_parsers[channel] =\ - self.build_parser(channel, channel_output_path[channel]) - channel_message_number[channel] = 0 - for record_file in record_files: - record_reader = RecordReader(record_file) - channel_message_number[ - channel] += record_reader.get_messagenumber(channel) - channel_message_number[channel] = channel_message_number[ - channel] // extraction_rates[channel] - - channel_message_number_total = 0 - for num in channel_message_number.values(): - channel_message_number_total += num - channel_processed_msg_num = 0 - - # if channel in SMALL_TOPICS: - # channel_messages[channel] = list() - for record_file in record_files: - record_reader = RecordReader(record_file) - for msg in record_reader.read_messages(): - if msg.topic in channels: - # Only care about messages in certain time intervals - msg_timestamp_sec = msg.timestamp / 1e9 - if not self.in_range(msg_timestamp_sec, - self.start_timestamp, - self.end_timestamp): - continue - - channel_occur_time[msg.topic] += 1 - # Extract the topic according to extraction_rate - if channel_occur_time[msg.topic] % extraction_rates[ - msg.topic] != 0: - continue - - ret = channel_parsers[msg.topic].parse_sensor_message(msg) - channel_processed_msg_num += 1 - self.progress.percentage = channel_processed_msg_num / \ - channel_message_number_total * 90.0 - # Calculate parsing statistics - if not ret: - process_msg_failure_num += 1 - if channel_success[msg.topic]: - channel_success[msg.topic] = False - process_channel_failure_num += 1 - process_channel_success_num -= 1 - log_string = ( - 'Failed to extract data from channel: ' - f'{msg.topic} in record {record_file}') - print(log_string) - self.progress.log_string = log_string - - self.writer.write(self.progress) - - # traverse the dict, if any channel topic stored as a list - # then save the list as a summary file, mostly binary file - for channel, parser in channel_parsers.items(): - self.save_combined_messages_info(parser, channel) - - # Logging statics about channel extraction - self.print_and_publish( - (f"Extracted sensor channel number {len(channels)} " - f"from record files: {' '.join(record_files)}")) - self.print_and_publish( - (f'Successfully processed {process_channel_success_num} channels, ' - f'and {process_channel_failure_num} was failed.')) - if process_msg_failure_num > 0: - self.print_and_publish( - f'Channel extraction failure number is {process_msg_failure_num}.', - preprocess_table_pb2.Status.FAIL) - - return True - - @staticmethod - def save_combined_messages_info(parser, channel): - if not parser.save_messages_to_file(): - raise ValueError( - f"cannot save combined messages into single file for : {channel}" - ) - if not parser.save_timestamps_to_file(): - raise ValueError(f"cannot save tiemstamp info for {channel}") - - @staticmethod - def generate_compressed_file(input_path, - input_name, - output_path, - compressed_file='sensor_data'): - """ - Compress data extraction directory as a single tar.gz archive - """ - cwd_path = os.getcwd() - os.chdir(input_path) - shutil.make_archive(base_name=os.path.join(output_path, - compressed_file), - format='gztar', - root_dir=input_path, - base_dir=input_name) - os.chdir(cwd_path) - - @staticmethod - def generate_extraction_rate_dict(channels, - large_topic_extraction_rate, - small_topic_extraction_rate=1): - """ - Default extraction rate for small topics is 1, which means no sampling - """ - - # Validate extration_rate, and set it as an integer. - if large_topic_extraction_rate < 1.0 or small_topic_extraction_rate < 1.0: - raise ValueError( - "Extraction rate must be a number no less than 1.") - - large_topic_extraction_rate = np.floor(large_topic_extraction_rate) - small_topic_extraction_rate = np.floor(small_topic_extraction_rate) - - rates = {} - for channel in channels: - if channel in SMALL_TOPICS: - rates[channel] = small_topic_extraction_rate - else: - rates[channel] = large_topic_extraction_rate - - return rates - - @staticmethod - def validate_record(record_file): - """Validate the record file.""" - # Check the validity of a cyber record file according to header info. - record_reader = RecordReader(record_file) - header_msg = record_reader.get_headerstring() - header = record_pb2.Header() - header.ParseFromString(header_msg) - print(f"header is {header}") - - if not header.is_complete: - print(f'Record file: {record_file} is not completed.') - return False - if header.size == 0: - print(f'Record file: {record_file}. size is 0.') - return False - if header.major_version != 1 and header.minor_version != 0: - print( - f'Record file: {record_file}. version [{header.major_version}: ' - f'{header.minor_version}] is wrong.') - return False - if header.begin_time >= header.end_time: - print( - f'Record file: {record_file}. begin time [{header.begin_time}] ' - f'is equal or larger than end time [{header.end_time}].') - return False - - if header.message_number < 1 or header.channel_number < 1: - print( - f'Record file: {record_file}. [message:channel] number ' - f'[{header.message_number}:{header.channel_number}] is invalid.' - ) - return False - - # There should be at least one sensor channel - sensor_channels = Extractor.get_sensor_channel_list(record_file) - if len(sensor_channels) < 1: - print(f'Record file: {record_file}. cannot find sensor channels.') - return False - - return True - - def validate_record_files(self, kword='.record.'): - # load file list from directory if needs - file_abs_paths = [] - if not isinstance(self.records, list): - raise ValueError("Record files must be in a list") - - records = self.records - if len(records) == 1 and os.path.isdir(records[0]): - print(f'Load cyber records from: {records[0]}') - for f in sorted(os.listdir(records[0])): - if kword in f: - file_abs_path = os.path.join(records[0], f) - if Extractor.validate_record(file_abs_path): - file_abs_paths.append(file_abs_path) - else: - print(f'Invalid record file: {file_abs_path}') - else: - for f in records: - if not os.path.isfile(f): - raise ValueError("Input cyber record does not exist " - f"or not a regular file: {f}") - - if Extractor.validate_record(f): - file_abs_paths.append(f) - else: - print(f'Invalid record file: {f}') - - if len(file_abs_paths) < 1: - raise ValueError("All the input record files are invalid") - - # Validate all record files have the same sensor topics - first_record_file = file_abs_paths[0] - default_sensor_channels = Extractor.get_sensor_channel_list( - first_record_file) - for i, f in enumerate(file_abs_paths[1:]): - sensor_channels = Extractor.get_sensor_channel_list(f) - if sensor_channels != default_sensor_channels: - print( - f'Default sensor channel list in {first_record_file} is: ') - print(default_sensor_channels) - print(f'but sensor channel list in {file_abs_paths[i]} is: ') - print(sensor_channels) - raise ValueError( - "The record files should contain the same channel list") - - return file_abs_paths - - def parse_channel_config(self): - channel_list = set() - extraction_rate_dict = dict() - - for channel in self.config.channels.channel: - if channel.name in channel_list: - raise ValueError( - f"Duplicated channel config for : {channel.name}") - else: - channel_list.add(channel.name) - extraction_rate_dict[channel.name] = channel.extraction_rate - return channel_list, extraction_rate_dict - - @staticmethod - def get_substring(str, prefix, suffix): - """return substring, eclusive prefix or suffix""" - str_p = str.rfind(prefix) + len(prefix) - end_p = str.rfind(suffix) - return str[str_p:end_p] - - def reorganize_extracted_data(self, - tmp_data_path, - remove_input_data_cache=False): - root_path = os.path.dirname(os.path.normpath(tmp_data_path)) - output_path = None - - config_yaml = ConfigYaml() - task_name = self.config.io_config.task_name - if task_name == 'lidar_to_gnss': - subfolders = [ - x for x in get_subfolder_list(tmp_data_path) - if '_apollo_sensor_' in x or '_localization_pose' in x - ] - odometry_subfolders = [ - x for x in subfolders if '_odometry' in x or '_pose' in x - ] - lidar_subfolders = [x for x in subfolders if '_PointCloud2' in x] - print(lidar_subfolders) - print(odometry_subfolders) - if len(lidar_subfolders) == 0 or len(odometry_subfolders) != 1: - raise ValueError(('one odometry and more than 0 lidar(s)' - 'sensor are needed for sensor calibration')) - odometry_subfolder = odometry_subfolders[0] - yaml_list = [] - gnss_name = 'novatel' - multi_lidar_out_path = os.path.join( - root_path, 'multi_lidar_to_gnss_calibration') - output_path = multi_lidar_out_path - - for lidar in lidar_subfolders: - # get the lidar name from folder name string - lidar_name = Extractor.get_substring(str=lidar, - prefix='_apollo_sensor_', - suffix='_PointCloud2') - - # reorganize folder structure: each lidar has its raw data, - # corresponding odometry and configuration yaml file - - if not Extractor.process_dir(multi_lidar_out_path, 'create'): - raise ValueError( - f'Failed to create directory: {multi_lidar_out_path}') - lidar_in_path = os.path.join(tmp_data_path, lidar) - lidar_out_path = os.path.join(multi_lidar_out_path, lidar) - if not os.path.exists(lidar_out_path): - shutil.copytree(lidar_in_path, lidar_out_path) - odometry_in_path = os.path.join(tmp_data_path, - odometry_subfolder) - odometry_out_path = os.path.join(multi_lidar_out_path, - odometry_subfolder) - if not os.path.exists(odometry_out_path): - shutil.copytree(odometry_in_path, odometry_out_path) - generated_config_yaml = os.path.join( - tmp_data_path, lidar_name + '_' + 'sample_config.yaml') - config_yaml.generate_task_config_yaml( - task_name=task_name, - source_sensor=lidar_name, - dest_sensor=gnss_name, - source_folder=lidar, - dest_folder=odometry_subfolder, - out_config_file=generated_config_yaml) - print(f'lidar {lidar_name} calibration data and configuration' - ' are generated.') - yaml_list.append(generated_config_yaml) - - out_data = { - 'calibration_task': task_name, - 'destination_sensor': gnss_name, - 'odometry_file': odometry_subfolder + '/odometry' - } - sensor_files_directory_list = [] - source_sensor_list = [] - transform_list = [] - for i in range(len(yaml_list)): - with open(yaml_list[i], 'r') as f: - data = yaml.safe_load(f) - sensor_files_directory_list.append( - data['sensor_files_directory']) - source_sensor_list.append(data['source_sensor']) - transform_list.append(data['transform']) - out_data['sensor_files_directory'] = sensor_files_directory_list - out_data['source_sensor'] = source_sensor_list - out_data['transform'] = transform_list - out_data['main_sensor'] = source_sensor_list[0] - - table = preprocess_table_pb2.PreprocessTable() - user_config = os.path.join(FLAGS.root_dir, 'config', - 'lidar_to_gnss_user.config') - if os.path.exists(user_config): - try: - get_pb_from_text_file(user_config, table) - except text_format.ParseError: - print(f'Error: Cannot parse {user_config} as text proto') - - if table.HasField("main_sensor"): - out_data['main_sensor'] = table.main_sensor - - multi_lidar_yaml = os.path.join(multi_lidar_out_path, - 'sample_config.yaml') - with open(multi_lidar_yaml, 'w') as f: - yaml.safe_dump(out_data, f) - - elif task_name == 'camera_to_lidar': - # data selection. - pair_data_folder_name = 'camera-lidar-pairs' - cameras, lidar = select_static_image_pcd( - path=tmp_data_path, - min_distance=5, - stop_times=4, - wait_time=3, - check_range=50, - image_static_diff_threshold=0.005, - output_folder_name=pair_data_folder_name, - image_suffix='.jpg', - pcd_suffix='.pcd') - lidar_name = Extractor.get_substring(str=lidar, - prefix='_apollo_sensor_', - suffix='_PointCloud2') - for camera in cameras: - camera_name = Extractor.get_substring(str=camera, - prefix='_apollo_sensor_', - suffix='_image') - out_path = os.path.join( - root_path, - camera_name + '_to_' + lidar_name + '_calibration') - output_path = out_path - if not Extractor.process_dir(out_path, 'create'): - raise ValueError(f'Failed to create directory: {out_path}') - # reorganize folder structure: each camera has its images, - # corresponding lidar pointclouds, camera initial extrinsics, - # intrinsics, and configuration yaml file - - in_pair_data_path = os.path.join(tmp_data_path, camera, - pair_data_folder_name) - out_pair_data_path = os.path.join(out_path, - pair_data_folder_name) - shutil.copytree(in_pair_data_path, out_pair_data_path) - generated_config_yaml = os.path.join(out_path, - 'sample_config.yaml') - config_yaml.generate_task_config_yaml( - task_name=task_name, - source_sensor=camera_name, - dest_sensor=lidar_name, - source_folder=None, - dest_folder=None, - out_config_file=generated_config_yaml) - elif task_name == 'radar_to_gnss': - print('not ready. stay tuned') - else: - raise ValueError( - f'Unsupported data extraction task for {task_name}') - - if remove_input_data_cache: - print(f'removing the cache at {tmp_data_path}') - os.system(f'rm -rf {tmp_data_path}') - return output_path - - def sanity_check_path(self, path): - """Sanity check wrapper""" - result, log_str = sanity_check(path) - if result is True: - self.progress.percentage = 100.0 - self.progress.status = preprocess_table_pb2.Status.SUCCESS - else: - self.progress.status = preprocess_table_pb2.Status.FAIL - self.progress.log_string = log_str - self.writer.write(self.progress) - time.sleep(0.5) - - def create_tmp_directory(self): - """Create directory to save the extracted data use time now() as folder name""" - output_relative_path = self.config.io_config.task_name + datetime.now( - ).strftime("-%Y-%m-%d-%H-%M") + '/tmp/' - - output_abs_path = os.path.join(self.config.io_config.output_path, - output_relative_path) - ret = self.process_dir(output_abs_path, 'create') - if not ret: - raise ValueError( - f'Failed to create extrated data directory: {output_abs_path}') - return output_abs_path - - -def main(argv): - """Main function""" - - cyber.init("data_extractor") - extractor = Extractor() - - valid_record_list = extractor.validate_record_files(kword='.record.') - - channels, extraction_rates = extractor.parse_channel_config() - print(f'parsing the following channels: {channels}') - - output_tmp_path = extractor.create_tmp_directory() - extractor.extract_data(valid_record_list, output_tmp_path, channels, - extraction_rates) - - output_abs_path = extractor.reorganize_extracted_data( - tmp_data_path=output_tmp_path, remove_input_data_cache=True) - - print('Data extraction is completed successfully!') - extractor.sanity_check_path(output_abs_path) - cyber.shutdown() - sys.exit(0) - - -if __name__ == '__main__': - # root_path = '/apollo/data/extracted_data/MKZ5-2019-05-15/lidar_to_gnss-2019-11-25-11-02/tmp' - # task_name = 'lidar_to_gnss' - # root_path = '/apollo/data/extracted_data/udevl002-2019-06-14/camera_to_lidar-2019-11-26-19-49/tmp' - # task_name = 'camera_to_lidar' - # reorganize_extracted_data(tmp_data_path=root_path, task_name=task_name) - app.run(main) diff --git a/modules/tools/sensor_calibration/extract_data.sh b/modules/tools/sensor_calibration/extract_data.sh deleted file mode 100755 index 4ff7a8ceff8..00000000000 --- a/modules/tools/sensor_calibration/extract_data.sh +++ /dev/null @@ -1,246 +0,0 @@ -#! /usr/bin/env bash - -############################################################################### -# 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. -############################################################################### - -TOP_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")/../../.." && pwd -P)" - -TARGET_DIR="${TOP_DIR}/output/sensor_calibration" -TEMPLATE_DIR="${TOP_DIR}/modules/tools/sensor_calibration/template" -DEFAULT_RECORD_DIR="${TOP_DIR}/data/bag" - -TASK="" -VALID_TASKS=("lidar_to_gnss" "camera_to_lidar") - -RECORD_FILES=() -RECORD_DIRS=() - -function join_by() { - local d=$1 - shift - echo -n "$1" - shift - printf "%s" "${@/#/$d}" -} - -function print_usage() { - echo "Usage: - ./extract_data.sh -t [ $(join_by ' | ' ${VALID_TASKS[@]}) ] -f -d - eg. - ./extract_data.sh -t lidar_to_gnss -f xxx/yyy.record.00000 -f xxx/yyy.record.00001 - or - ./extract_data.sh -t camera_to_lidar -d xxx -c front_6mm - " -} - -function parse_args() { - # read options - while getopts ':t:c:f:d:' flag; do - case "${flag}" in - t) - TASK="${OPTARG}" - ;; - f) - RECORD_FILES+=("${OPTARG}") - ;; - d) - RECORD_DIRS+=("${OPTARG}") - ;; - *) - print_usage - exit 1 - ;; - esac - done - - if [[ " ${VALID_TASKS[@]} " =~ " ${TASK} " ]]; then - TARGET_DIR="${TARGET_DIR}/${TASK}" - TEMPLATE_DIR="${TEMPLATE_DIR}/${TASK}" - else - print_usage - exit 1 - fi -} - -function check_target_dir() { - if [[ ! -d "${TARGET_DIR}" ]]; then - mkdir -p ${TARGET_DIR} - elif [[ ! -z "$(ls -A ${TARGET_DIR})" ]]; then - rm -rf ${TARGET_DIR}/* - fi - cp -R ${TEMPLATE_DIR}/* ${TARGET_DIR} -} - -# Since pypcd installed via `pip install` only works with python2.7, -# we can only install it this way -function _install_pypcd() { - git clone https://github.com/DanielPollithy/pypcd - pushd pypcd >/dev/null - sudo make install - popd >/dev/null - sudo rm -rf pypcd -} - -function _get_latest() { - local parent_dir=$1 - local latest=$(ls -lt ${parent_dir} | grep -v '_s' | - grep -m1 '^d' | awk '{print $NF}') - if [[ -z "${latest}" ]]; then - echo "There is no reord directories in ${parent_dir}!" - exit 1 - else - echo "${parent_dir}/${latest}" - fi -} - -function get_records() { - if [[ ${#RECORD_FILES[*]} -eq 0 && ${#RECORD_DIRS[*]} -eq 0 ]]; then - RECORD_DIRS+=($(_get_latest ${DEFAULT_RECORD_DIR})) - fi - - local tmp_file="${TARGET_DIR}/tmp.txt" - - for file in "${RECORD_FILES[@]}"; do - if [[ -f "${file}" ]]; then - if [[ "${file}" == *"record"* ]]; then - echo -e ' record_path: "'$(readlink -f ${file})'"\n' >>"${tmp_file}" - sed -i "/# records can be specified as a list/r ${tmp_file}" "${TARGET_DIR}/${TASK}.config" - else - echo "The input file ${file} is not a record!" - exit 1 - fi - else - echo "File ${file} doesn't exist!" - exit 1 - fi - done - rm -f ${tmp_file} - - for dir in "${RECORD_DIRS[@]}"; do - if [[ -d "${dir}" ]]; then - if [[ -z "$(ls ${dir} | grep record)" ]]; then - echo "There is no reord file in ${dir}!" - exit 1 - fi - echo -e ' record_path: "'$(readlink -f ${dir})'"\n' >>"${tmp_file}" - sed -i "/# or, records can be loaded from a directory/r ${tmp_file}" "${TARGET_DIR}/${TASK}.config" - else - echo "Directory ${dir} doesn't exist!" - exit 1 - fi - done - rm -f ${tmp_file} -} - -function install_if_not_exist() { - while [[ $# -gt 0 ]]; do - local pkg=$1 - shift - pip show --files "${pkg}" >/dev/null - if [[ $? -ne 0 ]]; then - if [[ "${pkg}" == "pypcd" ]]; then - _install_pypcd - else - sudo pip install --no-cache-dir "${pkg}" - fi - fi - done -} - -function update_lidar_config() { - local record - local lidar_channels - local tmp_file="${TARGET_DIR}/tmp.txt" - local channel_template="${TEMPLATE_DIR}/channel_template.txt" - local extraction_rate="5" - if [[ ${#RECORD_FILES[*]} -ne 0 ]]; then - record="$(readlink -f ${RECORD_FILES[0]})" - else - record="$(readlink -f ${RECORD_DIRS[0]})/$(ls ${RECORD_DIRS[0]} | grep -m1 record)" - fi - lidar_channels=($(cyber_recorder info ${record} | awk '{print $1}' | - grep "PointCloud2" | grep -v "fusion" | grep -v "compensator")) - - if [ "${#lidar_channels[*]}" -eq 0 ]; then - echo "There is no PointCloud messages in ${record}, please check your record!" - exit 1 - fi - - sed -i "s|__RATE__|${extraction_rate}|g" "${channel_template}" - for channel in "${lidar_channels[@]}"; do - sed -i "s|__NAME__|${channel}|g" "${channel_template}" - cat "${channel_template}" >>"${tmp_file}" - sed -i "s|${channel}|__NAME__|g" "${channel_template}" - done - sed -i "s|${extraction_rate}|__RATE__|g" "${channel_template}" - - sed -i "/# channel of mulitple lidars/{n;N;N;N;N;d}" "${TARGET_DIR}/lidar_to_gnss.config" - sed -i "/# channel of mulitple lidars/r ${tmp_file}" "${TARGET_DIR}/lidar_to_gnss.config" - rm -f ${tmp_file} -} - -function update_camera_config() { - local channel_template="${TEMPLATE_DIR}/channel_template.txt" - local extraction_rate=5 - if [[ ${#RECORD_FILES[*]} -ne 0 ]]; then - record="$(readlink -f ${RECORD_FILES[0]})" - else - record="$(readlink -f ${RECORD_DIRS[0]})/$(ls ${RECORD_DIRS[0]} | grep -m1 record)" - fi - camera_channels=($(cyber_recorder info ${record} | grep "image" | grep -v "compressed" | awk '$2>0{print $1}')) - if [ "${#camera_channels[*]}" -ne 1 ]; then - echo "There should be only one camera channel in ${record}, please check your record!" - exit 1 - fi - sed -i "s|__RATE__|${extraction_rate}|g" "${channel_template}" - sed -i "s|__NAME__|${camera_channels[0]}|g" "${channel_template}" - sed -i "/# channel of camera image channels/{n;N;N;N;N;d}" "${TARGET_DIR}/camera_to_lidar.config" - sed -i "/# channel of camera image channels/r ${channel_template}" "${TARGET_DIR}/camera_to_lidar.config" - sed -i "s|${extraction_rate}|__RATE__|g" "${channel_template}" - sed -i "s|${camera_channels[0]}|__NAME__|g" "${channel_template}" -} - -function main() { - parse_args "$@" - check_target_dir - get_records - if [[ "${TASK}" == "lidar_to_gnss" ]]; then - update_lidar_config - fi - if [[ "${TASK}" == "camera_to_lidar" ]]; then - update_camera_config - fi - install_if_not_exist "pyyaml" "pypcd" - - set -e - - local extract_data_bin="/opt/apollo/neo/packages/tools-dev/latest/sensor_calibration/extract_data" - - if [[ ! -f "${extract_data_bin}" ]];then - extract_data_bin="${TOP_DIR}/bazel-bin/modules/tools/sensor_calibration/extract_data" - fi - - if [[ -f "${extract_data_bin}" ]]; then - "${extract_data_bin}" --config "${TARGET_DIR}/${TASK}.config" - else - bazel run //modules/tools/sensor_calibration:extract_data \ - -- --config "${TARGET_DIR}/${TASK}.config" - fi - - rm -f ${TARGET_DIR}/records/* -} - -main "$@" diff --git a/modules/tools/sensor_calibration/extract_static_data.py b/modules/tools/sensor_calibration/extract_static_data.py deleted file mode 100644 index d9ab77c43d0..00000000000 --- a/modules/tools/sensor_calibration/extract_static_data.py +++ /dev/null @@ -1,356 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -""" -This is a tool to etract useful information from already extracted sensor data, -mainly for camera lidar calibration. -""" - -from datetime import datetime -from shutil import copyfile -import argparse -import cv2 -import os -import six -import sys - -from google.protobuf import text_format -import numpy as np - -from cyber.python.cyber_py3.record import RecordReader -from cyber.proto import record_pb2 -from modules.tools.sensor_calibration.configuration_yaml_generator import ConfigYaml -from modules.tools.sensor_calibration.data_file_object import TimestampFileObject, OdometryFileObject -from modules.tools.sensor_calibration.proto import extractor_config_pb2 - - -CYBER_PATH = os.environ['CYBER_PATH'] -CYBER_RECORD_HEADER_LENGTH = 2048 - -Z_FILL_LEN = 4 -Z_DEFAULT_LEN = 5 - - -def mkdir_p(path): - if not os.path.isdir(path): - os.makedirs(path) - else: - print('folder {} exists'.format(path)) - - -def get_subfolder_list(d): - """list the 1st-level directories under the root directory - ignore hidden folders""" - return [f for f in os.listdir(d) if not f.startswith('.') and - os.path.isdir(os.path.join(d, f))] - - -def sort_files_by_timestamp(in_path, out_path, - timestamp_filename, - extension='.png'): - """sort files by timestamp""" - ts_file = os.path.join(in_path, timestamp_filename) - out_ts_file = os.path.join(out_path, timestamp_filename) - ts_map = np.loadtxt(ts_file) - sorted_ids = np.argsort(ts_map[:, 1]) - ts_map = ts_map[sorted_ids] - # sorted_ts = np.vstack((np.arange(sorted_ids), ts_map[:,1])).T - # np.savetxt(out_ts_file, ts_map, sorted_ts) - ts_obj = TimestampFileObject(file_path=out_ts_file) - ts_obj.save_to_file(ts_map[:, 1]) - - if extension == '.png' or extension == '.pcd': - for i, idx in enumerate(ts_map[:, 0]): - in_file_name = os.path.join(in_path, ("%06d" % (idx + 1)) + extension) - out_file_name = os.path.join(out_path, ("%06d" % (i + 1)) + extension) - copyfile(in_file_name, out_file_name) - - elif extension == 'odometry': - tmp_file = os.path.join(in_path, 'odometry') - in_odm = OdometryFileObject(file_path=tmp_file, - operation='read', - file_type='binary') - data = in_odm.load_file() - sorted_data = [] - for idx in ts_map[:, 0]: - d = data[idx] - sorted_data.append(d) - - tmp_file = os.path.join(out_path, 'odometry') - out_odm = OdometryFileObject(file_path=tmp_file, - operation='write', - file_type='binary') - out_odm.save_to_file(sorted_data) - - -def find_nearest(array, value): - idx = np.searchsorted(array, value, side="left") - if idx > 0 and (idx == len(array) or - math.fabs(value - array[idx-1]) < math.fabs(value - array[idx])): - return idx-1 - else: - return idx - - -def find_synchronized_timestamp_index(query_ts, source_ts, max_threshold=1.0): - # for each element in query, find the nearest element in source, - # if the distance < max_threshold - ts1 = query_ts - ts2 = source_ts - if len(ts1) == 0 or len(ts2) == 0: - return {} - - nearest_index_map = {} - start = 0 - for i in range(len(ts1)): - if start >= len(ts2): - break - - min_ts_diff = max_threshold - min_j = -1 - for j in range(start, len(ts2)): - ts_diff = ts2[j] - ts1[i] - if abs(ts_diff) < min_ts_diff: - min_j = j - min_ts_diff = abs(ts_diff) - - if ts_diff >= 0: - # the rest ts2 > ts1, no need to loop ts2 anymore - break - - if min_j > 0: # find valid nearest index in ts2 - start = min_j # reset start for case i++ - nearest_index_map[i] = min_j - # for i, j in nearest_index_map.items(): - # print([i, j, query_ts[i], source_ts[j]]) - return nearest_index_map - - -def get_difference_score_between_images(path, file_indexes, - suffix=".png", thumbnail_size=32): - image_sum = np.zeros(len(file_indexes), dtype=np.float32) - image_diff = np.zeros(len(file_indexes), dtype=np.float32) - image_thumbnails = [] - for c, idx in enumerate(file_indexes): - image_file = os.path.join(path, str(int(idx)).zfill(Z_DEFAULT_LEN) + suffix) - image = cv2.imread(image_file) - image_thumbnails.append(cv2.resize(image, - (thumbnail_size, thumbnail_size), interpolation=cv2.INTER_AREA)) - image_sum[c] = np.sum(image_thumbnails[-1]) - - image_diff[0] = np.finfo(float).max - for c in range(len(file_indexes)-1, 0, -1): - image_diff[c] = np.sum(cv2.absdiff(image_thumbnails[c], image_thumbnails[c-1])) - image_diff[c] = image_diff[c] / image_sum[c] - - # print("image_diff is: ") - # for i in range(len(image_diff)): - # print([i, image_diff[i], image_sum[i]]) - return image_diff - - -def get_distance_by_odometry(data, i, j): - # calculate x-y plane distance - return np.linalg.norm(data[i, -3:-1] - data[j, -3:-1]) - - -def check_static_by_odometry(data, index, check_range=40, - movable_threshold=0.01): - start_idx = np.maximum(index - check_range, 0) - end_idx = np.minimum(index + check_range, data.shape[0]-1) - # skip if start and end index are too nearby. - if end_idx - start_idx < 2 * check_range: - return False - # calculate x-y plane distance - distance = get_distance_by_odometry(data, start_idx, end_idx) - # print("distance is %d %d %f" % (start_idx, end_idx,distance)) - return distance < movable_threshold - - -def select_static_image_pcd(path, min_distance=5, stop_times=5, - wait_time=3, check_range=50, - image_static_diff_threshold=0.005, - output_folder_name='camera-lidar-pairs', - image_suffix='.jpg', pcd_suffix='.pcd'): - """ - select pairs of images and pcds, odometry information may - come from /apollolocalization/pose as well - """ - subfolders = [x for x in get_subfolder_list( - path) if '_apollo_sensor_' in x or '_localization_pose' in x] - lidar_subfolder = [x for x in subfolders if '_PointCloud2' in x] - odometry_subfolder = [x for x in subfolders if'_odometry' in x or '_localization_pose' in x] - camera_subfolders = [x for x in subfolders if'_image' in x] - if len(lidar_subfolder) is not 1 or \ - len(odometry_subfolder) is not 1: - raise ValueError('only one main lidar and one Odometry' - 'sensor is needed for sensor calibration') - - lidar_subfolder = lidar_subfolder[0] - odometry_subfolder = odometry_subfolder[0] - # load timestamp dictionary - timestamp_dict = {} - for f in subfolders: - f_abs_path = os.path.join(path, f) - ts_file = os.path.join(f_abs_path, 'timestamps') - ts_map = np.loadtxt(ts_file) - timestamp_dict[f] = ts_map - # load odometry binary file - odometry_file = os.path.join(path, odometry_subfolder, 'odometry') - in_odm = OdometryFileObject(file_path=odometry_file, - operation='read', - file_type='binary') - odometry_data = np.array(in_odm.load_file()) - for camera in camera_subfolders: - print("working on sensor message: {}".format(camera)) - camera_gps_nearest_pairs = \ - find_synchronized_timestamp_index( - timestamp_dict[camera][:, 1], - timestamp_dict[odometry_subfolder][:, 1], - max_threshold=0.2) - - camera_lidar_nearest_pairs = \ - find_synchronized_timestamp_index( - timestamp_dict[camera][:, 1], - timestamp_dict[lidar_subfolder][:, 1], - max_threshold=0.5) - - # clean camera-lidar paris not exist in both dictionary - del_ids = [] - for key in camera_lidar_nearest_pairs: - if key not in camera_gps_nearest_pairs: - del_ids.append(key) - for key in del_ids: - del camera_lidar_nearest_pairs[key] - - camera_folder_path = os.path.join(path, camera) - print('foder: {}'.format(camera_folder_path)) - camera_diff = get_difference_score_between_images( - camera_folder_path, timestamp_dict[camera][:, 0], suffix=image_suffix) - valid_image_indexes = [x for x, v in enumerate(camera_diff) - if v <= image_static_diff_threshold] - valid_images = (timestamp_dict[camera][valid_image_indexes, 0]).astype(int) - # generate valid camera frame - candidate_idx = [] - last_idx = -1 - last_odometry_idx = -1 - for i in valid_images: - if i in camera_lidar_nearest_pairs: - odometry_idx = camera_gps_nearest_pairs[i] - # not static considering odometry motion. - if not check_static_by_odometry(odometry_data, - odometry_idx, check_range=check_range): - continue - - if last_idx is -1: - last_idx = i - last_odometry_idx = odometry_idx - candidate_idx.append(i) - continue - time_interval = timestamp_dict[camera][i, 1] - timestamp_dict[camera][last_idx, 1] - odomerty_interval = \ - get_distance_by_odometry(odometry_data, odometry_idx, last_odometry_idx) - # timestamp interval > wait_time and odometry_interval > min_distance` - if time_interval < wait_time or \ - odomerty_interval < min_distance: - continue - - candidate_idx.append(i) - last_idx = i - last_odometry_idx = odometry_idx - # print(odometry_data[odometry_idx]) - # print(odometry_data[last_odometry_idx]) - # print([i, odomerty_interval]) - # check candidate number and select best stop according to camera_diff score - print("all valid static image index: ", candidate_idx) - if len(candidate_idx) < stop_times: - raise ValueError('not enough stops detected,' - 'thus no sufficient data for camera-lidar calibration') - elif len(candidate_idx) > stop_times: - tmp_diff = camera_diff[candidate_idx] - - tmp_idx = np.argsort(tmp_diff)[:stop_times] - candidate_idx = [candidate_idx[x] for x in tmp_idx] - candidate_idx.sort() - # save files - image_idx = candidate_idx - print("selected best static image index: ", image_idx) - lidar_idx = [camera_lidar_nearest_pairs[x] for x in image_idx] - output_path = os.path.join(camera_folder_path, output_folder_name) - mkdir_p(output_path) - for count, i in enumerate(image_idx): - # save images - in_file = os.path.join(camera_folder_path, str( - int(i)).zfill(Z_DEFAULT_LEN) + image_suffix) - out_file = os.path.join(output_path, str( - int(count)).zfill(Z_FILL_LEN) + '_00' + image_suffix) - copyfile(in_file, out_file) - j = camera_lidar_nearest_pairs[i] - # save pcd - in_file = os.path.join(path, lidar_subfolder, str( - int(j)).zfill(Z_DEFAULT_LEN) + pcd_suffix) - out_file = os.path.join(output_path, str( - int(count)).zfill(Z_FILL_LEN) + '_00' + pcd_suffix) - copyfile(in_file, out_file) - print("generate image-lidar-pair:[%d, %d]" % (i, j)) - return camera_subfolders, lidar_subfolder - - -def main2(): - for str in ['_apollo_sensor_lidar16_front_center_PointCloud2', - '_apollo_sensor_lidar16_rear_left_PointCloud2', - '_apollo_sensor_lidar16_rear_right_PointCloud2', - '_apollo_sensor_lidar128_PointCloud2']: - # _apollo_sensor_lidar128_PointCloud2' - in_path = '/apollo/data/Lidar_GNSS_Calibration-2019-07-12-15-25/' + str - out_path = os.path.join(in_path, 'new') - mkdir_p(out_path) - timestamp_filename = 'timestamps.txt' - extension = '.pcd' - sort_files_by_timestamp(in_path, out_path, timestamp_filename, extension=extension) - - in_path = '/apollo/data/Lidar_GNSS_Calibration-2019-07-12-15-25/_apollo_sensor_gnss_odometry' - out_path = os.path.join(in_path, 'new') - mkdir_p(out_path) - timestamp_filename = 'timestamps.txt' - extension = 'odometry' - sort_files_by_timestamp(in_path, out_path, timestamp_filename, extension=extension) - - -def main(): - if CYBER_PATH is None: - print('Error: environment variable CYBER_PATH was not found, ' - 'set environment first.') - sys.exit(1) - - os.chdir(CYBER_PATH) - - parser = argparse.ArgumentParser( - description='A tool to extract useful data information for camera-to-lidar calibration.') - parser.add_argument("-i", "--workspace_path", action="store", default="", required=True, - dest='workspace', - help="Specify the worksapce where storing extracted sensor messages") - args = parser.parse_args() - - select_static_image_pcd(path=args.workspace, min_distance=5, stop_times=5, - wait_time=3, check_range=50, - image_static_diff_threshold=0.005) - - -if __name__ == '__main__': - main() diff --git a/modules/tools/sensor_calibration/ins_stat_publisher.py b/modules/tools/sensor_calibration/ins_stat_publisher.py deleted file mode 100755 index 38b332bf7b1..00000000000 --- a/modules/tools/sensor_calibration/ins_stat_publisher.py +++ /dev/null @@ -1,75 +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. -############################################################################### - -import argparse -import atexit -import logging -import os -import sys -import time - -#from common.logger import Logger -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import cyber_time - -from modules.common_msgs.sensor_msgs import ins_pb2 - - -class InsStat(object): - def __init__(self,node): - self.insstat_pub = node.create_writer('/apollo/sensor/gnss/ins_stat', ins_pb2.InsStat) - self.sequence_num = 0 - self.terminating = False - - def publish_statmsg(self): - insstat = ins_pb2.InsStat() - now = cyber_time.Time.now().to_sec() - insstat.header.timestamp_sec = now - insstat.header.module_name = "ins_stat" - insstat.header.sequence_num = self.sequence_num - self.sequence_num = self.sequence_num + 1 - insstat.ins_status = 3 - insstat.pos_type = 56 - #self.logger.info("%s"%insstat) - self.insstat_pub.write(insstat) - - def shutdown(self): - """ - shutdown rosnode - """ - self.terminating = True - #self.logger.info("Shutting Down...") - time.sleep(0.2) - -def main(): - """ - Main rosnode - """ - node=cyber.Node('ins_stat_publisher') - ins_stat = InsStat(node) - while not cyber.is_shutdown(): - now = cyber_time.Time.now().to_sec() - ins_stat.publish_statmsg() - sleep_time = 0.5 - (cyber_time.Time.now().to_sec() - now) - if sleep_time > 0: - time.sleep(sleep_time) - -if __name__ == '__main__': - cyber.init() - main() - cyber.shutdown() diff --git a/modules/tools/sensor_calibration/odom_publisher.py b/modules/tools/sensor_calibration/odom_publisher.py deleted file mode 100755 index 69077f3941d..00000000000 --- a/modules/tools/sensor_calibration/odom_publisher.py +++ /dev/null @@ -1,112 +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. -############################################################################### - -import argparse -import atexit -import logging -import os -import sys -import time - -#from common.logger import Logger -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import cyber_time - -from modules.common_msgs.localization_msgs import localization_pb2 -from modules.common_msgs.localization_msgs import gps_pb2 - -class OdomPublisher(object): - def __init__(self, node): - self.localization = localization_pb2.LocalizationEstimate() - self.gps_odom_pub = node.create_writer('/apollo/sensor/gnss/odometry', gps_pb2.Gps) - self.sequence_num = 0 - self.terminating = False - self.position_x = 0 - self.position_y = 0 - self.position_z = 0 - self.orientation_x = 0 - self.orientation_y = 0 - self.orientation_z = 0 - self.orientation_w = 0 - self.linear_velocity_x = 0 - self.linear_velocity_y = 0 - self.linear_velocity_z = 0 - - def localization_callback(self, data): - """ - New message received - """ - self.localization.CopyFrom(data) - self.position_x = self.localization.pose.position.x - self.position_y = self.localization.pose.position.y - self.position_z = self.localization.pose.position.z - self.orientation_x = self.localization.pose.orientation.qx - self.orientation_y = self.localization.pose.orientation.qy - self.orientation_z = self.localization.pose.orientation.qz - self.orientation_w = self.localization.pose.orientation.qw - self.linear_velocity_x = self.localization.pose.linear_velocity.x - self.linear_velocity_y = self.localization.pose.linear_velocity.y - self.linear_velocity_z = self.localization.pose.linear_velocity.z - - def publish_odom(self): - odom = gps_pb2.Gps() - now = cyber_time.Time.now().to_sec() - odom.header.timestamp_sec = now - odom.header.module_name = "odometry" - odom.header.sequence_num = self.sequence_num - self.sequence_num = self.sequence_num + 1 - - odom.localization.position.x = self.position_x - odom.localization.position.y = self.position_y - odom.localization.position.z = self.position_z - odom.localization.orientation.qx = self.orientation_x - odom.localization.orientation.qy = self.orientation_y - odom.localization.orientation.qz = self.orientation_z - odom.localization.orientation.qw = self.orientation_w - odom.localization.linear_velocity.x = self.linear_velocity_x - odom.localization.linear_velocity.y = self.linear_velocity_y - odom.localization.linear_velocity.z = self.linear_velocity_z - #self.logger.info("%s"%odom) - self.gps_odom_pub.write(odom) - - def shutdown(self): - """ - shutdown rosnode - """ - self.terminating = True - #self.logger.info("Shutting Down...") - time.sleep(0.2) - -def main(): - """ - Main rosnode - """ - node = cyber.Node('odom_publisher') - odom = OdomPublisher(node) - node.create_reader('/apollo/localization/pose', localization_pb2.LocalizationEstimate, odom.localization_callback) - while not cyber.is_shutdown(): - now = cyber_time.Time.now().to_sec() - odom.publish_odom() - sleep_time = 0.01 - (cyber_time.Time.now().to_sec() - now) - if sleep_time > 0: - time.sleep(sleep_time) - -if __name__ == '__main__': - cyber.init() - main() - cyber.shutdown() diff --git a/modules/tools/sensor_calibration/proto/BUILD b/modules/tools/sensor_calibration/proto/BUILD deleted file mode 100644 index d7a7381eb3e..00000000000 --- a/modules/tools/sensor_calibration/proto/BUILD +++ /dev/null @@ -1,25 +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") - -package(default_visibility = ["//visibility:public"]) - -cc_proto_library( - name = "extractor_config_cc_proto", - deps = [ - ":extractor_config_proto", - ], -) - -proto_library( - name = "extractor_config_proto", - srcs = ["extractor_config.proto"], -) - -py_proto_library( - name = "extractor_config_py_pb2", - deps = [ - ":extractor_config_proto", - ], -) diff --git a/modules/tools/sensor_calibration/proto/extractor_config.proto b/modules/tools/sensor_calibration/proto/extractor_config.proto deleted file mode 100644 index e38c5ebfccd..00000000000 --- a/modules/tools/sensor_calibration/proto/extractor_config.proto +++ /dev/null @@ -1,47 +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. - *****************************************************************************/ - -// data extractor configuration - -syntax = "proto2"; - -message IoConfig { - required string task_name = 1 [default = "tmp"]; - required string output_path = 2 [default = "extracted_data"]; - optional string start_timestamp = 3 [default = "FLOAT_MIN"]; - optional string end_timestamp = 4 [default = "FLOAT_MAX"]; - optional string main_sensor = 5; -}; - -message ChannelConfig { - optional string description = 1 [default = ""]; - required string name = 2; - required uint32 extraction_rate = 3 [default = 1]; -}; - -message Channels { - repeated ChannelConfig channel = 1; -}; - -message Records { - repeated string record_path = 1; -}; - -message DataExtractionConfig { - required IoConfig io_config = 1; - required Channels channels = 2; - required Records records = 3; -}; diff --git a/modules/tools/sensor_calibration/sanity_check.py b/modules/tools/sensor_calibration/sanity_check.py deleted file mode 100644 index 0189c2d057b..00000000000 --- a/modules/tools/sensor_calibration/sanity_check.py +++ /dev/null @@ -1,171 +0,0 @@ -#!/usr/bin/env python - -############################################################################### -# 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. -############################################################################### -""" -This is a tool to sanity check the output files of extract_data.py -""" - -import os -import yaml - -from absl import app -from absl import flags -from absl import logging - -import modules.tools.common.file_utils as file_utils - -flags.DEFINE_string('input_folder', '', 'The folder stores extracted messages') - - -def missing_config_file(path): - sample_config_files = [] - for (dirpath, _, filenames) in os.walk(path): - for filename in filenames: - if filename == 'sample_config.yaml': - end_file = os.path.join(dirpath, filename) - sample_config_files.append(end_file) - if (len(sample_config_files) == 0): - return True, [] - return False, sample_config_files - - -def missing_calibration_task(sample_config_files): - for sample_config_file in sample_config_files: - print(sample_config_file) - with open(sample_config_file, 'r') as f: - data = yaml.safe_load(f) - if not ('calibration_task' in data): - return True - return False - - -def file_type_exist(file_dir, file_type): - files = os.listdir(file_dir) - - for k in range(len(files)): - files[k] = os.path.splitext(files[k])[1] - if file_type in files: - return True - return False - - -def list_to_str(data): - if isinstance(data, list): - return data[0] - else: - return data - - -def missing_lidar_gnss_file(lidar_gnss_config): - with open(lidar_gnss_config, 'r') as f: - data = yaml.safe_load(f) - yaml_dir = os.path.dirname(lidar_gnss_config) - odometry_dir = os.path.join(yaml_dir, data['odometry_file']) - point_cloud_dir = os.path.join(yaml_dir, - list_to_str(data['sensor_files_directory'])) - logging.info( - f"odometry_dir:{odometry_dir} , point_cloud_dir: {point_cloud_dir}") - if not os.access(odometry_dir, os.F_OK): - logging.info('odometry file does not exist') - return True - if not file_type_exist(point_cloud_dir, '.pcd'): - logging.info('pcd file does not exist') - return True - return False - - -def missing_camera_lidar_file(camera_lidar_configs): - with open(camera_lidar_configs, 'r') as f: - data = yaml.safe_load(f) - yaml_dir = os.path.dirname(camera_lidar_configs) - camera_lidar_pairs_dir = os.path.join(yaml_dir, data['data_path']) - extrinsics_yaml_dir = os.path.join(yaml_dir, data['extrinsic']) - intrinsics_yaml_dir = os.path.join(yaml_dir, data['intrinsic']) - jpg_flag = file_type_exist(camera_lidar_pairs_dir, '.jpg') - pcd_flag = file_type_exist(camera_lidar_pairs_dir, '.pcd') - if not (jpg_flag and pcd_flag): - logging.info('camera_lidar_pairs data error') - return True - if not os.access(extrinsics_yaml_dir, os.F_OK): - logging.info('extrinsics_yaml file does not exist') - return True - if not os.access(intrinsics_yaml_dir, os.F_OK): - logging.info('intrinsics_yaml file does not exist') - return True - return False - - -def missing_calibration_data_file(sample_config_files): - lidar_file_flag = False - camera_file_flag = False - for sample_config_file in sample_config_files: - with open(sample_config_file, 'r') as f: - data = yaml.safe_load(f) - if data['calibration_task'] == 'lidar_to_gnss': - if (missing_lidar_gnss_file(sample_config_file)): - lidar_file_flag = True - if data['calibration_task'] == 'camera_to_lidar': - if (missing_camera_lidar_file(sample_config_file)): - camera_file_flag = True - return lidar_file_flag, camera_file_flag - - -def is_oversize_file(path): - dir_size = file_utils.getInputDirDataSize(path) - if dir_size == 0: - logging.error('The input dir is empty!') - return True - if dir_size >= 5 * 1024 * 1024 * 1024: - logging.error('The record file is oversize!') - return True - return False - - -def sanity_check(input_folder): - err_msg = None - lidar_gnss_flag = False - camera_lidar_flag = False - if is_oversize_file(input_folder): - err_msg = "The input file is oversize(1G)!" - - config_flag, config_files = missing_config_file(input_folder) - if config_flag: - err_msg = "Missing sample_config.yaml!" - if missing_calibration_task(config_files): - err_msg = "The sample_config.yaml file miss calibration_task config!" - lidar_gnss_flag, camera_lidar_flag = missing_calibration_data_file( - config_files) - if lidar_gnss_flag and not camera_lidar_flag: - err_msg = "Missing Lidar_gnss files!" - elif not lidar_gnss_flag and camera_lidar_flag: - err_msg = "Missing camera_lidar files!" - elif lidar_gnss_flag and camera_lidar_flag: - err_msg = "Missing lidar_gnss and camera_lidar files!" - else: - info_msg = f"{input_folder} Passed sanity check." - logging.info(info_msg) - return True, info_msg - logging.error(err_msg) - return False, err_msg - - -def main(argv): - sanity_check(input_folder=flags.FLAGS.input_folder) - - -if __name__ == "__main__": - app.run(main) diff --git a/modules/tools/sensor_calibration/sensor_msg_extractor.py b/modules/tools/sensor_calibration/sensor_msg_extractor.py deleted file mode 100644 index f7d271bd307..00000000000 --- a/modules/tools/sensor_calibration/sensor_msg_extractor.py +++ /dev/null @@ -1,397 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# 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. -############################################################################### - -""" -This is a bunch of classes to manage cyber record channel extractor. -""" - -import os -import struct -import sys - -import cv2 -import numpy as np - -from pypcd import pypcd - -from modules.tools.sensor_calibration.data_file_object import TimestampFileObject, OdometryFileObject -from modules.common_msgs.sensor_msgs import conti_radar_pb2 -from modules.common_msgs.sensor_msgs import sensor_image_pb2 -from modules.common_msgs.sensor_msgs import pointcloud_pb2 -from modules.common_msgs.localization_msgs import gps_pb2 -from modules.common_msgs.localization_msgs import localization_pb2 - - -class SensorMessageParser(object): - """Wrapper for cyber channel message extractor""" - - # Initializing extractor - def __init__(self, output_path, instance_saving=True): - """ - instance_saving: - True for large channel message, e.g., Camera/lidar/Radar; - False for small channel message, e.g., GNSS topics - """ - self._msg_parser = None - self._timestamps = [] - self._proto_parser = None - self._init_parser() - self._parsed_data = None - self._output_path = output_path - self._timestamp_file = os.path.join(self._output_path, "timestamps") - self._instance_saving = instance_saving - - # initializing msg and proto parser - def _init_parser(self): - raise NotImplementedError - - def parse_sensor_message(self, msg): - raise NotImplementedError - - def save_messages_to_file(self): - return True - - def get_msg_count(self): - return len(self._timestamps) - - def get_timestamps(self): - return self._timestamps - - def save_timestamps_to_file(self): - timestamp_file_obj = TimestampFileObject(self._timestamp_file, - operation='write', - file_type='txt') - timestamp_file_obj.save_to_file(self._timestamps) - return True - - -class GpsParser(SensorMessageParser): - """ - class to parse GNSS odometry channel. - saving this small topic as a whole. - """ - - def __init__(self, output_path, instance_saving=False): - super(GpsParser, self).__init__(output_path, instance_saving) - if not self._instance_saving: - self._parsed_data = [] - self._odomotry_output_file = os.path.join(self._output_path, "odometry") - - def _init_parser(self): - self._msg_parser = gps_pb2.Gps() - - def parse_sensor_message(self, msg): - """ parse Gps information from GNSS odometry channel""" - gps = self._msg_parser - gps.ParseFromString(msg.message) - - # all double, except point_type is int32 - ts = gps.header.timestamp_sec - self._timestamps.append(ts) - - point_type = 56 - qw = gps.localization.orientation.qw - qx = gps.localization.orientation.qx - qy = gps.localization.orientation.qy - qz = gps.localization.orientation.qz - x = gps.localization.position.x - y = gps.localization.position.y - z = gps.localization.position.z - # save 9 values as a tuple, for eaisier struct packing during storage - if self._instance_saving: - raise ValueError("Gps odometry should be saved in a file") - else: - self._parsed_data.append((ts, point_type, qw, qx, qy, qz, x, y, z)) - - return True - - def save_messages_to_file(self): - """save list of parsed Odometry messages to file""" - odometry_file_obj = OdometryFileObject(file_path=self._odomotry_output_file, - operation='write', - file_type='binary') - odometry_file_obj.save_to_file(self._parsed_data) - return True - - -class PoseParser(GpsParser): - """ - inherit similar data saver and data structure from GpsParser - save the ego-localization information same as odometry - """ - - def _init_parser(self): - self._msg_parser = localization_pb2.LocalizationEstimate() - - def parse_sensor_message(self, msg): - """ parse localization information from localization estimate channel""" - loc_est = self._msg_parser - loc_est.ParseFromString(msg.message) - - # all double, except point_type is int32 - ts = loc_est.header.timestamp_sec - self._timestamps.append(ts) - - point_type = 56 - qw = loc_est.pose.orientation.qw - qx = loc_est.pose.orientation.qx - qy = loc_est.pose.orientation.qy - qz = loc_est.pose.orientation.qz - x = loc_est.pose.position.x - y = loc_est.pose.position.y - z = loc_est.pose.position.z - # save 9 values as a tuple, for eaisier struct packing during storage - if self._instance_saving: - raise ValueError("localization--pseudo odometry-- should be saved in a file") - else: - self._parsed_data.append((ts, point_type, qw, qx, qy, qz, x, y, z)) - - return True - - -class PointCloudParser(SensorMessageParser): - """ - class to parse apollo/$(lidar)/PointCloud2 channels. - saving separately each parsed msg - """ - - def __init__(self, output_path, instance_saving=True, suffix='.pcd'): - super(PointCloudParser, self).__init__(output_path, instance_saving) - self._suffix = suffix - - def convert_xyzit_pb_to_array(self, xyz_i_t, data_type): - arr = np.zeros(len(xyz_i_t), dtype=data_type) - for i, point in enumerate(xyz_i_t): - # change timestamp to timestamp_sec - arr[i] = (point.x, point.y, point.z, - point.intensity, point.timestamp/1e9) - return arr - - def make_xyzit_point_cloud(self, xyz_i_t): - """ - Make a pointcloud object from PointXYZIT message, as Pointcloud.proto. - message PointXYZIT { - optional float x = 1 [default = nan]; - optional float y = 2 [default = nan]; - optional float z = 3 [default = nan]; - optional uint32 intensity = 4 [default = 0]; - optional uint64 timestamp = 5 [default = 0]; - } - """ - - md = {'version': .7, - 'fields': ['x', 'y', 'z', 'intensity', 'timestamp'], - 'count': [1, 1, 1, 1, 1], - 'width': len(xyz_i_t), - 'height': 1, - 'viewpoint': [0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0], - 'points': len(xyz_i_t), - 'type': ['F', 'F', 'F', 'U', 'F'], - 'size': [4, 4, 4, 4, 8], - 'data': 'binary_compressed'} - - typenames = [] - for t, s in zip(md['type'], md['size']): - np_type = pypcd.pcd_type_to_numpy_type[(t, s)] - typenames.append(np_type) - - np_dtype = np.dtype(list(zip(md['fields'], typenames))) - pc_data = self.convert_xyzit_pb_to_array(xyz_i_t, data_type=np_dtype) - pc = pypcd.PointCloud(md, pc_data) - return pc - - def save_pointcloud_meta_to_file(self, pc_meta, pcd_file): - pypcd.save_point_cloud_bin_compressed(pc_meta, pcd_file) - - def _init_parser(self): - self._msg_parser = pointcloud_pb2.PointCloud() - - def parse_sensor_message(self, msg): - """ - Transform protobuf PointXYZIT to standard PCL bin_compressed_file(*.pcd). - """ - pointcloud = self._msg_parser - pointcloud.ParseFromString(msg.message) - - self._timestamps.append(pointcloud.measurement_time) - # self._timestamps.append(pointcloud.header.timestamp_sec) - - self._parsed_data = self.make_xyzit_point_cloud(pointcloud.point) - - if self._instance_saving: - file_name = "%05d" % self.get_msg_count() + self._suffix - output_file = os.path.join(self._output_path, file_name) - self.save_pointcloud_meta_to_file(pc_meta=self._parsed_data, pcd_file=output_file) - else: - raise ValueError("not implement multiple message concatenation for PointCloud2 topic") - # TODO(gchen-Apollo): add saint check - return True - - -class ImageParser(SensorMessageParser): - """ - class to parse apollo/$(camera)/image channels. - saving separately each parsed msg - """ - - def __init__(self, output_path, instance_saving=True, suffix='.jpg'): - super(ImageParser, self).__init__(output_path, instance_saving) - self._suffix = suffix - - def _init_parser(self): - self._msg_parser = sensor_image_pb2.Image() - - def parse_sensor_message(self, msg): - - image = self._msg_parser - image.ParseFromString(msg.message) - - self._timestamps.append(image.header.timestamp_sec) - # Save image according to cyber format, defined in sensor camera proto. - # height = 4, image height, that is, number of rows. - # width = 5, image width, that is, number of columns. - # encoding = 6, as string, type is 'rgb8', 'bgr8' or 'gray'. - # step = 7, full row length in bytes. - # data = 8, actual matrix data in bytes, size is (step * rows). - # type = CV_8UC1 if image step is equal to width as gray, CV_8UC3 - # if step * 3 is equal to width. - if image.encoding == 'rgb8' or image.encoding == 'bgr8': - if image.step != image.width * 3: - print('Image.step %d does not equal to Image.width %d * 3 for color image.' - % (image.step, image.width)) - return False - elif image.encoding == 'gray' or image.encoding == 'y': - if image.step != image.width: - print('Image.step %d does not equal to Image.width %d or gray image.' - % (image.step, image.width)) - return False - else: - print('Unsupported image encoding type: %s.' % image.encoding) - return False - - channel_num = image.step // image.width - self._parsed_data = np.fromstring(image.data, dtype=np.uint8).reshape( - (image.height, image.width, channel_num)) - - if self._instance_saving: - file_name = "%05d" % self.get_msg_count() + self._suffix - output_file = os.path.join(self._output_path, file_name) - self.save_image_mat_to_file(image_file=output_file) - else: - raise ValueError("not implement multiple message concatenation for Image topic") - - return True - - def save_image_mat_to_file(self, image_file): - # Save image in BGR oder - image_mat = self._parsed_data - if self._msg_parser.encoding == 'rgb8': - cv2.imwrite(image_file, cv2.cvtColor(image_mat, cv2.COLOR_RGB2BGR)) - else: - cv2.imwrite(image_file, image_mat) - - -class ContiRadarParser(SensorMessageParser): - """ - class to parse apollo/sensor/radar/$(position) channels. - saving separately each parsed msg - """ - - def __init__(self, output_path, instance_saving=True, suffix='.pcd'): - super(ContiRadarParser, self).__init__(output_path, instance_saving) - self._suffix = suffix - - def convert_contiobs_pb_to_array(self, obs, data_type): - arr = np.zeros(len(obs), dtype=data_type) - for i, ob in enumerate(obs): - # change timestamp to timestamp_sec - # z value is 0 - # now using x, y, z, and t. later more information will be added - arr[i] = (ob.longitude_dist, ob.lateral_dist, 0, ob.header.timestamp_sec) - return arr - - def make_contidata_point_cloud(self, contiobs): - """ - Make a pointcloud object from contiradar message, as conti_radar.proto. - message ContiRadarObs { - // x axis ^ - // | longitude_dist - // | - // | - // | - // lateral_dist | - // y axis | - // <---------------- - // ooooooooooooo //radar front surface - - optional apollo.common.Header header = 1; - // longitude distance to the radar; (+) = forward; unit = m - optional double longitude_dist = 4; - // lateral distance to the radar; (+) = left; unit = m - optional double lateral_dist = 5; - ....... - } - """ - - md = {'version': .7, - 'fields': ['x', 'y', 'z', 'timestamp'], - 'count': [1, 1, 1, 1], - 'width': len(contiobs), - 'height': 1, - 'viewpoint': [0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0], - 'points': len(contiobs), - 'type': ['F', 'F', 'F', 'F'], - 'size': [4, 4, 4, 8], - 'data': 'binary'} - - typenames = [] - for t, s in zip(md['type'], md['size']): - np_type = pypcd.pcd_type_to_numpy_type[(t, s)] - typenames.append(np_type) - - np_dtype = np.dtype(list(zip(md['fields'], typenames))) - pc_data = self.convert_contiobs_pb_to_array(contiobs, data_type=np_dtype) - pc = pypcd.PointCloud(md, pc_data) - return pc - - def save_pointcloud_meta_to_file(self, pc_meta, pcd_file): - pypcd.save_point_cloud_bin(pc_meta, pcd_file) - - def _init_parser(self): - self._msg_parser = conti_radar_pb2.ContiRadar() - - def parse_sensor_message(self, msg): - """ - Transform protobuf radar message to standard PCL bin_file(*.pcd). - """ - radar_data = self._msg_parser - radar_data.ParseFromString(msg.message) - - self._timestamps.append(radar_data.header.timestamp_sec) - # self._timestamps.append(pointcloud.header.timestamp_sec) - - self._parsed_data = self.make_contidata_point_cloud(radar_data.contiobs) - - if self._instance_saving: - file_name = "%05d" % self.get_msg_count() + self._suffix - output_file = os.path.join(self._output_path, file_name) - self.save_pointcloud_meta_to_file(pc_meta=self._parsed_data, pcd_file=output_file) - else: - raise ValueError("not implement multiple message concatenation for COontiRadar topic") - # TODO(gchen-Apollo): add saint check - return True diff --git a/modules/tools/sensor_calibration/template/camera_to_lidar/camera_to_lidar.config b/modules/tools/sensor_calibration/template/camera_to_lidar/camera_to_lidar.config deleted file mode 100644 index 7b463402d6d..00000000000 --- a/modules/tools/sensor_calibration/template/camera_to_lidar/camera_to_lidar.config +++ /dev/null @@ -1,44 +0,0 @@ -# data extraction configuration for multi-camera to lidar calibration -# must includes: -# at least 1 camera image channel -# lidar 16 point cloud channel -# GNSS Gps/odometry channel - -io_config: { - task_name: "camera_to_lidar" - output_path: "/apollo/output/sensor_calibration/camera_to_lidar/extracted_data" - # start_timestamp: "FLOAT_MIN" - # end_timestamp: "FLOAT_MAX" - # start_timestamp: "1553901009.071362291" - # end_timestamp: "1553901012.01" -} - -records: { - # records can be specified as a list - #record_path: "/apollo/data/bag/test/20190325185008.record.00001" - #record_path: "/apollo/data/bag/test/20190325185008.record.00002" - #record_path: "/apollo/data/bag/test/20190325185008.record.00003" - # or, records can be loaded from a directory - # record_path: "/apollo/output/sensor_calibration/camera_to_lidar/records" -} - -channels: { - # channel of camera image channels - channel: { - description: "front camera 6mm" - name: "/apollo/sensor/camera/front_6mm/image" - extraction_rate: 5 - } - # channel of 16-beam lidar - channel: { - description: "lidar 16 point cloud" - name: "/apollo/sensor/lidar16/PointCloud2" - extraction_rate: 5 - } - # channel of localization pose odometry - channel: { - description: "GNSS odometry" - name: "/apollo/localization/pose" - extraction_rate: 1 - } -} diff --git a/modules/tools/sensor_calibration/template/camera_to_lidar/channel_template.txt b/modules/tools/sensor_calibration/template/camera_to_lidar/channel_template.txt deleted file mode 100644 index 4e6359df3e0..00000000000 --- a/modules/tools/sensor_calibration/template/camera_to_lidar/channel_template.txt +++ /dev/null @@ -1,4 +0,0 @@ - channel: { - name: "__NAME__" - extraction_rate: __RATE__ - } diff --git a/modules/tools/sensor_calibration/template/camera_to_lidar/extracted_data/readme.txt b/modules/tools/sensor_calibration/template/camera_to_lidar/extracted_data/readme.txt deleted file mode 100644 index 0dfd31e528a..00000000000 --- a/modules/tools/sensor_calibration/template/camera_to_lidar/extracted_data/readme.txt +++ /dev/null @@ -1 +0,0 @@ -output_path diff --git a/modules/tools/sensor_calibration/template/camera_to_lidar/records/readme.txt b/modules/tools/sensor_calibration/template/camera_to_lidar/records/readme.txt deleted file mode 100644 index 3d3d3398edc..00000000000 --- a/modules/tools/sensor_calibration/template/camera_to_lidar/records/readme.txt +++ /dev/null @@ -1 +0,0 @@ -record_path diff --git a/modules/tools/sensor_calibration/template/lidar_to_gnss/channel_template.txt b/modules/tools/sensor_calibration/template/lidar_to_gnss/channel_template.txt deleted file mode 100644 index 4e6359df3e0..00000000000 --- a/modules/tools/sensor_calibration/template/lidar_to_gnss/channel_template.txt +++ /dev/null @@ -1,4 +0,0 @@ - channel: { - name: "__NAME__" - extraction_rate: __RATE__ - } diff --git a/modules/tools/sensor_calibration/template/lidar_to_gnss/extracted_data/readme.txt b/modules/tools/sensor_calibration/template/lidar_to_gnss/extracted_data/readme.txt deleted file mode 100644 index 0dfd31e528a..00000000000 --- a/modules/tools/sensor_calibration/template/lidar_to_gnss/extracted_data/readme.txt +++ /dev/null @@ -1 +0,0 @@ -output_path diff --git a/modules/tools/sensor_calibration/template/lidar_to_gnss/lidar_to_gnss.config b/modules/tools/sensor_calibration/template/lidar_to_gnss/lidar_to_gnss.config deleted file mode 100644 index 7d02edbc2d1..00000000000 --- a/modules/tools/sensor_calibration/template/lidar_to_gnss/lidar_to_gnss.config +++ /dev/null @@ -1,38 +0,0 @@ -# data extraction configuration for multi-lidar to GNSS Gps calibration -# must includes: -# at least 1 lidar pointcloud2 channel -# GNSS Gps/odometry channel - -io_config: { - # task name now only support "camera_to_lidar, lidar_to_gnss" - task_name: "lidar_to_gnss" - output_path: "/apollo/output/sensor_calibration/lidar_to_gnss/extracted_data" - # start_timestamp: "FLOAT_MIN" - # end_timestamp: "FLOAT_MAX" - # start_timestamp: "1553901009.071362291" - # end_timestamp: "1553901012.01" -} - -records: { - # records can be specified as a list - #record_path: "/apollo/data/bag/test/20190325185008.record.00001" - #record_path: "/apollo/data/bag/test/20190325185008.record.00002" - #record_path: "/apollo/data/bag/test/20190325185008.record.00003" - # or, records can be loaded from a directory - #record_path: "/apollo/output/sensor_calibration/lidar_to_gnss/records" -} - -channels: { - # channel of mulitple lidars - channel: { - description: "lidar 16 front up point cloud" - name: "/apollo/sensor/lidar16/PointCloud2" - extraction_rate: 5 - } - # channel of GNSS odometry - channel: { - description: "localization pose" - name: "/apollo/localization/pose" - extraction_rate: 1 - } -} diff --git a/modules/tools/sensor_calibration/template/lidar_to_gnss/records/readme.txt b/modules/tools/sensor_calibration/template/lidar_to_gnss/records/readme.txt deleted file mode 100644 index 3d3d3398edc..00000000000 --- a/modules/tools/sensor_calibration/template/lidar_to_gnss/records/readme.txt +++ /dev/null @@ -1 +0,0 @@ -record_path diff --git a/modules/tools/tools.BUILD b/modules/tools/tools.BUILD deleted file mode 100644 index acfc87ea8e1..00000000000 --- a/modules/tools/tools.BUILD +++ /dev/null @@ -1,11 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_library") - -cc_library( - name = "tools", - includes = ["include"], - hdrs = glob(["include/**/*.h"]), - srcs = glob(["lib/**/*.so*"]), - include_prefix = "modules/tools", - strip_include_prefix = "include", - visibility = ["//visibility:public"], -) \ No newline at end of file diff --git a/modules/tools/vehicle_calibration/BUILD b/modules/tools/vehicle_calibration/BUILD deleted file mode 100644 index f5ee43b2f40..00000000000 --- a/modules/tools/vehicle_calibration/BUILD +++ /dev/null @@ -1,104 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary", "py_library") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -install( - name = "install", - data = ["runtime_files"], - data_dest = "tools/vehicle_calibration", - py_dest = "tools/vehicle_calibration", - targets = [ - ":data_collector", - ":plot_data", - ":plot_grid", - ":plot_results", - ":preprocess", - ":process_data", - ":result2pb", - ] -) - -py_binary( - name = "data_collector", - srcs = ["data_collector.py"], - deps = [ - ":plot_data", - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:cyber_time", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/control_msgs:control_cmd_py_pb2", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - ], -) - -py_binary( - name = "plot_data", - srcs = ["plot_data.py"], - deps = [ - ":process", - ], -) - -py_binary( - name = "plot_grid", - srcs = ["plot_grid.py"], -) - -py_binary( - name = "plot_results", - srcs = ["plot_results.py"], -) - -py_binary( - name = "preprocess", - srcs = ["preprocess.py"], - deps = [ - ":sanity_check", - "//cyber/python/cyber_py3:cyber", - "//modules/dreamview/proto:preprocess_table_py_pb2", - ], -) - -py_library( - name = "process", - srcs = ["process.py"], -) - -py_binary( - name = "process_data", - srcs = ["process_data.py"], - deps = [ - ":process", - ], -) - -py_binary( - name = "result2pb", - srcs = ["result2pb.py"], - deps = [ - "//modules/control/proto:calibration_table_py_pb2", - "//modules/control/proto:control_conf_py_pb2", - "//modules/tools/common:proto_utils", - ], -) - -py_library( - name = "sanity_check", - srcs = ["sanity_check.py"], - deps = [ - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/config_msgs:vehicle_config_py_pb2", - "//modules/tools/common:file_utils", - "//modules/tools/common:proto_utils", - ], -) - -filegroup( - name = "runtime_files", - srcs = glob([ - "calibration_data_sample/**", - "*.py", - "*.sh", - ]), -) diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/b13_up.txt b/modules/tools/vehicle_calibration/calibration_data_sample/b13_up.txt deleted file mode 100644 index 19f40504200..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/b13_up.txt +++ /dev/null @@ -1,9 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 13.0 -a: throttle = 0.0 -c: vehicle_speed >= 10.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/b15_up.txt b/modules/tools/vehicle_calibration/calibration_data_sample/b15_up.txt deleted file mode 100644 index b24653d6bdb..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/b15_up.txt +++ /dev/null @@ -1,9 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 15.0 -a: throttle = 0.0 -c: vehicle_speed >= 10.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/b17_up.txt b/modules/tools/vehicle_calibration/calibration_data_sample/b17_up.txt deleted file mode 100644 index cd954115193..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/b17_up.txt +++ /dev/null @@ -1,9 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 17.0 -a: throttle = 0.0 -c: vehicle_speed >= 10.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/b20_up.txt b/modules/tools/vehicle_calibration/calibration_data_sample/b20_up.txt deleted file mode 100644 index 598f9579946..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/b20_up.txt +++ /dev/null @@ -1,9 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 20.0 -a: throttle = 0.0 -c: vehicle_speed >= 10.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/b22_up.txt b/modules/tools/vehicle_calibration/calibration_data_sample/b22_up.txt deleted file mode 100644 index 5596d7ebafd..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/b22_up.txt +++ /dev/null @@ -1,9 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 22.0 -a: throttle = 0.0 -c: vehicle_speed >= 10.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t15_down.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t15_down.txt deleted file mode 100644 index ce531f9c162..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t15_down.txt +++ /dev/null @@ -1,12 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 60.0 -c: vehicle_speed >= 11.0 -a: throttle = 15.0 -a: brake = 0.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t15b13.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t15b13.txt deleted file mode 100644 index 4e09ec1dcc4..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t15b13.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 15.0 -c: vehicle_speed >= 10.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 13.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t17_down.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t17_down.txt deleted file mode 100644 index bd701db1506..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t17_down.txt +++ /dev/null @@ -1,12 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 60.0 -c: vehicle_speed >= 10.0 -a: throttle = 17.0 -a: brake = 0.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t17b13.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t17b13.txt deleted file mode 100644 index c4567b2cb30..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t17b13.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 17.0 -c: vehicle_speed >= 10.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 13.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t20_down.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t20_down.txt deleted file mode 100644 index 0debd1100e8..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t20_down.txt +++ /dev/null @@ -1,12 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 50.0 -c: vehicle_speed >= 10.4 -a: throttle = 20.0 -a: brake = 0.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t20b13.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t20b13.txt deleted file mode 100644 index f2f1b28759c..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t20b13.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 20.0 -c: vehicle_speed >= 10.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 13.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t22b30.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t22b30.txt deleted file mode 100644 index 1631f704637..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t22b30.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 22.0 -c: vehicle_speed >= 10.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 30.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t25b30.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t25b30.txt deleted file mode 100644 index 4aed6033e84..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t25b30.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 25.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 30.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t27b30.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t27b30.txt deleted file mode 100644 index 683e75a200d..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t27b30.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 27.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 30.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t30b30.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t30b30.txt deleted file mode 100644 index b2f8e9a1e9b..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t30b30.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 30.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 30.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t35b30.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t35b30.txt deleted file mode 100644 index 2f386f7ec76..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t35b30.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 35.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 30.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t40b13.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t40b13.txt deleted file mode 100644 index 06940f84a61..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t40b13.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 40.0 -c: vehicle_speed >= 10.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 13.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t40b15.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t40b15.txt deleted file mode 100644 index b09d26659a5..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t40b15.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 40.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 15.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t40b17.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t40b17.txt deleted file mode 100644 index ae408da8fd6..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t40b17.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 40.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 17.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t40b20.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t40b20.txt deleted file mode 100644 index 9c5f251f82c..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t40b20.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 40.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 20.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t40b22.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t40b22.txt deleted file mode 100644 index 68fbd947bd8..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t40b22.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 40.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 22.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t40b25.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t40b25.txt deleted file mode 100644 index e79367f9cb1..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t40b25.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 40.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 25.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t40b27.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t40b27.txt deleted file mode 100644 index ee96833b172..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t40b27.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 40.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 27.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t40b30.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t40b30.txt deleted file mode 100644 index 808273ae1e4..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t40b30.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 40.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 30.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t40b33.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t40b33.txt deleted file mode 100644 index 96180ed3e05..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t40b33.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 40.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 33.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t40b35.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t40b35.txt deleted file mode 100644 index b72c684a42a..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t40b35.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 40.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 35.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t45b30.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t45b30.txt deleted file mode 100644 index a8e3127293d..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t45b30.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 45.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 30.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t50b30.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t50b30.txt deleted file mode 100644 index 1a4f6c04368..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t50b30.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 50.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 30.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t55b30.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t55b30.txt deleted file mode 100644 index 91eb1ed16d2..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t55b30.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 55.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 30.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t60b30.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t60b30.txt deleted file mode 100644 index fb60d923c5c..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t60b30.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 60.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 30.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t65b30.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t65b30.txt deleted file mode 100644 index 1ff127bb9bd..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t65b30.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 65.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 30.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t70b30.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t70b30.txt deleted file mode 100644 index 2bb7fb2e5e1..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t70b30.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 70.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 30.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t75b30.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t75b30.txt deleted file mode 100644 index 434210d8a9b..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t75b30.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 75.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 30.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/calibration_data_sample/t80b30.txt b/modules/tools/vehicle_calibration/calibration_data_sample/t80b30.txt deleted file mode 100644 index 40dc9822898..00000000000 --- a/modules/tools/vehicle_calibration/calibration_data_sample/t80b30.txt +++ /dev/null @@ -1,13 +0,0 @@ -a: gear_location = chassis_pb2.Chassis.GEAR_DRIVE -a: brake = 40.0 -a: steering_target = 0.0 -a: throttle = 0.0 -c: vehicle_speed == 0.0 -t: 2.0 -a: brake = 0.0 -a: throttle = 80.0 -c: vehicle_speed >= 12.0 -a: throttle = 0.0 -t: 1.0 -a: brake = 30.0 -c: vehicle_speed == 0.0 diff --git a/modules/tools/vehicle_calibration/data_collector.py b/modules/tools/vehicle_calibration/data_collector.py deleted file mode 100644 index 0119696d9e8..00000000000 --- a/modules/tools/vehicle_calibration/data_collector.py +++ /dev/null @@ -1,237 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -Data Collector -""" - -import os -import signal -import sys -import time - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3 import cyber_time -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.control_msgs import control_cmd_pb2 -from modules.common_msgs.localization_msgs import localization_pb2 -from modules.tools.vehicle_calibration.plot_data import Plotter - - -class DataCollector(object): - """ - DataCollector Class - """ - - def __init__(self, node): - self.sequence_num = 0 - self.control_pub = node.create_writer('/apollo/control', - control_cmd_pb2.ControlCommand) - time.sleep(0.3) - self.controlcmd = control_cmd_pb2.ControlCommand() - - self.canmsg_received = False - self.localization_received = False - - self.case = 'a' - self.in_session = False - - self.outfile = "" - - def run(self, cmd): - signal.signal(signal.SIGINT, self.signal_handler) - - self.in_session = True - self.cmd = list(map(float, cmd)) - out = '' - if self.cmd[0] > 0: - out += 't' - else: - out += 'b' - out = out + str(int(self.cmd[0])) - if self.cmd[2] > 0: - out += 't' - else: - out += 'b' - out += str(int(self.cmd[2])) + 'r' - i = 0 - self.outfile = out + str(i) + '_recorded.csv' - while os.path.exists(self.outfile): - i += 1 - self.outfile = out + str(i) + '_recorded.csv' - self.file = open(self.outfile, 'w') - self.file.write( - "time,io,ctlmode,ctlbrake,ctlthrottle,ctlgear_location," + - "vehicle_speed,engine_rpm,driving_mode,throttle_percentage," + - "brake_percentage,gear_location,imu\n" - ) - - print('Send Reset Command.') - self.controlcmd.header.module_name = "control" - self.controlcmd.header.sequence_num = self.sequence_num - self.sequence_num = self.sequence_num + 1 - self.controlcmd.header.timestamp_sec = cyber_time.Time.now().to_sec() - self.controlcmd.pad_msg.action = 2 - self.control_pub.write(self.controlcmd) - - time.sleep(0.2) - # Set Default Message - print('Send Default Command.') - self.controlcmd.pad_msg.action = 1 - self.controlcmd.throttle = 0 - self.controlcmd.brake = 0 - self.controlcmd.steering_rate = 100 - self.controlcmd.steering_target = 0 - self.controlcmd.gear_location = chassis_pb2.Chassis.GEAR_DRIVE - - self.canmsg_received = False - self.case = 'a' - - while self.in_session: - now = cyber_time.Time.now().to_sec() - self.publish_control() - sleep_time = 0.01 - (cyber_time.Time.now().to_sec() - now) - if sleep_time > 0: - time.sleep(sleep_time) - - def signal_handler(self, signal, frame): - self.in_session = False - - def callback_localization(self, data): - """ - New Localization - """ - self.acceleration = data.pose.linear_acceleration_vrf.y - self.localization_received = True - - def callback_canbus(self, data): - """ - New CANBUS - """ - if not self.localization_received: - print('No Localization Message Yet') - return - timenow = data.header.timestamp_sec - self.vehicle_speed = data.speed_mps - self.engine_rpm = data.engine_rpm - self.throttle_percentage = data.throttle_percentage - self.brake_percentage = data.brake_percentage - self.gear_location = data.gear_location - self.driving_mode = data.driving_mode - - self.canmsg_received = True - if self.in_session: - self.write_file(timenow, 0) - - def publish_control(self): - """ - New Control Command - """ - if not self.canmsg_received: - print('No CAN Message Yet') - return - - self.controlcmd.header.sequence_num = self.sequence_num - self.sequence_num += 1 - - if self.case == 'a': - if self.cmd[0] > 0: - self.controlcmd.throttle = self.cmd[0] - self.controlcmd.brake = 0 - else: - self.controlcmd.throttle = 0 - self.controlcmd.brake = -self.cmd[0] - if self.vehicle_speed >= self.cmd[1]: - self.case = 'd' - elif self.case == 'd': - if self.cmd[2] > 0: - self.controlcmd.throttle = self.cmd[0] - self.controlcmd.brake = 0 - else: - self.controlcmd.throttle = 0 - self.controlcmd.brake = -self.cmd[2] - if self.vehicle_speed == 0: - self.in_session = False - - self.controlcmd.header.timestamp_sec = cyber_time.Time.now().to_sec() - self.control_pub.write(self.controlcmd) - self.write_file(self.controlcmd.header.timestamp_sec, 1) - if self.in_session == False: - self.file.close() - - def write_file(self, time, io): - """ - Write Message to File - """ - self.file.write( - "%.4f,%s,%s,%s,%s,%s,%s,%s,%s,%s,%s,%s,%s\n" % - (time, io, 1, self.controlcmd.brake, self.controlcmd.throttle, - self.controlcmd.gear_location, self.vehicle_speed, self.engine_rpm, - self.driving_mode, self.throttle_percentage, self.brake_percentage, - self.gear_location, self.acceleration)) - - -def main(): - """ - Main function - """ - node = cyber.Node("data_collector") - - data_collector = DataCollector(node) - plotter = Plotter() - node.create_reader('/apollo/localization/pose', - localization_pb2.LocalizationEstimate, - data_collector.callback_localization) - node.create_reader('/apollo/canbus/chassis', chassis_pb2.Chassis, - data_collector.callback_canbus) - - print('Enter q to quit.') - print('Enter p to plot result from last run.') - print('Enter x to remove result from last run.') - print('Enter x y z, where x is acceleration command, ' + - 'y is speed limit, z is decceleration command.') - print('Positive number for throttle and negative number for brake.') - - while True: - cmd = input("Enter commands: ").split() - if len(cmd) == 0: - print('Quiting.') - break - elif len(cmd) == 1: - if cmd[0] == "q": - break - elif cmd[0] == "p": - print('Plotting result.') - if os.path.exists(data_collector.outfile): - plotter.process_data(data_collector.outfile) - plotter.plot_result() - else: - print('File does not exist: %s' % data_collector.outfile) - elif cmd[0] == "x": - print('Removing last result.') - if os.path.exists(data_collector.outfile): - os.remove(data_collector.outfile) - else: - print('File does not exist: %s' % date_collector.outfile) - elif len(cmd) == 3: - data_collector.run(cmd) - - -if __name__ == '__main__': - cyber.init() - main() - cyber.shutdown() diff --git a/modules/tools/vehicle_calibration/plot_data.py b/modules/tools/vehicle_calibration/plot_data.py deleted file mode 100644 index 00ee8a2d499..00000000000 --- a/modules/tools/vehicle_calibration/plot_data.py +++ /dev/null @@ -1,142 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -This module provide function to plot the speed control info from log csv file -""" - -import sys - -import matplotlib.pyplot as plt -import numpy as np -import tkinter.filedialog - -from modules.tools.vehicle_calibration.process import get_start_index -from modules.tools.vehicle_calibration.process import preprocess -from modules.tools.vehicle_calibration.process import process - - -class Plotter(object): - """ - Plot the speed info - """ - - def __init__(self): - """ - Init the speed info - """ - np.set_printoptions(precision=3) - self.file = open('temp_result.csv', 'a') - - def process_data(self, filename): - """ - Load the file and preprocess th data - """ - self.data = preprocess(filename) - - self.tablecmd, self.tablespeed, self.tableacc, self.speedsection, self.accsection, self.timesection = process( - self.data) - - def plot_result(self): - """ - Plot the desired data - """ - fig, axarr = plt.subplots(2, 1, sharex=True) - plt.tight_layout() - fig.subplots_adjust(hspace=0) - - axarr[0].plot( - self.data['time'], self.data['ctlbrake'], label='Brake CMD') - axarr[0].plot( - self.data['time'], - self.data['brake_percentage'], - label='Brake Output') - axarr[0].plot( - self.data['time'], self.data['ctlthrottle'], label='Throttle CMD') - axarr[0].plot( - self.data['time'], - self.data['throttle_percentage'], - label='Throttle Output') - axarr[0].plot( - self.data['time'], - self.data['engine_rpm'] / 100, - label='Engine RPM') - axarr[0].legend(fontsize='medium') - axarr[0].grid(True) - axarr[0].set_title('Command') - - axarr[1].plot( - self.data['time'], - self.data['vehicle_speed'], - label='Vehicle Speed') - - for i in range(len(self.timesection)): - axarr[1].plot( - self.timesection[i], - self.speedsection[i], - label='Speed Segment') - axarr[1].plot( - self.timesection[i], self.accsection[i], label='IMU Segment') - - axarr[1].legend(fontsize='medium') - axarr[1].grid(True) - axarr[1].set_title('Speed') - - mng = plt.get_current_fig_manager() - mng.full_screen_toggle() - - # plt.tight_layout(pad=0.20) - fig.canvas.mpl_connect('key_press_event', self.press) - plt.show() - - def press(self, event): - """ - Keyboard events during plotting - """ - if event.key == 'q' or event.key == 'Q': - self.file.close() - plt.close() - - if event.key == 'w' or event.key == 'W': - for i in range(len(self.tablecmd)): - for j in range(len(self.tablespeed[i])): - self.file.write("%s, %s, %s\n" % - (self.tablecmd[i], self.tablespeed[i][j], - self.tableacc[i][j])) - print("Finished writing results") - - -def main(): - """ - demo - """ - if len(sys.argv) == 2: - # Get the latest file - file_path = sys.argv[1] - else: - file_path = tkinter.filedialog.askopenfilename( - initialdir="/home/caros/.ros", - filetypes=(("csv files", ".csv"), ("all files", "*.*"))) - print('File path: %s' % file_path) - plotter = Plotter() - plotter.process_data(file_path) - print('Finished reading the file.') - plotter.plot_result() - - -if __name__ == '__main__': - main() diff --git a/modules/tools/vehicle_calibration/plot_grid.py b/modules/tools/vehicle_calibration/plot_grid.py deleted file mode 100644 index d7cbebd8bf5..00000000000 --- a/modules/tools/vehicle_calibration/plot_grid.py +++ /dev/null @@ -1,65 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import math -import sys - -import matplotlib.pyplot as plt -import numpy as np -from matplotlib import cm as cmx -from matplotlib import colors as mcolors - -markers = [ - "o", "v", "^", "<", ">", "1", "2", "3", "4", "8", "s", "p", "*", "+", "x", - "d", "|", "_" -] - -if len(sys.argv) < 2: - print('Usage: %s result.csv' % sys.argv[0]) - sys.exit(0) - -fn = sys.argv[1] - -speed_table = {} -with open(fn, 'r') as f: - for line in f: - items = line.split(',') - cmd = round(float(items[0])) - speed = float(items[1]) - acc = round(float(items[2]), 2) - if speed in speed_table: - cmd_table = speed_table[speed] - if cmd in cmd_table: - cmd_table[cmd].append(acc) - else: - cmd_table[cmd] = [acc] - else: - cmd_table = {} - cmd_table[cmd] = [acc] - speed_table[speed] = cmd_table - -for speed in speed_table: - cmd_dict = speed_table[speed] - speed_list = [] - acc_list = [] - for cmd in cmd_dict: - for acc in cmd_dict[cmd]: - speed_list.append(speed) - acc_list.append(acc) - plt.plot(speed_list, acc_list, 'b.') -plt.show() diff --git a/modules/tools/vehicle_calibration/plot_results.py b/modules/tools/vehicle_calibration/plot_results.py deleted file mode 100644 index e883159a26b..00000000000 --- a/modules/tools/vehicle_calibration/plot_results.py +++ /dev/null @@ -1,93 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import math -import sys - -import matplotlib.pyplot as plt -import numpy as np -from matplotlib import cm as cmx -from matplotlib import colors as mcolors - -markers = [ - "o", "v", "^", "<", ">", "1", "2", "3", "4", "8", "s", "p", "*", "+", "x", - "d", "|", "_" -] - -if len(sys.argv) < 2: - print("Usage: python plot_results.py result.csv") - sys.exit(0) - -with open(sys.argv[1], 'r') as f: - cmd_table = {} - - for line in f: - items = line.split(',') - cmd = round(float(items[0])) - speed = float(items[1]) - acc = float(items[2]) - if cmd in cmd_table: - speed_table = cmd_table[cmd] - if speed in speed_table: - speed_table[speed].append(acc) - else: - speed_table[speed] = [acc] - else: - speed_table = {} - speed_table[speed] = [acc] - cmd_table[cmd] = speed_table - -NCURVES = len(cmd_table) -np.random.seed(101) -curves = [np.random.random(20) for i in range(NCURVES)] -values = list(range(NCURVES)) -jet = cm = plt.get_cmap('brg') -cNorm = mcolors.Normalize(vmin=0, vmax=values[-1]) -scalarMap = cmx.ScalarMappable(norm=cNorm, cmap=jet) - -cnt = 0 -cmds = list(cmd_table.keys()) -cmds.sort() - -fig, ax = plt.subplots() -for cmd in cmds: - print('ctrl cmd = %s' % cmd) - speed_table = cmd_table[cmd] - X = [] - Y = [] - speeds = list(speed_table.keys()) - speeds.sort() - for speed in speeds: - X.append(speed) - Y.append(np.mean(speed_table[speed])) - colorVal = scalarMap.to_rgba(values[cnt]) - ax.plot( - X, - Y, - c=colorVal, - linestyle=':', - marker=markers[cnt % len(markers)], - label="cmd=" + str(cmd)) - cnt += 1 - -ax.legend(loc='upper center', shadow=True, bbox_to_anchor=(0.5, 1.1), ncol=5) - -plt.ylabel("acc") -plt.xlabel("speed") -plt.grid() -plt.show() diff --git a/modules/tools/vehicle_calibration/preprocess.py b/modules/tools/vehicle_calibration/preprocess.py deleted file mode 100755 index b0b80838d88..00000000000 --- a/modules/tools/vehicle_calibration/preprocess.py +++ /dev/null @@ -1,178 +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. -############################################################################### -""" -This module provides the preprocessing function of vehicle calibration data -""" -import os -import re -import shutil -import time - -from absl import app -from absl import flags -from absl import logging -from datetime import datetime - -from cyber.python.cyber_py3 import cyber -from modules.dreamview.proto import preprocess_table_pb2 -from modules.tools.vehicle_calibration.sanity_check import sanity_check - -flags.DEFINE_string('vehicle_type', '', 'The vehicle type to be calibrated') -flags.DEFINE_string('data_path', '/apollo/output', 'Default output data path') -flags.DEFINE_string('calibration_data_path', - '/apollo/modules/calibration/data', - 'Default vehicle configuration file directory') -flags.DEFINE_string('config_file_name', 'vehicle_param.pb.txt', - 'Default vehicle configuration file name') -flags.DEFINE_string('record_root_path', '/apollo/data/bag', - 'Default record root path') -flags.DEFINE_integer( - 'record_num', 1, 'The number of record folders ' - 'required for this calibration task') - -FLAGS = flags.FLAGS - - -def main(argv): - cyber.init("Preprocessor") - preprocessor = Preprocessor() - task_dir = preprocessor.create_tree() - preprocessor.sanity_check_path(task_dir) - cyber.shutdown() - - -class Preprocessor(object): - def __init__(self): - self.record_num = FLAGS.record_num - self.vehicle_type = self.folder_case(FLAGS.vehicle_type) - self.config_file = self.get_config_path() - self.node = cyber.Node("vehicle_calibration_preprocessor") - self.writer = self.node.create_writer("/apollo/dreamview/progress", - preprocess_table_pb2.Progress, - 10) - self.progress = preprocess_table_pb2.Progress() - self.progress.percentage = 0.0 - self.progress.log_string = "Press the button to start preprocessing" - - @staticmethod - def folder_case(str): - """Convert a string from title case to folder case""" - return "_".join(str.lower().split(" ")) - - def create_if_not_exists(self, path): - """Create dir if path does not exists""" - try: - if not os.path.exists(path): - os.makedirs(path) - self.log_and_publish(f'Sucessfully created {path}') - except OSError: - self.log_and_publish(f'Failed to create: {path}', 'error') - - return path - - def get_config_path(self): - """Get the configuration file of the specified vehicle type""" - return os.path.join(FLAGS.calibration_data_path, self.vehicle_type, - FLAGS.config_file_name) - - def get_records_info(self): - """Get records required for calibration""" - res = [] - for dir in os.listdir(FLAGS.record_root_path): - match = re.match(r'(^\d{4}-\d{2}-\d{2})-(\d{2}-\d{2}-\d{2}_s$)', - dir) - if match is not None: - record_info = {} - record_info['rel_path'] = match.group() - record_info['abs_path'] = os.path.join(FLAGS.record_root_path, - match.group()) - record_info['prefix'] = match.group(1) - res.append(record_info) - if len(res) < self.record_num: - self.log_and_publish( - f'The number of records in {FLAGS.record_root_path} ' - f'is less than {self.record_num}', 'error') - - res = sorted(res, key=lambda record: record['rel_path'], - reverse=True)[:self.record_num] - return res - - def log_and_publish(self, - str, - logging_level="info", - status=preprocess_table_pb2.Status.UNKNOWN): - """Publish the str by cyber writer""" - if logging_level == 'info': - logging.info(str) - elif logging_level == 'warn': - logging.warn(str) - elif logging_level == 'error': - logging.error(str) - elif logging_level == 'fatal': - logging.fatal(str) - else: - logging.info(str) - - self.progress.log_string = str - self.progress.status = status - self.writer.write(self.progress) - time.sleep(0.5) - - def create_tree(self): - """Create file tree according to a specific order""" - task_dir = self.create_if_not_exists( - os.path.join(FLAGS.data_path, - 'task' + datetime.now().strftime("-%Y-%m-%d-%H-%M"))) - vehicle_dir = self.create_if_not_exists( - os.path.join(task_dir, self.vehicle_type)) - records_dir = self.create_if_not_exists( - os.path.join(vehicle_dir, "Records")) - shutil.copy(self.config_file, vehicle_dir) - records_info = self.get_records_info() - finished_records = 0 - self.progress.log_string = 'Start preprocessing...' - - for iter in records_info: - sub_dir = self.create_if_not_exists( - os.path.join(records_dir, iter['prefix'])) - shutil.copytree(iter['abs_path'], - os.path.join(sub_dir, iter['rel_path'])) - finished_records += 1 - self.progress.percentage = ( - finished_records / self.record_num) * 80.0 - self.writer.write(self.progress) - - self.log_and_publish( - f'The file tree has been successfully created at {task_dir}.') - return task_dir - - def sanity_check_path(self, path): - """Sanity check wrapper""" - result, log_str = sanity_check(path) - if result is True: - self.progress.percentage = 100.0 - self.progress.status = preprocess_table_pb2.Status.SUCCESS - else: - self.progress.status = preprocess_table_pb2.Status.FAIL - self.progress.log_string = log_str - self.writer.write(self.progress) - time.sleep(0.5) - - -if __name__ == "__main__": - app.run(main) diff --git a/modules/tools/vehicle_calibration/preprocess.sh b/modules/tools/vehicle_calibration/preprocess.sh deleted file mode 100755 index b3b73e21205..00000000000 --- a/modules/tools/vehicle_calibration/preprocess.sh +++ /dev/null @@ -1,30 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# 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. -############################################################################### - -TOP_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")/../../.." && pwd -P)" - -PREPROCESS_BIN=/opt/apollo/neo/packages/tools-dev/latest/vehicle_calibration/preprocess -if [[ ! -f "${PREPROCESS_BIN}" ]]; then - PREPROCESS_BIN=${TOP_DIR}/bazel-bin/modules/tools/vehicle_calibration/preprocess -fi - -if [[ -f "${PREPROCESS_BIN}" ]]; then - "${PREPROCESS_BIN}" "$@" -else - bazel run //modules/tools/vehicle_calibration:preprocess -- "$@" -fi diff --git a/modules/tools/vehicle_calibration/process.py b/modules/tools/vehicle_calibration/process.py deleted file mode 100644 index f7acbff9ef6..00000000000 --- a/modules/tools/vehicle_calibration/process.py +++ /dev/null @@ -1,177 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -This module provide function to plot the speed control info from log csv file -""" - -import math -import warnings - -import numpy as np -import scipy.signal as signal - - -warnings.simplefilter('ignore', np.RankWarning) - -SPEED_INTERVAL = 0.2 -SPEED_DELAY = 130 # Speed report delay relative to IMU information - - -def preprocess(filename): - data = np.genfromtxt(filename, delimiter=',', names=True) - data = data[np.where(data['io'] == 0)[0]] - data = data[np.argsort(data['time'])] - data['time'] = data['time'] - data['time'][get_start_index(data)] - - b, a = signal.butter(6, 0.05, 'low') - data['imu'] = signal.filtfilt(b, a, data['imu']) - - data['imu'] = np.append(data['imu'][-SPEED_DELAY // 10:], - data['imu'][0:-SPEED_DELAY // 10]) - return data - - -def get_start_index(data): - if np.all(data['vehicle_speed'] == 0): - return 0 - - start_ind = np.where(data['brake_percentage'] == 40) - - if len(start_ind[0] > 0): - ind = start_ind[0][0] - while ind < len(data): - if data['brake_percentage'][ind] == 40: - ind += 1 - else: - break - return ind - else: - ind = 0 - while ind < len(data): - if abs(data['vehicle_speed'][ind]) < 0.01: - ind += 1 - else: - break - return ind - - -def process(data): - """ - process data - """ - np.set_printoptions(precision=3) - - if np.all(data['vehicle_speed'] == 0): - print("All Speed = 0") - return [], [], [], [], [], [] - - start_index = get_start_index(data) - - # print "Start index: ", start_index - data = data[start_index:] - data['time'] = data['time'] - data['time'][0] - - transition = np.where( - np.logical_or( - np.diff(data['ctlbrake']) != 0, np.diff(data['ctlthrottle']) != 0))[ - 0] - transition = np.insert(np.append(transition, len(data) - 1), 0, 0) - # print "Transition indexes: ", transition - - speedsegments = [] - timesegments = [] - accsegments = [] - tablespeed = [] - tableacc = [] - tablecmd = [] - - for i in range(len(transition) - 1): - # print "process transition index:", data['time'][transition[i]], ":", data['time'][transition[i + 1]] - speedsection = data['vehicle_speed'][transition[i]:transition[i + - 1] + 1] - timesection = data['time'][transition[i]:transition[i + 1] + 1] - brake = data['ctlbrake'][transition[i] + 1] - throttle = data['ctlthrottle'][transition[i] + 1] - imusection = data['imu'][transition[i]:transition[i + 1] + 1] - if brake == 0 and throttle == 0: - continue - # print "Brake CMD: ", brake, " Throttle CMD: ", throttle - firstindex = 0 - - while speedsection[firstindex] == 0: - firstindex += 1 - firstindex = max(firstindex - 2, 0) - speedsection = speedsection[firstindex:] - timesection = timesection[firstindex:] - imusection = imusection[firstindex:] - - if speedsection[0] < speedsection[-1]: - is_increase = True - lastindex = np.argmax(speedsection) - else: - is_increase = False - lastindex = np.argmin(speedsection) - - speedsection = speedsection[0:lastindex + 1] - timesection = timesection[0:lastindex + 1] - imusection = imusection[0:lastindex + 1] - - speedmin = np.min(speedsection) - speedmax = np.max(speedsection) - speedrange = np.arange( - max(0, round(speedmin / SPEED_INTERVAL) * SPEED_INTERVAL), - min(speedmax, 10.01), SPEED_INTERVAL) - # print "Speed min, max", speedmin, speedmax, is_increase, firstindex, lastindex, speedsection[-1] - accvalue = [] - for value in speedrange: - val_ind = 0 - if is_increase: - while val_ind < len( - speedsection) - 1 and value > speedsection[val_ind]: - val_ind += 1 - else: - while val_ind < len( - speedsection) - 1 and value < speedsection[val_ind]: - val_ind += 1 - if val_ind == 0: - imu_value = imusection[val_ind] - else: - slope = (imusection[val_ind] - imusection[val_ind - 1]) / ( - speedsection[val_ind] - speedsection[val_ind - 1]) - imu_value = imusection[val_ind - 1] + slope * ( - value - speedsection[val_ind - 1]) - accvalue.append(imu_value) - - if brake == 0: - cmd = throttle - else: - cmd = -brake - # print "Overall CMD: ", cmd - # print "Time: ", timesection - # print "Speed: ", speedrange - # print "Acc: ", accvalue - # print cmd - tablecmd.append(cmd) - tablespeed.append(speedrange) - tableacc.append(accvalue) - - speedsegments.append(speedsection) - accsegments.append(imusection) - timesegments.append(timesection) - - return tablecmd, tablespeed, tableacc, speedsegments, accsegments, timesegments diff --git a/modules/tools/vehicle_calibration/process_data.py b/modules/tools/vehicle_calibration/process_data.py deleted file mode 100644 index 2f87d6b4a98..00000000000 --- a/modules/tools/vehicle_calibration/process_data.py +++ /dev/null @@ -1,89 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### -""" -This module provide function to plot the speed control info from log csv file -""" - -import math -import sys - -import numpy as np -import tkinter.filedialog - -from modules.tools.vehicle_calibration.process import get_start_index -from modules.tools.vehicle_calibration.process import preprocess -from modules.tools.vehicle_calibration.process import process - - -class Plotter(object): - """ - plot the speed info - """ - - def __init__(self, filename): - """ - init the speed info - """ - - np.set_printoptions(precision=3) - self.file = open('result.csv', 'a') - self.file_one = open(filename + ".result", 'w') - - def process_data(self, filename): - """ - load the file and preprocess th data - """ - - self.data = preprocess(filename) - - self.tablecmd, self.tablespeed, self.tableacc, self.speedsection, self.accsection, self.timesection = process( - self.data) - - def save_data(self): - """ - save_data - """ - for i in range(len(self.tablecmd)): - for j in range(len(self.tablespeed[i])): - self.file.write("%s, %s, %s\n" % - (self.tablecmd[i], self.tablespeed[i][j], - self.tableacc[i][j])) - self.file_one.write("%s, %s, %s\n" % - (self.tablecmd[i], self.tablespeed[i][j], - self.tableacc[i][j])) - - -def main(): - """ - demo - """ - if len(sys.argv) == 2: - # get the latest file - file_path = sys.argv[1] - else: - file_path = tkinter.filedialog.askopenfilename( - initialdir="/home/caros/.ros", - filetypes=(("csv files", ".csv"), ("all files", "*.*"))) - plotter = Plotter(file_path) - plotter.process_data(file_path) - plotter.save_data() - print('save result to:', file_path + ".result") - - -if __name__ == '__main__': - main() diff --git a/modules/tools/vehicle_calibration/process_data.sh b/modules/tools/vehicle_calibration/process_data.sh deleted file mode 100755 index 6e06f1e1027..00000000000 --- a/modules/tools/vehicle_calibration/process_data.sh +++ /dev/null @@ -1,25 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" -rm $DIR/result.csv -for f in `ls ${1}/*_recorded.csv` -do - echo "Processing $f" - python -W ignore $DIR/process_data.py $f -done diff --git a/modules/tools/vehicle_calibration/result2pb.py b/modules/tools/vehicle_calibration/result2pb.py deleted file mode 100644 index ab8245352ac..00000000000 --- a/modules/tools/vehicle_calibration/result2pb.py +++ /dev/null @@ -1,120 +0,0 @@ -#!/usr/bin/env python3 - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -import sys - -import numpy as np - -import modules.tools.common.proto_utils as proto_utils -from modules.control.proto import calibration_table_pb2 -from modules.control.proto.control_conf_pb2 import ControlConf - - -def load_calibration_raw_data(fn): - speed_table = {} - with open(fn, 'r') as f: - for line in f: - items = line.split(',') - cmd = round(float(items[0])) - speed = float(items[1]) - acc = round(float(items[2]), 2) - if speed in speed_table: - cmd_table = speed_table[speed] - if cmd in cmd_table: - cmd_table[cmd].append(acc) - else: - cmd_table[cmd] = [acc] - else: - cmd_table = {} - cmd_table[cmd] = [acc] - speed_table[speed] = cmd_table - - for speed in speed_table: - cmd_table = speed_table[speed] - for cmd in cmd_table: - cmd_table[cmd] = round(np.mean(cmd_table[cmd]), 2) - # After this the acc_list converted to an average float number. - - speed_table2 = {} - for speed in speed_table: - cmd_table = speed_table[speed] - acc_table = {} - for cmd in cmd_table: - acc = cmd_table[cmd] - if acc in acc_table: - acc_table[acc].append(cmd) - else: - acc_table[acc] = [cmd] - speed_table2[speed] = acc_table - - return speed_table2 - - -def load_calibration_raw_data_old(fn): - speed_table = {} - with open(fn, 'r') as f: - for line in f: - items = line.split(',') - cmd = round(float(items[0])) - speed = float(items[1]) - acc = round(float(items[2]), 2) - if speed in speed_table: - acc_table = speed_table[speed] - if acc in acc_table: - acc_table[acc].append(cmd) - else: - acc_table[acc] = [cmd] - else: - acc_table = {} - acc_table[acc] = [cmd] - speed_table[speed] = acc_table - - return speed_table - - -def get_calibration_table_pb(speed_table): - calibration_table_pb = calibration_table_pb2.ControlCalibrationTable() - speeds = list(speed_table.keys()) - speeds.sort() - for speed in speeds: - acc_table = speed_table[speed] - accs = list(acc_table.keys()) - accs.sort() - for acc in accs: - cmds = acc_table[acc] - cmd = np.mean(cmds) - item = calibration_table_pb.calibration.add() - item.speed = speed - item.acceleration = acc - item.command = cmd - return calibration_table_pb - - -if __name__ == '__main__': - if len(sys.argv) != 3: - print("Usage: %s old_control_conf.pb.txt result.csv" % sys.argv[0]) - sys.exit(0) - - ctl_conf_pb = proto_utils.get_pb_from_text_file(sys.argv[1], ControlConf()) - speed_table_dict = load_calibration_raw_data(sys.argv[2]) - calibration_table_pb = get_calibration_table_pb(speed_table_dict) - ctl_conf_pb.lon_controller_conf.calibration_table.CopyFrom( - calibration_table_pb) - - with open('control_conf.pb.txt', 'w') as f: - f.write(str(ctl_conf_pb)) diff --git a/modules/tools/vehicle_calibration/result2pb.sh b/modules/tools/vehicle_calibration/result2pb.sh deleted file mode 100755 index 6fb809f4ad0..00000000000 --- a/modules/tools/vehicle_calibration/result2pb.sh +++ /dev/null @@ -1,27 +0,0 @@ -#!/usr/bin/env bash - -############################################################################### -# Copyright 2017 The Apollo Authors. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -############################################################################### - -TOP_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")/../../.." && pwd -P)" -if [[ -f "/opt/apollo/neo/packages/tools-dev/latest/vehicle_calibration/result2pb" ]]; then - /opt/apollo/neo/packages/tools-dev/latest/vehicle_calibration/result2pb /opt/apollo/neo/packages/control-dev/latest/conf/control_conf.pb.txt $1 -else - ${TOP_DIR}/bazel-bin/modules/tools/vehicle_calibration/result2pb ${TOP_DIR}/modules/control/conf/control_conf.pb.txt $1 -fi - -echo "Created control conf file: control_conf_pb.txt" - diff --git a/modules/tools/vehicle_calibration/sanity_check.py b/modules/tools/vehicle_calibration/sanity_check.py deleted file mode 100644 index 9b1d60bc28c..00000000000 --- a/modules/tools/vehicle_calibration/sanity_check.py +++ /dev/null @@ -1,184 +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. -############################################################################### -""" -This is a tool to sanity check the vechicle calibration files -""" -import fnmatch -import math -import os -import google.protobuf.text_format as text_format -from absl import logging - -from cyber.python.cyber_py3.record import RecordReader -import modules.common_msgs.config_msgs.vehicle_config_pb2 as vehicle_config_pb2 -import modules.tools.common.proto_utils as proto_utils -import modules.tools.common.file_utils as file_utils - -# could be a list -ConfFile = 'vehicle_param.pb.txt' -CHASSIS_CHANNEL = '/apollo/canbus/chassis' -LOCALIZATION_CHANNEL = '/apollo/localization/pose' -CHANNELS = {CHASSIS_CHANNEL, LOCALIZATION_CHANNEL} - - -def is_record_file(path): - """Naive check if a path is a record.""" - return path.endswith('.record') or fnmatch.fnmatch(path, '*.record.?????') - - -def get_vehicle(path): - return [ - subdir for subdir in os.listdir(path) - if os.path.isdir(os.path.join(path, subdir)) - ] - - -def missing_input_path(path): - input_size = file_utils.getInputDirDataSize(path) - if input_size == 0: - return True - return False - - -def list_records(path): - logging.info("in list_records:%s" % path) - records = [] - for (dirpath, _, filenames) in os.walk(path): - logging.info('filenames: %s' % filenames) - logging.info('dirpath %s' % dirpath) - for filename in filenames: - end_file = os.path.join(dirpath, filename) - logging.info("end_files: %s" % end_file) - if is_record_file(end_file): - records.append(end_file) - return records - - -def missing_file(path): - vehicles = get_vehicle(path) - logging.info(f'vehicles {vehicles}') - result = [] - for vehicle in vehicles: - # config file - conf = os.path.join(path, vehicle, ConfFile) - logging.info(f'vehicles conf {conf}') - if not os.path.exists(conf): - logging.error(f'Missing configuration file in {vehicle}') - result.append(ConfFile) - # record file - logging.info("list of records:" % - list_records(os.path.join(path, vehicle))) - if len(list_records(os.path.join(path, vehicle))) == 0: - logging.error(f'No record files in {vehicle}') - result.append('record') - if len(result): - return True, result - return False, [] - - -def parse_error(path): - vehicles = get_vehicle(path) - pb_value = vehicle_config_pb2.VehicleConfig() - for vehicle in vehicles: - conf = os.path.join(path, vehicle, ConfFile) - try: - proto_utils.get_pb_from_text_file(conf, pb_value) - return False - except text_format.ParseError: - logging.error( - f'Error: Cannot parse {conf} as binary or text proto') - return True - - -def check_vehicle_id(conf): - # print(conf.HasField('vehicle_id.other_unique_id')) - vehicle_id = conf.vehicle_param.vehicle_id - if vehicle_id.vin or vehicle_id.plate or vehicle_id.other_unique_id: - return True - logging.error('Error: No vehicle ID') - return False - - -def missing_field(path): - vehicles = get_vehicle(path) - logging.info(f'vehicles in missing field: {vehicles}') - result = [] - for vehicle in vehicles: - conf_file = os.path.join(path, vehicle, ConfFile) - logging.info(f'conf_file: {conf_file}') - # reset for each vehicle to avoid overwrited - pb_value = vehicle_config_pb2.VehicleConfig() - conf = proto_utils.get_pb_from_text_file(conf_file, pb_value) - logging.info(f'vehicles conf {conf}') - if not check_vehicle_id(conf): - result.append("vehicle_id") - # required field - fields = [ - conf.vehicle_param.brake_deadzone, - conf.vehicle_param.throttle_deadzone, - conf.vehicle_param.max_acceleration, - conf.vehicle_param.max_deceleration - ] - # for value in conf.vehicle_param: - # has field is always true since a default value is given - for field in fields: - if math.isnan(field): - result.append(field) - if len(result): - return True, result - return False, result - - -def missing_message_data(path, channels=CHANNELS): - result = [] - for record in list_records(path): - logging.info(f'reading records {record}') - reader = RecordReader(record) - for channel in channels: - logging.info(f'has {reader.get_messagenumber(channel)} messages') - if reader.get_messagenumber(channel) == 0: - result.append(record) - if len(result): - return True, result - return False, [] - - -def sanity_check(input_folder): - err_msg = None - path_flag = missing_input_path(input_folder) - field_flag, field_result = missing_field(input_folder) - channel_flag, channel_result = missing_message_data(input_folder) - file_flag, file_result = missing_file(input_folder) - if path_flag: - err_msg = f'Input path {input_folder} folder structure is wrong' - if file_flag: - err_msg = f'One or more files are missing in {input_folder}' - elif parse_error(input_folder): - err_msg = f'Config file cannot be parsed in {input_folder}' - elif field_flag: - err_msg = f'One or more fields are missing in {input_folder}' - elif channel_flag: - err_msg = ( - 'Messages are missing in records channels apollo/chassis or ' - f'apollo/localization/pose, records are {channel_result}') - else: - info_msg = f'{input_folder} Passed sanity check.' - logging.info(info_msg) - return True, info_msg - logging.error(err_msg) - return False, err_msg diff --git a/modules/tools/vehicle_profile/BUILD b/modules/tools/vehicle_profile/BUILD deleted file mode 100644 index 94ec1e9bbbb..00000000000 --- a/modules/tools/vehicle_profile/BUILD +++ /dev/null @@ -1,23 +0,0 @@ -load("@rules_python//python:defs.bzl", "py_binary") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -py_binary( - name = "vehicle_profile", - srcs = ["vehicle_profile.py"], - deps = [ - "//cyber/python/cyber_py3:cyber", - "//cyber/python/cyber_py3:record", - "//modules/common_msgs/chassis_msgs:chassis_py_pb2", - "//modules/common_msgs/control_msgs:control_cmd_py_pb2", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - "//modules/common_msgs/planning_msgs:planning_py_pb2", - ], -) - -install( - name = "install", - py_dest = "tools/vehicle_profile", - targets = [":vehicle_profile"], -) diff --git a/modules/tools/vehicle_profile/vehicle_profile.py b/modules/tools/vehicle_profile/vehicle_profile.py deleted file mode 100644 index 97c8341757c..00000000000 --- a/modules/tools/vehicle_profile/vehicle_profile.py +++ /dev/null @@ -1,936 +0,0 @@ -#!/usr/bin/env python -# -*- coding:UTF-8 -*- -############################################################################### -# Copyright 2023 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. -############################################################################### -""" -Control Planning Analyzer -""" -import argparse -import os -import math -import sys -import threading -import time -import matplotlib -import matplotlib.pyplot as plt -import numpy -import fnmatch -# import xlrd -import xlsxwriter - -from matplotlib import patches -from matplotlib import lines - -from cyber.python.cyber_py3 import cyber -from cyber.python.cyber_py3.record import RecordReader - -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.control_msgs import control_cmd_pb2 -from modules.common_msgs.localization_msgs import localization_pb2 -from modules.common_msgs.chassis_msgs import chassis_pb2 -from modules.common_msgs.planning_msgs import planning_pb2 -from modules.common_msgs.control_msgs import control_cmd_pb2 - -import importlib - -importlib.reload(sys) - - -class ControlInfo(object): - """ - ControlInfo Class - """ - - def __init__(self, axarr, t=False): - - self.controltime = [] - self.canbustime = [] - # front and back information - self.station_reference = [] - self.current_station = [] - self.station_error = [] - # speed information - self.canbus_speed = [] - self.speed_reference = [] - self.current_speed = [] - self.speed_error = [] - # left and right information - self.lateral_error = [] - # heading information - self.ref_heading = [] - self.heading = [] - self.heading_error = [] - self.driving_mode = 0 - self.mode_time = [] - self.target_time = [] - self.axarr = axarr - self.print_traj = False - self.planningavailable = False - self.lock = threading.Lock() - self.carx = [] - self.cary = [] - self.cartime = [] - self.pathx = [] - self.pathy = [] - self.planningx = [] - self.planningy = [] - self.i = 0 - self.score_num = 0 - - def callback_planning(self, entity): - """ - New Planning Trajectory - """ - basetime = entity.header.timestamp_sec - self.pathx = [p.path_point.x for p in entity.trajectory_point] - self.pathy = [p.path_point.y for p in entity.trajectory_point] - if self.i < 40: - self.planningx = self.pathx - self.planningy = self.pathy - - self.i += 1 - numpoints = len(entity.trajectory_point) - if numpoints == 0: - self.planningavailable = False - else: - self.planningavailable = True - - def callback_control(self, entity): - """ - New Control Command - """ - self.controltime.append(entity.header.timestamp_sec) - #evaluation of front and back distance - self.station_reference.append( - entity.debug.simple_lon_debug.station_reference) - self.current_station.append( - entity.debug.simple_lon_debug.current_station) - self.station_error.append(entity.debug.simple_lon_debug.station_error) - - #evaluation of speed - self.speed_reference.append( - entity.debug.simple_lon_debug.speed_reference) - #print"speed_reference is \n", self.speed_reference - self.current_speed.append( - entity.debug.simple_lon_debug.speed_reference - - entity.debug.simple_lon_debug.speed_error) - #print"current_speed is \n", self.current_speed - self.speed_error.append(entity.debug.simple_lon_debug.speed_error) - #evaluation of left and right - self.lateral_error.append(entity.debug.simple_lat_debug.lateral_error) - #evaluation of heading error - self.ref_heading.append(entity.debug.simple_lat_debug.ref_heading) - self.heading.append(entity.debug.simple_lat_debug.heading) - self.heading_error.append(entity.debug.simple_lat_debug.heading_error) - with self.lock: - if self.planningavailable: - self.target_time.append(entity.header.timestamp_sec) - - def callback_canbus(self, entity): - """ - New Canbus - """ - self.canbus_speed.append(entity.speed_mps) - self.canbustime.append(entity.header.timestamp_sec) - - if entity.driving_mode == chassis_pb2.Chassis.COMPLETE_AUTO_DRIVE: - if self.driving_mode == 0: - self.mode_time.append(entity.header.timestamp_sec) - self.driving_mode = 1 - elif self.driving_mode == 1: - self.mode_time.append(entity.header.timestamp_sec) - self.driving_mode = 0 - - def callback_localization(self, entity): - """ - New localization pose - """ - self.carx.append(entity.pose.position.x) - self.cary.append(entity.pose.position.y) - self.cartime.append(entity.header.timestamp_sec) - - def control_planning_dif(self, file, t=False): - """ - Showing Longitudinal - """ - fig, ax = plt.subplots(2, 2) - ax[0, 0].get_shared_x_axes().join(ax[0, 0], ax[0, 0]) - ax[0, 0].get_shared_x_axes().join(ax[0, 0], ax[0, 0]) - ax[0, 0].get_shared_x_axes().join(ax[0, 0], ax[0, 1]) - ax[0, 0].get_shared_x_axes().join(ax[0, 0], ax[1, 0]) - ax[0, 0].get_shared_x_axes().join(ax[0, 0], ax[1, 1]) - # del_head_error = 100 - # del_head_error = self.calculate_head_error(self.current_speed) - if self.current_speed: - del_head_error = self.calculate_head_error(self.current_speed) - else: - del_head_error = self.calculate_head_error(self.canbus_speed) - # del_head_error = 100 - # print('del_head_error is %', del_head_error) - if self.current_station: - del_end_error = self.calculate_end_error(self.current_station) - self.print_traj = t - - #station_error - self.station_reference = self.station_reference[ - del_head_error:del_end_error] - # for sta in self.station_reference: - # print(sta) - self.current_station = self.current_station[ - del_head_error:del_end_error] - max_station = max(self.current_station) - # print "Vehicel max drive distance is: %.0fm" % int(max_station) - self.station_error = self.station_error[del_head_error:del_end_error] - self.controltime = self.controltime[del_head_error:del_end_error] - - if not self.print_traj: - ax[0, 0].plot(self.controltime, - self.station_reference, - linewidth=1.0, - label='station_reference') - #self.controltime, self.station_reference) - ax[0, 0].plot(self.controltime, - self.current_station, - linewidth=1.0, - label='current_station') - #self.controltime, self.curre302,nt_station) - ax[0, 0].plot(self.controltime, - self.station_error, - linewidth=1.0, - label='station_error') - #self.controltime, self.station_error) - # legend=ax[0, 0].legend(fontsize='small', loc='upper left') - legend = ax[0, 0].legend(fontsize='small') - frame = legend.get_frame() - frame.set_alpha(1) - frame.set_facecolor('none') - ax[0, 0].grid(True) - ax[0, 0].set_title('station information') - ax[0, 0].set_xlabel('Time') - # python3 map return object not list - abs_station_error = list(map(abs, self.station_error)) - max_station_error = max(abs_station_error) - min_station_error = min(abs_station_error) - average_station_error = self.calculate_average(abs_station_error) - - #lateral_error - self.lateral_error = self.lateral_error[del_head_error:del_end_error] - if not self.print_traj: - ax[0, 1].plot(self.controltime, - self.lateral_error, - linewidth=1.0, - label='lateral_error') - #self.controltime, self.lateral_error) - # legend=ax[0, 1].legend(fontsize='small',loc='upper left') - legend = ax[0, 1].legend(fontsize='small') - frame = legend.get_frame() - frame.set_alpha(1) - frame.set_facecolor('none') - ax[0, 1].grid(True) - ax[0, 1].set_title('lateral Information') - ax[0, 1].set_xlabel('Time') - abs_lateral_error = list(map(abs, self.lateral_error)) - max_lateral_error = max(abs_lateral_error) - min_lateral_error = min(abs_lateral_error) - average_lateral_error = self.calculate_average(abs_lateral_error) - - # speed_error - self.speed_reference = self.speed_reference[ - del_head_error:del_end_error] - self.current_speed = self.current_speed[del_head_error:del_end_error] - # self.speed_error = self.speed_error[del_head_error:del_end_error] - self.canbus_speed = self.canbus_speed[del_head_error:del_end_error] - self.canbustime = self.canbustime[del_head_error:del_end_error] - max_speed = max(self.current_speed) - max_chassis_speed = max(self.canbus_speed) - if not self.print_traj: - print("Vehicel max speed is: %.3fm/s" % max_speed) - # print("Vehicel max chassis_speed is: %.3fm/s" % max_chassis_speed) - self.speed_error = self.speed_error[del_head_error:del_end_error] - if not self.print_traj: - ax[1, 0].plot(self.canbustime, - self.canbus_speed, - linewidth=1.0, - label='canbus_speed') - ax[1, 0].plot(self.controltime, - self.speed_reference, - linewidth=1.0, - label='speed_reference') - #self.controltime, self.speed_reference) - ax[1, 0].plot(self.controltime, - self.current_speed, - linewidth=1.0, - label='current_speed') - #self.controltime, self.current_speed) - ax[1, 0].plot(self.controltime, - self.speed_error, - linewidth=1.0, - label='speed_error') - #self.controltime, self.speed_error) - legend = ax[1, 0].legend(fontsize='small', loc='upper left') - frame = legend.get_frame() - frame.set_alpha(1) - frame.set_facecolor('none') - ax[1, 0].grid(True) - ax[1, 0].set_title('Speed information') - ax[1, 0].set_xlabel('Time') - abs_speed_error = list(map(abs, self.speed_error)) - max_speed_error = max(abs_speed_error) - min_speed_error = min(abs_speed_error) - average_speed_error = self.calculate_average(abs_speed_error) - - #heading_error - self.ref_heading = self.ref_heading[del_head_error:del_end_error] - self.heading = self.heading[del_head_error:del_end_error] - vehicel_behavior = self.get_vehicle_behavior(self.heading) - # print "Vehicel host behavior is: %s" % vehicel_behavior - self.heading_error = self.heading_error[del_head_error:del_end_error] - if not self.print_traj: - ax[1, 1].plot(self.controltime, - self.ref_heading, - linewidth=1.0, - label='ref_heading') - #self.controltime, self.ref_heading) - ax[1, 1].plot(self.controltime, - self.heading, - linewidth=1.0, - label='heading') - #self.controltime, self.heading) - ax[1, 1].plot(self.controltime, - self.heading_error, - linewidth=1.0, - label='heading_error') - #self.controltime, self.heading_error) - legend = ax[1, 1].legend( - fontsize='small' - ) #, mode='expend', shadow=True, bbox_to_anchor=(1.05,1), loc = 'upper left', borderaxespad=0. - frame = legend.get_frame() - frame.set_alpha(1) - frame.set_facecolor('none') - ax[1, 1].grid(True) - ax[1, 1].set_title('Heading information') - ax[1, 1].set_xlabel('Time') - abs_heading_error = list(map(abs, self.heading_error)) - max_heading_error = max(abs_heading_error) - min_heading_error = min(abs_heading_error) - average_heading_error = self.calculate_average(abs_heading_error) - - # Plot Trajectory - # self.carx = self.carx[del_head_error:del_end_error] - # self.cary = self.cary[del_head_error:del_end_error] - # self.pathx = self.pathx[del_head_error:del_end_error] - # self.pathy = self.pathy[del_head_error:del_end_error] - # self.planningx = self.planningx[del_head_error:del_end_error] - # self.planningy = self.planningy[del_head_error:del_end_error] - - if self.print_traj: - # print('carx list length is %', len(self.carx)) - # print('pathx list length is %', len(self.pathx)) - fig, ax = plt.subplots(1, 1) - ax.plot(self.planningx, - self.planningy, - linewidth=2.0, - linestyle='--', - label='planning path') - ax.plot(self.carx, self.cary, linewidth=1.0, label='pose') - ax.plot(self.pathx, - self.pathy, - linewidth=1.0, - label='planning path remain') - legend = ax.legend(fontsize='small') - frame = legend.get_frame() - frame.set_alpha(1) - frame.set_facecolor('none') - ax.grid(True) - ax.set_title('Trajectory') - ax.set_xlabel('x') - ax.set_ylabel('y') - - #write result to excel and calculate grade - #book_format = book.add_format({'font_color': 'black', 'align': 'center'}) - # 设置单元格居中,自动换行 - book_format = book.add_format({'align': 'center', 'text_wrap': True}) - sheet.write(file_num, 0, file) - sheet.write(file_num, 1, format(max_station_error, '.3f'), book_format) - sheet.write(file_num, 2, format(min_station_error, '.3f'), book_format) - sheet.write(file_num, 3, format(average_station_error, '.3f'), - book_format) - station_error_grade = self.get_station_error_grade(max_station_error) - station_error_stype = self.get_grade_style(int(station_error_grade)) - station_error_stype.set_bold() - sheet.write(file_num, 4, format(station_error_grade, '.2f'), - station_error_stype) - - sheet.write(file_num, 5, format(max_lateral_error, '.3f'), book_format) - sheet.write(file_num, 6, format(min_lateral_error, '.3f'), book_format) - sheet.write(file_num, 7, format(average_lateral_error, '.3f'), - book_format) - lateral_error_grade = self.get_lateral_error_grade(max_lateral_error) - lateral_error_stype = self.get_grade_style(int(lateral_error_grade)) - lateral_error_stype.set_bold() - sheet.write(file_num, 8, format(lateral_error_grade, '.2f'), - lateral_error_stype) - - sheet.write(file_num, 9, format(max_speed_error, '.3f'), book_format) - sheet.write(file_num, 10, format(min_speed_error, '.3f'), book_format) - sheet.write(file_num, 11, format(average_speed_error, '.3f'), - book_format) - speed_error_grade = self.get_speed_error_grade(max_speed_error) - speed_error_stype = self.get_grade_style(int(speed_error_grade)) - speed_error_stype.set_bold() - sheet.write(file_num, 12, format(speed_error_grade, '.2f'), - speed_error_stype) - - sheet.write(file_num, 13, format(max_heading_error, '.3f'), book_format) - sheet.write(file_num, 14, format(min_heading_error, '.3f'), book_format) - sheet.write(file_num, 15, format(average_heading_error, '.3f'), - book_format) - heading_error_grade = self.get_heading_error_grade(max_heading_error) - heading_error_stype = self.get_grade_style(int(heading_error_grade)) - heading_error_stype.set_bold() - sheet.write(file_num, 16, format(heading_error_grade, '.2f'), - heading_error_stype) - - average_score = format((station_error_grade + lateral_error_grade + - speed_error_grade + heading_error_grade) / 4.0, - '.2f') - sheet.write(file_num, 17, average_score, book_format) - - sheet.write(file_num, 18, vehicel_behavior, book_format) - sheet.write(file_num, 19, format(max_speed, '.3f'), book_format) - sheet.write(file_num, 20, int(max_station), book_format) - - # debug for heading/localization/path - # sheet.write_column('V2', self.pathx) - # sheet.write_column('W2', self.pathy) - # sheet.write_column('X2', self.cartime) - # debug for speed - # sheet.write_column('Y2', self.speed_reference) - # sheet.write_column('Z2', self.current_station) - # sheet.write_column('AA2', self.speed_error) - - if args.path and not self.print_traj: - average_score = format( - (station_error_grade + lateral_error_grade + speed_error_grade + - heading_error_grade) / 4.0, '.2f') - # print(type(average_score)) - # global score_num - # score_num = 0 - self.score_num = float(self.score_num) + float(average_score) - # score_num = score_num + average_score - #book_format = book.add_format({'align':'center','text_wrap': True}) - book_format17 = book.add_format({ - 'font_color': 'black', - 'align': 'center' - }) - book_format17.set_bold() - case_sheet.write(record_num, 0, file) - case_sheet.write(record_num, 1, vehicel_behavior, book_format) - case_sheet.write(record_num, 2, format(max_speed, '.3f'), - book_format) - case_sheet.write(record_num, 3, int(max_station), book_format) - case_sheet.write(record_num, 5, format(max_station_error, '.3f'), - book_format) - case_sheet.write(record_num, 6, format(average_station_error, - '.3f'), book_format) - case_sheet.write(record_num, 7, format(station_error_grade, '.2f'), - station_error_stype) - case_sheet.write(record_num, 8, format(max_lateral_error, '.3f'), - book_format) - case_sheet.write(record_num, 9, format(average_lateral_error, - '.3f'), book_format) - case_sheet.write(record_num, 10, format(lateral_error_grade, '.2f'), - lateral_error_stype) - case_sheet.write(record_num, 11, format(max_speed_error, '.3f'), - book_format) - case_sheet.write(record_num, 12, format(average_speed_error, '.3f'), - book_format) - case_sheet.write(record_num, 13, format(speed_error_grade, '.2f'), - speed_error_stype) - case_sheet.write(record_num, 14, format(max_heading_error, '.3f'), - book_format) - case_sheet.write(record_num, 15, format(average_heading_error, - '.3f'), book_format) - case_sheet.write(record_num, 16, format(heading_error_grade, '.2f'), - heading_error_stype) - case_sheet.write(record_num, 17, average_score, book_format) - - if not self.print_traj: - if len(self.mode_time) % 2 == 1: - self.mode_time.append(self.controltime[-1]) - for i in range(0, len(self.mode_time), 2): - ax[0, 0].axvspan(self.mode_time[i], - self.mode_time[i + 1], - fc='0.1', - alpha=0.1) - ax[1, 0].axvspan(self.mode_time[i], - self.mode_time[i + 1], - fc='0.1', - alpha=0.1) - ax[1, 1].axvspan(self.mode_time[i], - self.mode_time[i + 1], - fc='0.1', - alpha=0.1) - - def plot_chassis_speed(self): - - fig, ax = plt.subplots(1, 1) - ax.plot(self.canbustime, - self.canbus_speed, - linewidth=1.0, - label='canbus_speed') - max_chassis_speed = max(self.canbus_speed) - print("Vehicel max chassis_speed is: %.3fm/s" % max_chassis_speed) - - def press(self, event): - """ - Keyboard events during plotting - """ - if event.key == 'q' or event.key == 'Q': - plt.close('all') - if event.key == 'd' or event.key == 'D': - self.control_planning_dif(file) - - def calculate_average(self, array): - sum = 0 - num = len(array) - for i in array: - sum = sum + abs(i) - return sum / num - - def calculate_head_error(self, list): - # print("list head data length is ", len(list)) - for i in range(3, len(list)): - if list[i + 1] - list[i] >= 0: - # print("head_i=", i) - head = i - break - return head - - def calculate_end_error(self, list): - for i in range(len(list), 0, -1): - if list[i - 1] != 0: - # print("end_i=", i) - end = i - 2 - break - return end - - def get_vehicle_behavior(self, heading, del_head_error=1): - k = 57.3248 - for i in range(len(heading), 0, -1): - if heading[i - 1] != 0: - # print("heading_end_i =", i) - end = i - 2 - break - # begin = del_head_error + 10 - begin = del_head_error - # print("heading_begin_i =", begin) - heading_begin = self.heading[begin] - # print("heading_begin =", heading_begin) - heading_end = self.heading[end] - # print("heading_end =", heading_end) - delta = (heading_end - heading_begin) * k - # print("delta is", delta) - behavior = '' - if -20 < delta < 20: - #behavior = 'go straight' - behavior = '直行' - elif 45 < delta < 135 or -315 < delta < -225: - #behavior = 'turn left' - behavior = '左转' - elif -135 < delta < -45 or 225 < delta < 315: - #behavior = 'turn right' - behavior = '右转' - return behavior - - def get_station_error_grade(self, value): - grade = 0 - if value >= 10: - grade = 1 - elif 6 <= value < 10: - grade = 3 - (value - 6) / 4 - elif 3 <= value < 6: - grade = 4 - (value - 3) / 3 - elif 1 <= value < 3: - grade = 5 - (value - 1) / 2 - elif 0 <= value < 1: - grade = 5 - return grade - - def get_lateral_error_grade(self, value): - grade = 0 - if value >= 2: - grade = 1 - elif 1 <= value < 2: - grade = 3 - (value - 1) / 1 - elif 0.5 <= value < 1: - grade = 4 - (value - 0.5) / 0.5 - elif 0.2 <= value < 0.5: - grade = 5 - (value - 0.2) / 0.3 - elif 0 <= value < 0.2: - grade = 5 - return grade - - def get_speed_error_grade(self, value): - grade = 0 - if value >= 5: - grade = 1 - elif 3 <= value < 5: - grade = 3 - (value - 3) / 2 - elif 1.5 <= value < 3: - grade = 4 - (value - 1.5) / 1.5 - elif 0.5 <= value < 1.5: - grade = 5 - (value - 0.5) / 1 - elif 0 <= value < 0.5: - grade = 5 - return grade - - def get_heading_error_grade(self, value): - grade = 0 - if value >= 0.6: - grade = 1 - elif 0.4 <= value < 0.6: - grade = 3 - (value - 0.4) / 0.2 - elif 0.2 <= value < 0.4: - grade = 4 - (value - 0.2) / 0.2 - elif 0.1 <= value < 0.2: - grade = 5 - (value - 0.1) / 0.1 - elif 0 <= value < 0.1: - grade = 5 - return grade - - def get_grade_style(self, value): - style = "" - style_dict = { - 1: book.add_format({ - 'align': 'center', - 'font_color': 'red' - }), - 2: book.add_format({ - 'align': 'center', - 'font_color': 'brown' - }), - 3: book.add_format({ - 'align': 'center', - 'font_color': 'orange' - }), - 4: book.add_format({ - 'align': 'center', - 'font_color': 'blue' - }), - 5: book.add_format({ - 'align': 'center', - 'font_color': 'dark_green' - }) - } - if value == 5: - style = style_dict[5] - elif value == 4: - style = style_dict[4] - elif value == 3: - style = style_dict[3] - elif value == 2: - style = style_dict[2] - elif value == 1: - style = style_dict[1] - return style - - def read_bag(self, bag_file): - file_path = bag_file - bag = RecordReader(file_path) - print("Begin reading the file: ", file_path) - for msg in bag.read_messages(): - #print msg.timestamp,msg.topic - if msg.topic == "/apollo/control": - control_cmd = control_cmd_pb2.ControlCommand() - control_cmd.ParseFromString(msg.message) - controlinfo.callback_control(control_cmd) - elif msg.topic == "/apollo/planning": - adc_trajectory = planning_pb2.ADCTrajectory() - #planning_pb = proto_utils.get_pb_from_text_file(planning_pb2, adc_trajectory) - adc_trajectory.ParseFromString(msg.message) - controlinfo.callback_planning(adc_trajectory) - elif msg.topic == "/apollo/canbus/chassis": - chassis = chassis_pb2.Chassis() - chassis.ParseFromString(msg.message) - controlinfo.callback_canbus(chassis) - elif msg.topic == "/apollo/localization/pose": - localization = localization_pb2.LocalizationEstimate() - localization.ParseFromString(msg.message) - controlinfo.callback_localization(localization) - print("Done reading the file: ", file_path) - - def add_excel_sheet(self, file): - sheet = book.add_worksheet(file) - # 设置单元格居中,自动换行 - book_format = book.add_format({'align': 'center', 'text_wrap': True}) - sheet.write(0, 0, 'file_name', book_format) - sheet.write(0, 1, 'max_station_error', book_format) - sheet.write(0, 2, 'min_station_error', book_format) - sheet.write(0, 3, 'average_station_error', book_format) - sheet.write(0, 4, 'station_error_grade', book_format) - - sheet.write(0, 5, 'max_lateral_error', book_format) - sheet.write(0, 6, 'min_lateral_error', book_format) - sheet.write(0, 7, 'average_lateral_error', book_format) - sheet.write(0, 8, 'lateral_error_grade', book_format) - - sheet.write(0, 9, 'max_speed_error', book_format) - sheet.write(0, 10, 'min_speed_error', book_format) - sheet.write(0, 11, 'average_speed_error', book_format) - sheet.write(0, 12, 'speed_error_grade', book_format) - - sheet.write(0, 13, 'max_heading_error', book_format) - sheet.write(0, 14, 'min_heading_error', book_format) - sheet.write(0, 15, 'average_heading_error', book_format) - sheet.write(0, 16, 'heading_error_grade', book_format) - sheet.write(0, 17, '平均得分', book_format) - sheet.write(0, 18, '主车行为', book_format) - sheet.write(0, 19, '最大车速(m/s)', book_format) - sheet.write(0, 20, '行驶距离(m)', book_format) - # sheet.write(0, 21, 'carx', book_format) - # sheet.write(0, 22, 'cary', book_format) - # sheet.write(0, 23, 'cartime', book_format) - # sheet.write(0, 24, 'speed_reference', book_format) - # sheet.write(0, 25, 'current_speed', book_format) - # sheet.write(0, 26, 'speed_error', book_format) - # 设置0行行高 - sheet.set_row(0, 45) - sheet.set_row(1, 25) - # 设置0列每个单元格宽度 - sheet.set_column(0, 0, 12) - # 设置1-19列每个单元格宽度 - sheet.set_column(1, 16, 8) - sheet.set_column(17, 19, 7) - return sheet - - -def add_test_case_result(book): - case_sheet = book.add_worksheet('测试用例及结果') - book_format = book.add_format({'align': 'center', 'text_wrap': True}) - case_sheet.merge_range(0, 0, 0, 18, 'Apollo车辆认证平台循迹测试报告') - case_sheet.write(1, 0, '循迹数据包名称', book_format) - case_sheet.write(1, 1, '主车行为', book_format) - case_sheet.write(1, 2, '最大车速(m/s)', book_format) - case_sheet.write(1, 3, '行驶距离(m)', book_format) - case_sheet.write(1, 4, '描述', book_format) - case_sheet.write(1, 5, '最大纵向误差:米max_station_error', book_format) - case_sheet.write(1, 6, '平均纵向误差:米average_station_error', book_format) - case_sheet.write(1, 7, '纵向误差评分 station_error_grade', book_format) - case_sheet.write(1, 8, '最大横向误差:米max_lateral_error', book_format) - case_sheet.write(1, 9, '平均横向误差:米average_lateral_error', book_format) - case_sheet.write(1, 10, '横向误差评分 lateral_error_grade', book_format) - case_sheet.write(1, 11, '最大速度误差:米max_speed_error', book_format) - case_sheet.write(1, 12, '平均速度误差:米average_speed_error', book_format) - case_sheet.write(1, 13, '速度误差评分 speed_error_grade', book_format) - case_sheet.write(1, 14, '最大航向误差:rad max_heading_error', book_format) - case_sheet.write(1, 15, '平均航向误差:rad average_heading_error', book_format) - case_sheet.write(1, 16, '航向误差评分 heading_error_grade', book_format) - case_sheet.write(1, 17, '综合评定(5分制)', book_format) - case_sheet.write(1, 18, '备注(测试时,根据实际场地和驾驶安全需要适当调整转弯速度)', book_format) - # 设置第1行行高 - case_sheet.set_row(1, 65) - # 设置0列每个单元格宽度 - case_sheet.set_column(0, 0, 12) - case_sheet.set_column(1, 4, 7) - case_sheet.set_column(5, 17, 10) - case_sheet.set_column(18, 18, 50) - return case_sheet - - -def is_record_file(path): - """Naive check if a path is a record.""" - return path.endswith('.record') or fnmatch.fnmatch( - path, '*.record.?????') or fnmatch.fnmatch(path, '*.record.????') - - -if __name__ == "__main__": - parser = argparse.ArgumentParser( - description="Process and analyze control and planning data. usage:\ - 'python control_planning_evaluation.py --path bag_file_directory_path',\ - 'python control_planning_evaluation.py --bag bag_file_path' ") - parser.add_argument('--bag', type=str, help='use cyber_recorder') - parser.add_argument('--path', type=str, help='path for bag files') - args = parser.parse_args() - cyber.init() - node = cyber.Node("control_profile") - fig, axarr = plt.subplots() - controlinfo = ControlInfo(axarr) - trajectory_print = True - read_bag_all = True - file_num = 0 - if args.path: - record_num = 1 - controlinfo.score_num = 0 - dir_path = args.path - new_path = os.path.join(dir_path, 'picture') - print("dir_path is", dir_path) - path_file_name = os.path.splitext(args.path)[0].split('/')[2] - print("path_file_name", path_file_name) - excel_name = dir_path + path_file_name + '_' + 'evaluation_result.xlsx' - print("excel_name", excel_name) - case_file_name = dir_path + 'case.xlsx' - flag = os.path.exists(case_file_name) - book = xlsxwriter.Workbook(excel_name) - case_sheet = add_test_case_result(book) - if read_bag_all: - if os.path.isdir(dir_path): - dirs = os.listdir(dir_path) - # print("dirs is", dirs) - dirs.sort() - if (os.path.exists(new_path) == False): - os.mkdir(new_path) - print("new path is", new_path) - for file in dirs: - # print("file", file) - if is_record_file(file): - controlinfo.read_bag(dir_path + file) - - record_num = record_num + 1 - file_num = 1 - sheet = controlinfo.add_excel_sheet(path_file_name) - # mng = plt.get_current_fig_manager() - controlinfo.control_planning_dif(path_file_name) - fig.canvas.mpl_connect('key_press_event', controlinfo.press) - # plt.show() - picture_name = new_path + '/' + path_file_name + '_' + 'picture' + '_' + '1' + '.jpg' - print("save picture1 to: ", picture_name) - plt.tight_layout() - plt.subplots_adjust(right=0.8) - plt.savefig(picture_name, dpi=300) - sheet.insert_image(4, 1, picture_name) - # plt trajectory - controlinfo.control_planning_dif(path_file_name, trajectory_print) - fig.canvas.mpl_connect('key_press_event', controlinfo.press) - picture_name = new_path + '/' + path_file_name + '_' + 'picture' + '_' + '2' + '.jpg' - print("save picture2 to:", picture_name) - plt.savefig(picture_name, dpi=300) #不设置分辨率300,不同的结果图片分辨率不同 - # sheet.insert_image(4, 11, picture_name) #设置插入到Excel内,图片的缩放,默认是1 - sheet.insert_image(4, 11, picture_name, { - 'x_scale': 0.9, - 'y_scale': 1 - }) - - record_num = record_num + 1 - case_sheet.merge_range(record_num, 0, record_num, 1, '') - case_sheet.merge_range(record_num, 2, record_num, 16, '') - case_sheet.write(record_num, 17, '总分:' + format(controlinfo.score_num)) - record_num = record_num + 1 - string_value = "总体主观评价" - case_sheet.merge_range(record_num, 0, record_num, 1, string_value) - case_sheet.write( - record_num, 17, - '平均:' + format(controlinfo.score_num / (record_num - 3), '.3f')) - #excel_name1 = dir_path + '/' + excel_name - print("save all results to: ", excel_name) - - book.close() - - else: - if os.path.isdir(dir_path): - dirs = os.listdir(dir_path) - dirs.sort() - if (os.path.exists(new_path) == False): - os.mkdir(new_path) - for file in dirs: - if is_record_file(file): - record_num = record_num + 1 - file_num = 1 - controlinfo.read_bag(dir_path + file) - sheet = controlinfo.add_excel_sheet(file) - controlinfo.control_planning_dif(file) - fig.canvas.mpl_connect('key_press_event', - controlinfo.press) - picture_name = new_path + '/' + file + '_' + '1' + '.jpg' - print("save picture1 to: ", picture_name) - plt.tight_layout() - plt.subplots_adjust(right=0.8) - plt.savefig(picture_name, dpi=300) - sheet.insert_image(4, 1, picture_name) - controlinfo = ControlInfo(axarr) - controlinfo.read_bag(dir_path + file) - controlinfo.control_planning_dif(file, trajectory_print) - fig.canvas.mpl_connect('key_press_event', - controlinfo.press) - picture_name = new_path + '/' + file + '_' + '2' + '.jpg' - print("save picture2 to:", picture_name) - plt.savefig(picture_name, - dpi=300) #不设置分辨率300,不同的结果图片分辨率不同 - sheet.insert_image(4, 11, picture_name, { - 'x_scale': 0.9, - 'y_scale': 1 - }) - record_num = record_num + 1 - case_sheet.merge_range(record_num, 0, record_num, 1, '') - case_sheet.merge_range(record_num, 2, record_num, 16, '') - case_sheet.write(record_num, 17, '总分:' + format(controlinfo.score_num)) - record_num = record_num + 1 - string_value = "总体主观评价" - case_sheet.merge_range(record_num, 0, record_num, 1, string_value) - case_sheet.write( - record_num, 17, - '平均:' + format(controlinfo.score_num / (record_num - 3), '.3f')) - #excel_name1 = dir_path + '/' + excel_name - print("save all results to: ", excel_name) - book.close() - elif args.bag: - file = os.path.basename(args.bag) - print('file name is', file) - print('bag name is', args.bag) - excel_name = os.path.splitext(args.bag)[0] + '_evaluation.xlsx' - book = xlsxwriter.Workbook(excel_name) - file_num = file_num + 1 - controlinfo = ControlInfo(axarr) - controlinfo.read_bag(args.bag) - controlinfo.plot_chassis_speed() - sheet = controlinfo.add_excel_sheet(file) - controlinfo.control_planning_dif(file) - fig.canvas.mpl_connect('key_press_event', controlinfo.press) - picture_name = os.path.splitext(args.bag)[0] + '_' + '1' + '.jpg' - print("save picture1 to:", picture_name) - plt.tight_layout() - plt.savefig(picture_name, dpi=300) #设置分辨率300 - sheet.insert_image(4, 1, picture_name) #设置插入到Excel内,图片的缩放,默认是1 - # print trajectory - fig, axarr = plt.subplots(1, 1) - controlinfo = ControlInfo(axarr) - controlinfo.read_bag(args.bag) - controlinfo.control_planning_dif(file, trajectory_print) - fig.canvas.mpl_connect('key_press_event', controlinfo.press) - picture_name = os.path.splitext(args.bag)[0] + '_' + '2' + '.jpg' - print("save picture2 to:", picture_name) - plt.tight_layout() - plt.savefig(picture_name, dpi=300) #设置分辨率300 - # time.sleep(5) - # sheet.insert_image(4, 11, picture_name) #设置插入到Excel内,图片的缩放,默认是1 - sheet.insert_image(4, 11, picture_name, {'x_scale': 0.9, 'y_scale': 1}) - print("save evaluation result to: ", excel_name) - book.close() - else: - file = "real_time_file" - file_num = file_num + 1 - controlinfo = ControlInfo(axarr) - controlsub = node.create_reader("/apollo/control", - control_cmd_pb2.ControlCommand, - controlinfo.callback_control) - canbussub = node.create_reader('/apollo/canbus/chassis', - chassis_pb2.Chassis, - controlinfo.callback_canbus) - mng = plt.get_current_fig_manager() - controlinfo.control_planning_dif(file) - fig.canvas.mpl_connect('key_press_event', controlinfo.press) - - cyber.shutdown() diff --git a/modules/tools/visualizer/BUILD b/modules/tools/visualizer/BUILD deleted file mode 100644 index b43c5cd56c3..00000000000 --- a/modules/tools/visualizer/BUILD +++ /dev/null @@ -1,77 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_binary") -load("//third_party/qt5:qt.bzl", "qt_cc_library") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -install( - name = "install", - runtime_dest = "tools/bin", - targets = [ - ":cyber_visualizer", - ], - deps = [ - "//cyber:install", - ], -) - -cc_binary( - name = "cyber_visualizer", - copts = [ - "-Iexternal/qt", - ], - includes = [ - ".", - ], - linkopts = [ - "-pthread", - ], - linkstatic = True, - deps = [ - ":visualizer_lib", - "@fastrtps", - "@qt//:qt_core", - "@qt//:qt_gui", - "@qt//:qt_opengl", - "@qt//:qt_widgets", - ], -) - -# TODO(all): Extract the large library to thin pieces. -qt_cc_library( - name = "visualizer_lib", - srcs = glob( - ["*.cc"], - ), - hdrs = glob([ - "*.h", - ]), - copts = [ - "-Iexternal/qt", - ], - includes = [ - ".", - ], - linkstatic = False, - res = glob([ - "*.qrc", - ]), - uis = glob([ - "uis/*.ui", - ]), - deps = [ - "//cyber", - "//modules/common_msgs/sensor_msgs:pointcloud_cc_proto", - "//modules/common_msgs/sensor_msgs:radar_cc_proto", - "//modules/common_msgs/sensor_msgs:sensor_image_cc_proto", - "@qt//:qt_core", - "@qt//:qt_gui", - "@qt//:qt_opengl", - "@qt//:qt_widgets", - ], -) - -# TODO(all): Disable linter temporarily as the generated ui files should be -# excluded from check. But we should also check the .h and .cc files, if they -# are extracted to their own cc_libraries. See the TODO above. -# cpplint() diff --git a/modules/tools/visualizer/abstract_camera.cc b/modules/tools/visualizer/abstract_camera.cc deleted file mode 100644 index 8a845d6d7dc..00000000000 --- a/modules/tools/visualizer/abstract_camera.cc +++ /dev/null @@ -1,67 +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/tools/visualizer/abstract_camera.h" -#include - -const QVector3D AbstractCamera::UP{0.0f, 1.0f, 0.0f}; - -QMatrix4x4 AbstractCamera::YawPitchRoll(float yaw, float pitch, float roll) { - yaw = Radians(yaw); - pitch = Radians(pitch); - roll = Radians(roll); - - register float tmpCy = std::cos(yaw); - register float tmpSy = std::sin(yaw); - register float tmpCp = std::cos(pitch); - register float tmpSp = std::sin(pitch); - register float tmpCr = std::cos(roll); - register float tmpSr = std::sin(roll); - - QMatrix4x4 Result; - Result(0, 0) = tmpCy * tmpCr + tmpSy * tmpSp * tmpSr; - Result(1, 0) = tmpSr * tmpCp; - Result(2, 0) = -tmpSy * tmpCr + tmpCy * tmpSp * tmpSr; - Result(3, 0) = 0.0f; - Result(0, 1) = -tmpCy * tmpSr + tmpSy * tmpSp * tmpCr; - Result(1, 1) = tmpCr * tmpCp; - Result(2, 1) = tmpSr * tmpSy + tmpCy * tmpSp * tmpCr; - Result(3, 1) = 0.0f; - Result(0, 2) = tmpSy * tmpCp; - Result(1, 2) = -tmpSp; - Result(2, 2) = tmpCy * tmpCp; - Result(3, 2) = 0.0f; - Result(0, 3) = 0.0f; - Result(1, 3) = 0.0f; - Result(2, 3) = 0.0f; - Result(3, 3) = 1.0f; - return Result; -} - -AbstractCamera::AbstractCamera() - : camera_mode_(CameraMode::PerspectiveMode), - fov_(45.0f), - near_plane_width_(1.0f), - near_plane_height_(1.0f), - near_plane_(0.1f), - far_plane_(1000.0f), - position_(0.0f, 0.0f, 0.0f), - attitude_(), - look_(0.0f, 0.0f, 1.0f), - up_(UP), - right_(1.0f, 0.0f, 0.0f), - projection_mat_(), - model_view_mat_() {} diff --git a/modules/tools/visualizer/abstract_camera.h b/modules/tools/visualizer/abstract_camera.h deleted file mode 100644 index fdc12b3dffe..00000000000 --- a/modules/tools/visualizer/abstract_camera.h +++ /dev/null @@ -1,149 +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 - -class AbstractCamera { - public: - enum class CameraMode { PerspectiveMode, OrthoMode }; - - static const QVector3D UP; - static float Radians(float degrees) { - return degrees * static_cast(0.01745329251994329576923690768489); - } - - static float Degrees(float radians) { - return radians * static_cast(57.295779513082320876798154814105); - } - - static QMatrix4x4 YawPitchRoll(float yawInDegrees, float picthInDegrees, - float rollInDegrees); - - AbstractCamera(void); - virtual ~AbstractCamera() {} - - virtual void UpdateWorld(void) = 0; // update modelview - - CameraMode camera_mode(void) const { return camera_mode_; } - void set_camera_mode(CameraMode cm) { camera_mode_ = cm; } - - const QMatrix4x4& projection_matrix(void) const { return projection_mat_; } - const QMatrix4x4& model_view_matrix(void) const { return model_view_mat_; } - - float near_plane_height(void) const { return near_plane_height_; } - float near_plane_width(void) const { return near_plane_width_; } - void set_near_plane_height(const float npHeight) { - near_plane_height_ = npHeight; - } - void set_near_plane_width(const float npWidth) { - near_plane_width_ = npWidth; - } - - float fov(void) const { return fov_; } - void set_fov(const float fovInDegrees) { fov_ = fovInDegrees; } - - float near_plane(void) const { return near_plane_; } - void set_near_plane(float n) { near_plane_ = n; } - - float far_plane(void) const { return far_plane_; } - void set_far_plane(float f) { far_plane_ = f; } - - void SetUpProjection(float fovInDegrees, float nearPlaneWidth, - float nearPlaneHeight, float near = 0.1f, - float far = 1000.f) { - fov_ = fovInDegrees; - near_plane_width_ = nearPlaneWidth; - near_plane_height_ = nearPlaneHeight; - near_plane_ = near; - far_plane_ = far; - } - - float x(void) const { return position_[0]; } - float y(void) const { return position_[1]; } - float z(void) const { return position_[2]; } - - void set_x(float x) { position_[0] = x; } - void set_y(float y) { position_[1] = y; } - void set_z(float z) { position_[2] = z; } - - const QVector3D& position(void) const { return position_; } - void set_position(const QVector3D& pos) { position_ = pos; } - void set_position(float x, float y, float z) { - position_.setX(x); - position_.setY(y); - position_.setZ(z); - } - - float yaw(void) const { return attitude_[0]; } - void set_yaw(float yInDegrees) { attitude_[0] = yInDegrees; } - - float pitch(void) const { return attitude_[1]; } - void set_pitch(float pInDegrees) { attitude_[1] = pInDegrees; } - - float roll(void) const { return attitude_[2]; } - void set_roll(float rInDegrees) { attitude_[2] = rInDegrees; } - - const QVector3D& attitude(void) const { return attitude_; } - - void SetAttitude(float yawInDegrees, float pitchInDegrees, - float rollInDegrees) { - attitude_[0] = yawInDegrees; - attitude_[1] = pitchInDegrees; - attitude_[2] = rollInDegrees; - } - - const QVector3D& look(void) const { return look_; } - - void UpdateProjection(void) { - projection_mat_.setToIdentity(); - if (camera_mode() == CameraMode::PerspectiveMode) { - projection_mat_.perspective(fov_, near_plane_width_ / near_plane_height_, - near_plane_, far_plane_); - } else { - projection_mat_.ortho(-near_plane_width_ / 2.0f, near_plane_width_ / 2.0f, - -near_plane_height_ / 2.0f, - near_plane_height_ / 2.0f, 0.0f, 0.0f); - } - } - - void Update(void) { - UpdateWorld(); - UpdateProjection(); - } - - protected: - CameraMode camera_mode_; - - float fov_; // in degrees - - float near_plane_width_; - float near_plane_height_; - - float near_plane_; // in look direction - float far_plane_; // in look direction - - QVector3D position_; // x, y, z - QVector3D attitude_; // 0:yaw, 1:pitch, 2:roll , in degrees - - QVector3D look_; - QVector3D up_; - QVector3D right_; - - QMatrix4x4 projection_mat_; - QMatrix4x4 model_view_mat_; -}; diff --git a/modules/tools/visualizer/channel_reader.h b/modules/tools/visualizer/channel_reader.h deleted file mode 100644 index a4ead280f83..00000000000 --- a/modules/tools/visualizer/channel_reader.h +++ /dev/null @@ -1,103 +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 "cyber/cyber.h" - -class MainWindow; - -template -using CyberChannelCallback = std::function&)>; - -template -class CyberChannReader { - public: - CyberChannReader(void) : channel_callback_(nullptr), channel_node_(nullptr) {} - - ~CyberChannReader() { CloseChannel(); } - - void CloseChannel(void) { - if (channel_reader_ != nullptr) { - channel_reader_.reset(); - } - - if (channel_node_ != nullptr) { - channel_node_.reset(); - } - } - - bool InstallCallbackAndOpen(CyberChannelCallback channelCallback, - const std::string& channelName, - const std::string& nodeName) { - return InstallCallback(channelCallback) && - OpenChannel(channelName, nodeName); - } - - bool InstallCallback(CyberChannelCallback channelCallback) { - if (channelCallback != nullptr) { - channel_callback_ = channelCallback; - return true; - } else { - std::cerr << "Parameter readerCallback is null" << std::endl; - return false; - } - } - - bool OpenChannel(const std::string& channelName, - const std::string& nodeName) { - if (channelName.empty() || nodeName.empty()) { - std::cerr << "Channel Name or Node Name must be not empty" << std::endl; - return false; - } - - if (channel_node_ != nullptr || channel_reader_ != nullptr || - !channel_callback_) { - return false; - } - - return CreateChannel(channelName, nodeName); - } - - const std::string& NodeName(void) const { return channel_node_->Name(); } - - private: - bool CreateChannel(const std::string& channelName, - const std::string& nodeName) { - if (channel_node_ == nullptr) { - channel_node_ = apollo::cyber::CreateNode(nodeName); - if (channel_node_ == nullptr) { - return false; - } - } - - channel_reader_ = - channel_node_->CreateReader(channelName, channel_callback_); - - if (channel_reader_ == nullptr) { - std::cout << "----------Creat reader failed---------" << std::endl; - return false; - } - return true; - } - - CyberChannelCallback channel_callback_; - std::shared_ptr> channel_reader_; - std::shared_ptr channel_node_; -}; diff --git a/modules/tools/visualizer/fixedaspectratiowidget.cc b/modules/tools/visualizer/fixedaspectratiowidget.cc deleted file mode 100644 index ec8c48cf1f6..00000000000 --- a/modules/tools/visualizer/fixedaspectratiowidget.cc +++ /dev/null @@ -1,119 +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/tools/visualizer/fixedaspectratiowidget.h" - -#include -#include -#include -#include - -FixedAspectRatioWidget::FixedAspectRatioWidget(QWidget* parent, int index) - : QWidget(parent), index_(index), refresh_timer_(this), viewer_() { - viewer_.setParent(this); - viewer_.setGeometry(geometry()); - - refresh_timer_.setObjectName(tr("_refreshTimer")); - refresh_timer_.setInterval(40); - connect(&refresh_timer_, SIGNAL(timeout()), &viewer_, SLOT(repaint())); - setAutoFillBackground(true); -} - -void FixedAspectRatioWidget::StartOrStopUpdate(bool b) { - if (viewer_.is_init_) { - if (b) { - refresh_timer_.start(); - } else { - refresh_timer_.stop(); - } - } -} - -void FixedAspectRatioWidget::SetupDynamicTexture( - const std::shared_ptr& textureObj) { - if (textureObj == nullptr) { - viewer_.default_image_->setSizeChanged(); - viewer_.plane_.set_texture(viewer_.default_image_); - } else { - viewer_.plane_.set_texture(textureObj); - } -} - -void FixedAspectRatioWidget::mouseDoubleClickEvent(QMouseEvent* event) { - if (event->button() == Qt::LeftButton) { - emit focusOnThis(this); - QWidget::mouseDoubleClickEvent(event); - } -} - -void FixedAspectRatioWidget::contextMenuEvent(QContextMenuEvent* event) { - emit focusOnThis(this); - QMenu m; - m.addActions(actions()); - m.exec(event->globalPos()); - m.clear(); - - QWidget::contextMenuEvent(event); -} - -void FixedAspectRatioWidget::resizeEvent(QResizeEvent* revent) { - QSize size = revent->size(); - - { - double aspect = static_cast(viewer_.plane_.texWidth()) / - static_cast(viewer_.plane_.texHeight()); - - int wc = 4; - int hc = 9; - if (aspect == 4.0 / 3.0) { - wc = 2; - hc = 3; - } else if (aspect == 16.0 / 10.0) { - wc = 4; - hc = 10; - } - - int w = size.width(); - int h = size.height(); - - int tmpH = w >> wc; - w = tmpH << wc; - size.setWidth(w); - tmpH *= hc; - if (tmpH <= h) { - size.setHeight(tmpH); - } else { - tmpH = h / hc; - h = tmpH * hc; - size.setHeight(h); - size.setWidth(tmpH << wc); - } - } - - viewer_.setGeometry((revent->size().width() - size.width()) / 2, - (revent->size().height() - size.height()) / 2, - size.width(), size.height()); - QWidget::resizeEvent(revent); -} - -void FixedAspectRatioWidget::paintEvent(QPaintEvent* event) { - QStyleOption opt; - opt.init(this); - QPainter p(this); - style()->drawPrimitive(QStyle::PE_Widget, &opt, &p, this); - - QWidget::paintEvent(event); -} diff --git a/modules/tools/visualizer/fixedaspectratiowidget.h b/modules/tools/visualizer/fixedaspectratiowidget.h deleted file mode 100644 index 0c46a4cdd1a..00000000000 --- a/modules/tools/visualizer/fixedaspectratiowidget.h +++ /dev/null @@ -1,52 +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 "modules/tools/visualizer/video_image_viewer.h" - -class FixedAspectRatioWidget : public QWidget { - Q_OBJECT - - public: - explicit FixedAspectRatioWidget(QWidget *parent = nullptr, int index = 0); - - bool is_init(void) const { return viewer_.is_init_; } - void SetupDynamicTexture(const std::shared_ptr &textureObj); - - void set_index(int i) { index_ = i; } - int index(void) const { return index_; } - - void StartOrStopUpdate(bool b); - int innerHeight(void) { return viewer_.plane_.texHeight(); } - - signals: - void focusOnThis(FixedAspectRatioWidget *); - - protected: - void mouseDoubleClickEvent(QMouseEvent *event) override; - void contextMenuEvent(QContextMenuEvent *) override; - void resizeEvent(QResizeEvent *) override; - void paintEvent(QPaintEvent *event) override; - - private: - int index_; - QTimer refresh_timer_; - VideoImgViewer viewer_; -}; diff --git a/modules/tools/visualizer/free_camera.cc b/modules/tools/visualizer/free_camera.cc deleted file mode 100644 index 5b98da801af..00000000000 --- a/modules/tools/visualizer/free_camera.cc +++ /dev/null @@ -1,37 +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/tools/visualizer/free_camera.h" - -FreeCamera::FreeCamera(void) - : AbstractCamera(), translation_(0.0, 0.0f, 0.0f) {} - -void FreeCamera::UpdateWorld(void) { - QMatrix4x4 R = YawPitchRoll(attitude_[0], attitude_[1], attitude_[2]); - - position_ += translation_; - translation_.setX(0.0f); - translation_.setY(0.0f); - translation_.setZ(0.0f); - - look_ = QVector3D(R * QVector4D(0.0f, 0.0f, 1.0f, 0.0f)); - up_ = QVector3D(R * QVector4D(0.0f, 1.0f, 0.0f, 0.0f)); - right_ = QVector3D::crossProduct(look_, up_); - - QVector3D tgt = position_ + look_; - model_view_mat_.setToIdentity(); - model_view_mat_.lookAt(position_, tgt, up_); -} diff --git a/modules/tools/visualizer/free_camera.h b/modules/tools/visualizer/free_camera.h deleted file mode 100644 index e2d8570bcf0..00000000000 --- a/modules/tools/visualizer/free_camera.h +++ /dev/null @@ -1,39 +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 "modules/tools/visualizer/abstract_camera.h" - -class FreeCamera : public AbstractCamera { - public: - FreeCamera(void); - ~FreeCamera() {} - - // After calling the function updateWorld - // the translation become zero vector - virtual void UpdateWorld(void); - - const QVector3D& tanslation(void) { return translation_; } - void set_translation(const QVector3D& t) { translation_ = t; } - - void Walk(const float dt) { translation_ += (look_ * dt); } - void Starfe(const float dt) { translation_ += (right_ * dt); } - void Lift(const float dt) { translation_ += (up_ * dt); } - - private: - QVector3D translation_; -}; diff --git a/modules/tools/visualizer/grid.cc b/modules/tools/visualizer/grid.cc deleted file mode 100644 index 6aa8c94717f..00000000000 --- a/modules/tools/visualizer/grid.cc +++ /dev/null @@ -1,44 +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/tools/visualizer/grid.h" - -Grid::Grid(int cellCountBySide) - : RenderableObject((cellCountBySide << 2) + 4, 2), - grid_color_(128, 128, 128) {} - -bool Grid::FillVertexBuffer(GLfloat* pBuffer) { - float x = static_cast(CellCount()) / 2.0f; - float z; - - for (z = -x; z <= x; ++z) { - *pBuffer++ = -x; - *pBuffer++ = z; - *pBuffer++ = x; - *pBuffer++ = z; - } - - z = x; - - for (x = -z; x <= z; ++x) { - *pBuffer++ = x; - *pBuffer++ = -z; - *pBuffer++ = x; - *pBuffer++ = z; - } - - return true; -} diff --git a/modules/tools/visualizer/grid.h b/modules/tools/visualizer/grid.h deleted file mode 100644 index 0cb48edd941..00000000000 --- a/modules/tools/visualizer/grid.h +++ /dev/null @@ -1,57 +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 "modules/tools/visualizer/renderable_object.h" - -class Grid : public RenderableObject { - public: - explicit Grid(int cellCountBySide = 1); - ~Grid() {} - - GLenum GetPrimitiveType(void) const { return GL_LINES; } - void SetupExtraUniforms(void) { - QVector3D color; - color.setX(static_cast(grid_color_.redF())); - color.setY(static_cast(grid_color_.greenF())); - color.setZ(static_cast(grid_color_.blueF())); - shader_program_->setUniformValue("color", color); - } - - int red(void) const { return grid_color_.red(); } - int green(void) const { return grid_color_.green(); } - int blue(void) const { return grid_color_.blue(); } - - const QColor& grid_color(void) const { return grid_color_; } - void set_grid_color(const QColor& color) { grid_color_ = color; } - - void SetCellCount(int cellCount) { - set_vertex_count(((cellCount << 1) + 2) * vertex_element_count()); - } - - int CellCount(void) const { - return (vertex_count() / vertex_element_count() - 2) >> 1; - } - - protected: - virtual bool FillVertexBuffer(GLfloat* pBuffer); - - private: - QColor grid_color_; -}; diff --git a/modules/tools/visualizer/images/app.ico b/modules/tools/visualizer/images/app.ico deleted file mode 100644 index 5d35cb360ac..00000000000 Binary files a/modules/tools/visualizer/images/app.ico and /dev/null differ diff --git a/modules/tools/visualizer/images/closeimage.png b/modules/tools/visualizer/images/closeimage.png deleted file mode 100644 index d0eec21dd92..00000000000 Binary files a/modules/tools/visualizer/images/closeimage.png and /dev/null differ diff --git a/modules/tools/visualizer/images/grid.png b/modules/tools/visualizer/images/grid.png deleted file mode 100644 index 7864c043750..00000000000 Binary files a/modules/tools/visualizer/images/grid.png and /dev/null differ diff --git a/modules/tools/visualizer/images/image.png b/modules/tools/visualizer/images/image.png deleted file mode 100644 index 618c9ae17fc..00000000000 Binary files a/modules/tools/visualizer/images/image.png and /dev/null differ diff --git a/modules/tools/visualizer/images/images.png b/modules/tools/visualizer/images/images.png deleted file mode 100644 index ebefe6b67d1..00000000000 Binary files a/modules/tools/visualizer/images/images.png and /dev/null differ diff --git a/modules/tools/visualizer/images/no_image.png b/modules/tools/visualizer/images/no_image.png deleted file mode 100644 index 70dc08f01c8..00000000000 Binary files a/modules/tools/visualizer/images/no_image.png and /dev/null differ diff --git a/modules/tools/visualizer/images/pause.png b/modules/tools/visualizer/images/pause.png deleted file mode 100644 index 5f6a5973a75..00000000000 Binary files a/modules/tools/visualizer/images/pause.png and /dev/null differ diff --git a/modules/tools/visualizer/images/play.png b/modules/tools/visualizer/images/play.png deleted file mode 100644 index 36e3dcd77c2..00000000000 Binary files a/modules/tools/visualizer/images/play.png and /dev/null differ diff --git a/modules/tools/visualizer/images/pointcloud.png b/modules/tools/visualizer/images/pointcloud.png deleted file mode 100644 index f551f78d443..00000000000 Binary files a/modules/tools/visualizer/images/pointcloud.png and /dev/null differ diff --git a/modules/tools/visualizer/main.cc b/modules/tools/visualizer/main.cc deleted file mode 100644 index 5febae2f31f..00000000000 --- a/modules/tools/visualizer/main.cc +++ /dev/null @@ -1,83 +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 -#include -#include - -#include "modules/tools/visualizer/main_window.h" - -int main(int argc, char* argv[]) { - QApplication a(argc, argv); - int major, minor; - { - QOffscreenSurface surf; - surf.create(); - - QOpenGLContext ctx; - ctx.create(); - ctx.makeCurrent(&surf); - - std::stringstream strStreamObj; - strStreamObj << (const char*)ctx.functions()->glGetString( - GL_SHADING_LANGUAGE_VERSION); - double version; - strStreamObj >> version; - major = static_cast(version); - minor = static_cast(version * 10.0 - major * 10); - if (major < 3 && minor < 3) { - std::cout << "Shading Language Version ( " << version - << ") is much lower than 3.3" << std::endl; - return -1; - } - } - QSurfaceFormat format; - - format.setVersion(major, minor); - format.setRenderableType(QSurfaceFormat::RenderableType::OpenGL); - format.setSwapBehavior(QSurfaceFormat::SwapBehavior::DoubleBuffer); - QSurfaceFormat::setDefaultFormat(format); - - a.setStyleSheet( - "QSplitter::handle {" - " background: lightGray;" - " border-radius: 2px; " - "}"); - - apollo::cyber::Init(argv[0]); - - MainWindow w; - - auto topologyCallback = - [&w](const apollo::cyber::proto::ChangeMsg& change_msg) { - w.TopologyChanged(change_msg); - }; - - auto channelManager = - apollo::cyber::service_discovery::TopologyManager::Instance() - ->channel_manager(); - channelManager->AddChangeListener(topologyCallback); - - std::vector role_attr_vec; - channelManager->GetWriters(&role_attr_vec); - for (auto& role_attr : role_attr_vec) { - w.AddNewWriter(role_attr); - } - - w.show(); - - return a.exec(); -} diff --git a/modules/tools/visualizer/main_window.cc b/modules/tools/visualizer/main_window.cc deleted file mode 100644 index c1e72a08f8c..00000000000 --- a/modules/tools/visualizer/main_window.cc +++ /dev/null @@ -1,1237 +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 -#include -#include -#include -#include -#include - -#include "modules/tools/visualizer/fixedaspectratiowidget.h" -#include "modules/tools/visualizer/grid.h" -#include "modules/tools/visualizer/main_window.h" -#include "modules/tools/visualizer/pointcloud.h" -#include "modules/tools/visualizer/radarpoints.h" -#include "modules/tools/visualizer/ui_main_window.h" -#include "modules/tools/visualizer/video_images_dialog.h" - -namespace { -const char* globalTreeItemStyle = "margin-right:10px"; - -const char* aboutMessage = - "Cyber_Visualizer\n" - "\n" - "One Visualization Tool for Presenting Cyber Channel Data\n" - "\n" - "F5 Play | Pause\n" - "\n" - "Main View PointCloud view\n" - "All Views have right button Menu"; - -const char* licenseMessage = - "Copyright 2018 The Apollo Authors. All Rights Reserved.\n" - "\n" - "Licensed under the Apache License, Version 2.0 (the \"License\");\n" - "you may not use this file except in compliance with the License.\n" - "You may obtain a copy of the License at\n" - "\n" - "http://www.apache.org/licenses/LICENSE-2.0\n" - "\n" - "Unless required by applicable law or agreed to in writing, software\n" - "distributed under the License is distributed on an \"AS IS\" BASIS,\n" - "WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n" - "See the License for the specific language governing permissions and\n" - "limitations under the License.\n"; - -const char* pcTempObjGroupName = "pointcloud"; -const char* pcVertexPath = ":/shaders/pointcloud.vert"; -const char* pcFragPath = ":/shaders/grid_pointcloud.frag"; -const char* gridVertexPath = ":/shaders/grid.vert"; -const char* gridFragPath = ":/shaders/grid_pointcloud.frag"; -const char* radarVertexPath = ":/shaders/radarpoints.vert"; -const char* radarFragPath = ":/shaders/radarpoints.frag"; - -const std::string CompressedImageType("apollo.drivers.CompressedImage"); - -} // namespace - -#define MEMBER_OFFSET(StructType, Member) \ - (size_t)( \ - reinterpret_cast(&(reinterpret_cast(1)->Member)) - \ - 1) -#define StructPtrByMemberPtr(MemberPtr, StructType, Member) \ - reinterpret_cast(reinterpret_cast(MemberPtr) - \ - MEMBER_OFFSET(StructType, Member)) - -struct MainWindow::VideoImgProxy { - FixedAspectRatioWidget video_image_viewer_; - QTreeWidgetItem root_item_; - QTreeWidgetItem channel_name_item_; - QTreeWidgetItem action_item_; - - QComboBox channel_name_combobox_; - QPushButton action_item_button_; - - QMutex reader_mutex_; - std::shared_ptr dynamic_texture_; - bool isCompressedImage_; - union { - CyberChannReader* image_reader_; - CyberChannReader* - compressed_image_reader_; - }; - - VideoImgProxy() - : video_image_viewer_(), - root_item_(), - channel_name_item_(), - action_item_(), - channel_name_combobox_(), - action_item_button_(), - reader_mutex_(), - dynamic_texture_(), - isCompressedImage_(false), - image_reader_(nullptr) {} - - void deleteReader(void) { - if (image_reader_) { - if (isCompressedImage_) { - delete compressed_image_reader_; - } else { - delete image_reader_; - } - image_reader_ = nullptr; - isCompressedImage_ = false; - } - } - - void CloseChannel(void) { - if (isCompressedImage_) { - compressed_image_reader_->CloseChannel(); - } else { - image_reader_->CloseChannel(); - } - } - - ~VideoImgProxy(void) { - dynamic_texture_.reset(); - deleteReader(); - } -}; - -struct MainWindow::RadarData { - QTreeWidgetItem root_item_; - QTreeWidgetItem channel_name_item_; - QTreeWidgetItem action_item_; - - QComboBox channel_name_combobox_; - QPushButton action_item_button_; - QCheckBox enable_checkBox_; - - QMutex reader_mutex_; - - CyberChannReader* channel_reader_; - - RadarData(void) - : root_item_(), - channel_name_item_(), - action_item_(), - channel_name_combobox_(), - action_item_button_(), - enable_checkBox_(), - reader_mutex_(), - channel_reader_(nullptr) {} - - ~RadarData(void) { - if (channel_reader_) { - delete channel_reader_; - channel_reader_ = nullptr; - } - } -}; - -MainWindow::MainWindow(QWidget* parent) - : QMainWindow(parent), - ui_(new Ui::MainWindow), - msg_dialog_(new MessageDialog), - open_images_dialog_(nullptr), - - grid_(nullptr), - enable_grid_checkBox_(nullptr), - grid_root_item_(nullptr), - - pointcloud_top_item_(nullptr), - pointcloud_comboBox_(new QComboBox), - pointcloud_button_(new QPushButton), - pointcloud_channel_Reader_(nullptr), - - pointcloud_reader_mutex_(), - - pointcloud_shader_(nullptr), - grid_shader_(nullptr), - radar_points_shader_(nullptr), - video_image_viewer_list_(), - closed_video_image_viewer_list_(), - radarData_list_(), - closed_radarData_list_(), - _channelName2TypeMap() { - ui_->setupUi(this); - ui_->videoImageGridLayout->setContentsMargins(2, 2, 2, 2); - ui_->videoImageWidget->setVisible(false); - - ui_->mainToolBar->addAction(ui_->actionAddGrid); - ui_->mainToolBar->addAction(ui_->actionPointCloud); - ui_->mainToolBar->addSeparator(); - ui_->mainToolBar->addAction(ui_->actionOpenImage); - ui_->mainToolBar->addAction(ui_->actionOpenImages); - ui_->mainToolBar->addAction(ui_->actionDelImage); - ui_->mainToolBar->addSeparator(); - ui_->mainToolBar->addAction(ui_->actionPlay); - ui_->mainToolBar->addAction(ui_->actionPause); - - pointcloud_reader_mutex_.lock(); - - { - QStringList tmp; - tmp << "ChannelNames" - << " "; - all_channel_root_ = new QTreeWidgetItem(tmp); - ui_->treeWidget->addTopLevelItem(all_channel_root_); - } - - connect(ui_->actionAbout, SIGNAL(triggered(bool)), this, SLOT(showMessage())); - connect(ui_->actionLicense, SIGNAL(triggered(bool)), this, - SLOT(showMessage())); - - pointcloud_button_->setCheckable(true); - pointcloud_button_->setStyleSheet(globalTreeItemStyle); - pointcloud_comboBox_->setStyleSheet(globalTreeItemStyle); - - connect(pointcloud_button_, SIGNAL(clicked(bool)), this, - SLOT(PlayRenderableObject(bool))); - connect(pointcloud_comboBox_, SIGNAL(currentIndexChanged(int)), this, - SLOT(ChangePointCloudChannel())); - - connect(ui_->treeWidget, SIGNAL(itemSelectionChanged()), this, - SLOT(UpdateActions())); - connect(ui_->treeWidget, SIGNAL(visibilityChanged(bool)), ui_->actionGlobal, - SLOT(setChecked(bool))); - connect(ui_->actionPlay, SIGNAL(triggered(bool)), this, SLOT(PlayPause())); - connect(ui_->actionPause, SIGNAL(triggered(bool)), this, SLOT(PlayPause())); -} - -MainWindow::~MainWindow() { - for (VideoImgProxy* item : video_image_viewer_list_) { - item->reader_mutex_.unlock(); - } - for (VideoImgProxy* item : closed_video_image_viewer_list_) { - item->reader_mutex_.unlock(); - } - for (RadarData* item : radarData_list_) { - item->reader_mutex_.unlock(); - } - for (RadarData* item : closed_radarData_list_) { - item->reader_mutex_.unlock(); - } - - pointcloud_reader_mutex_.unlock(); - - if (pointcloud_channel_Reader_) { - delete pointcloud_channel_Reader_; - pointcloud_channel_Reader_ = nullptr; - } - - for (VideoImgProxy* item : video_image_viewer_list_) { - delete item; - } - - for (VideoImgProxy* item : closed_video_image_viewer_list_) { - delete item; - } - - for (RadarData* item : radarData_list_) { - delete item; - } - - for (RadarData* item : closed_radarData_list_) { - delete item; - } - - delete ui_; - delete msg_dialog_; -} - -void MainWindow::calculateWH(void) { - int count = video_image_viewer_list_.count(); - - if (count > 0) { - QSize wh; - wh.setWidth(ui_->sceneWidget->width() - count * 2 + 2); - wh.setHeight(50); - wh.setWidth(wh.width() / count); - int index = 0; - - for (VideoImgProxy* p : video_image_viewer_list_) { - p->video_image_viewer_.setMinimumSize(wh); - ui_->videoImageGridLayout->removeWidget(&p->video_image_viewer_); - ui_->videoImageGridLayout->addWidget(&p->video_image_viewer_, index / 3, - index % 3, 1, 1); - ++index; - } - ui_->videoImageWidget->adjustSize(); - } -} - -MainWindow::VideoImgProxy* MainWindow::AddVideoImgViewer() { - std::shared_ptr tex(new Texture); - if (tex == nullptr) { - return nullptr; - } - VideoImgProxy* ret = new VideoImgProxy(); - - if (ret) { - int index = video_image_viewer_list_.count(); - ret->video_image_viewer_.set_index(index); - - ret->video_image_viewer_.setStyleSheet("background-color:black;"); - ret->video_image_viewer_.setVisible(false); - - QString imgName = tr("Camera%1").arg(index); - - ret->root_item_.setHidden(true); - ret->root_item_.setText(0, imgName); - ret->root_item_.setText(1, ""); - - ret->channel_name_item_.setText(0, "ChannelName"); - ret->action_item_.setText(0, "Action"); - - ret->action_item_button_.setObjectName(tr("pushButton%1").arg(index)); - ret->action_item_button_.setText("Play"); - ret->action_item_button_.setCheckable(true); - ret->action_item_button_.setStyleSheet(globalTreeItemStyle); - - ret->channel_name_combobox_.setObjectName(tr("comboBox%1").arg(index)); - ret->channel_name_combobox_.setStyleSheet(globalTreeItemStyle); - - ret->root_item_.addChild(&ret->channel_name_item_); - ret->root_item_.addChild(&ret->action_item_); - - ret->dynamic_texture_ = tex; - ret->video_image_viewer_.SetupDynamicTexture(tex); - - ret->video_image_viewer_.setSizePolicy(QSizePolicy::Preferred, - QSizePolicy::Preferred); - ret->video_image_viewer_.addAction(ui_->actionDelImage); - ret->reader_mutex_.lock(); - } - return ret; -} - -MainWindow::RadarData* MainWindow::createRadarData(void) { - RadarData* ret = new RadarData(); - - if (ret) { - int index = radarData_list_.count(); - QString radarName = tr("Radar%1").arg(index); - - ret->root_item_.setHidden(true); - ret->root_item_.setText(0, radarName); - - ret->channel_name_item_.setText(0, "ChannelName"); - ret->action_item_.setText(0, "Action"); - ret->enable_checkBox_.setChecked(true); - - ret->action_item_button_.setText("Play"); - ret->action_item_button_.setCheckable(true); - ret->action_item_button_.setStyleSheet(globalTreeItemStyle); - - ret->channel_name_combobox_.setObjectName(tr("comboBox%1").arg(index)); - ret->channel_name_combobox_.setStyleSheet(globalTreeItemStyle); - - ret->root_item_.addChild(&ret->channel_name_item_); - ret->root_item_.addChild(&ret->action_item_); - ret->reader_mutex_.lock(); - } - return ret; -} - -void MainWindow::EnableGrid(bool b) { grid_->set_is_renderable(b); } - -void MainWindow::ActionAddGrid(void) { - if (grid_shader_ == nullptr) { - grid_shader_ = RenderableObject::CreateShaderProgram(tr(gridVertexPath), - tr(gridFragPath)); - if (grid_shader_ != nullptr) { - ui_->sceneWidget->AddNewShaderProg("grid", grid_shader_); - } - } - - if (grid_root_item_ == nullptr) { - QTreeWidgetItem* colorChild = nullptr; - QTreeWidgetItem* cellCountChild = nullptr; - QSpinBox* spinbox = nullptr; - - grid_ = new Grid(6); - if (grid_ == nullptr) { - goto _ret1; - } - - if (grid_shader_ == nullptr) { - goto _ret2; - } - - enable_grid_checkBox_ = new QCheckBox(ui_->treeWidget); - if (enable_grid_checkBox_ == nullptr) { - goto _ret2; - } - - grid_root_item_ = new QTreeWidgetItem(ui_->treeWidget); - if (grid_root_item_ == nullptr) { - goto _ret3; - } - - colorChild = new QTreeWidgetItem(grid_root_item_); - if (colorChild == nullptr) { - goto _ret4; - } - grid_root_item_->addChild(colorChild); - colorChild->setText(0, "Color"); - colorChild->setText(1, tr("%1;%2;%3") - .arg(grid_->red()) - .arg(grid_->green()) - .arg(grid_->blue())); - - spinbox = new QSpinBox(ui_->treeWidget); - if (spinbox == nullptr) { - goto _ret5; - } - spinbox->setMinimum(1); - spinbox->setMaximum(100); - spinbox->setSingleStep(1); - spinbox->setValue(grid_->CellCount()); - spinbox->setStyleSheet(globalTreeItemStyle); - - cellCountChild = new QTreeWidgetItem(grid_root_item_); - if (cellCountChild == nullptr) { - goto _ret6; - } - grid_root_item_->addChild(cellCountChild); - cellCountChild->setText(0, "CellCount"); - - grid_->set_shader_program(grid_shader_); - if (!ui_->sceneWidget->AddPermanentRenderObj(grid_)) { - goto _ret7; - } - - enable_grid_checkBox_->setText("Enable"); - enable_grid_checkBox_->setChecked(true); - grid_root_item_->setText(0, "Grid"); - grid_root_item_->setText(1, ""); - - ui_->treeWidget->addTopLevelItem(grid_root_item_); - - ui_->treeWidget->setItemWidget(grid_root_item_, 1, enable_grid_checkBox_); - ui_->treeWidget->setItemWidget(cellCountChild, 1, spinbox); - - connect(enable_grid_checkBox_, SIGNAL(clicked(bool)), this, - SLOT(EnableGrid(bool))); - connect(ui_->treeWidget, SIGNAL(itemDoubleClicked(QTreeWidgetItem*, int)), - this, SLOT(EditGridColor(QTreeWidgetItem*, int))); - connect(spinbox, SIGNAL(valueChanged(int)), this, - SLOT(ChangeGridCellCountBySize(int))); - return; - - _ret7: - delete cellCountChild; - _ret6: - delete spinbox; - _ret5: - delete colorChild; - _ret4: - delete grid_root_item_; - _ret3: - delete enable_grid_checkBox_; - _ret2: - delete grid_; - _ret1: - QMessageBox::warning(this, tr("Error"), - tr("There is no enough memory for creating Grid!!!"), - QMessageBox::Ok); - return; - } -} - -void MainWindow::ChangeGridCellCountBySize(int v) { - grid_->Destroy(); - grid_->set_shader_program(grid_shader_); - grid_->SetCellCount(v); - grid_->set_is_renderable(true); -} - -void MainWindow::EditGridColor(QTreeWidgetItem* item, int column) { - if (column && item != nullptr && grid_root_item_ != nullptr && - item == grid_root_item_->child(0)) { - QStringList rgb = item->text(1).split(';'); - QColor color(rgb.at(0).toInt(), rgb.at(1).toInt(), rgb.at(2).toInt()); - - color = QColorDialog::getColor(color, nullptr, tr("set grid color")); - - if (color.isValid()) { - QString str = - tr("%1;%2;%3").arg(color.red()).arg(color.green()).arg(color.blue()); - item->setText(1, str); - - grid_->set_grid_color(color); - } - } -} - -void MainWindow::EnableRadarPoints(bool b) { - QCheckBox* obj = static_cast(sender()); - RadarData* r = StructPtrByMemberPtr(obj, RadarData, enable_checkBox_); - ui_->sceneWidget->setTempObjGroupEnabled(r->root_item_.text(0).toStdString(), - b); -} - -void MainWindow::ActionOpenRadarChannel(void) { - if (radar_points_shader_ == nullptr) { - radar_points_shader_ = RenderableObject::CreateShaderProgram( - tr(radarVertexPath), tr(radarFragPath)); - if (radar_points_shader_ != nullptr) { - ui_->sceneWidget->AddNewShaderProg("radarpoints", radar_points_shader_); - } else { - QMessageBox::warning( - this, tr("NO Shader"), - tr("There is no suitable shader for Radar Points!!!"), - QMessageBox::Ok); - return; - } - } - - RadarData* radarProxy; - - if (closed_radarData_list_.empty()) { - radarProxy = createRadarData(); - - if (radarProxy == nullptr) { - QMessageBox::warning(this, tr("No Enough Memory"), - tr("There is no enough memory!!!\nCannot add new " - "image or video channel!"), - QMessageBox::Ok); - return; - } - - ui_->treeWidget->addTopLevelItem(&radarProxy->root_item_); - ui_->treeWidget->setItemWidget(&radarProxy->root_item_, 1, - &radarProxy->enable_checkBox_); - - ui_->treeWidget->setItemWidget(&radarProxy->channel_name_item_, 1, - &radarProxy->channel_name_combobox_); - ui_->treeWidget->setItemWidget(&radarProxy->action_item_, 1, - &radarProxy->action_item_button_); - - for (int i = 0; i < all_channel_root_->childCount(); ++i) { - QTreeWidgetItem* child = all_channel_root_->child(i); - QString channel = child->text(0); - if (channel.contains("radar")) { - radarProxy->channel_name_combobox_.addItem(channel); - } - } - } else { - radarProxy = closed_radarData_list_.takeFirst(); - } - - connect(&radarProxy->action_item_button_, SIGNAL(clicked(bool)), this, - SLOT(openRadarChannel(bool))); - connect(&radarProxy->enable_checkBox_, SIGNAL(clicked(bool)), this, - SLOT(EnableRadarPoints(bool))); - connect(&radarProxy->channel_name_combobox_, SIGNAL(currentIndexChanged(int)), - this, SLOT(ChangeRadarChannel())); - - radarData_list_.append(radarProxy); - - radarProxy->root_item_.setHidden(false); - - ui_->treeWidget->setVisible(true); - ui_->actionGlobal->setChecked(true); -} - -void MainWindow::openRadarChannel(bool b) { - QPushButton* obj = static_cast(QObject::sender()); - RadarData* theVideoImg = - StructPtrByMemberPtr(obj, RadarData, action_item_button_); - DoOpenRadarChannel(b, theVideoImg); -} - -void MainWindow::DoOpenRadarChannel(bool b, RadarData* radarProxy) { - if (b) { - if (radarProxy->channel_name_combobox_.currentText().isEmpty()) { - QMessageBox::warning( - this, tr("Setup Channel Name"), - tr("Channel Name cannot be empty!!!\nPlease select one!"), - QMessageBox::Ok); - radarProxy->action_item_button_.setChecked(false); - return; - } - - if (!radarProxy->channel_reader_) { - radarProxy->channel_reader_ = - new CyberChannReader(); - - if (!radarProxy->channel_reader_) { - QMessageBox::warning(this, tr("Create cyber Channel Reader"), - tr("There is no enough memory!!!\nCannot create " - "cyber channel reader!"), - QMessageBox::Ok); - return; - } - - auto radarcallback = - [this, radarProxy]( - const std::shared_ptr& pdata) { - this->RadarRenderCallback(pdata, radarProxy); - }; - - std::string nodeName("Visualizer-"); - nodeName.append(radarProxy->root_item_.text(0).toStdString()); - - if (!radarProxy->channel_reader_->InstallCallbackAndOpen( - radarcallback, - radarProxy->channel_name_combobox_.currentText().toStdString(), - nodeName)) { - QMessageBox::warning( - this, tr("Setup Channel Callback"), - tr("Channel Callback cannot be installed!!!\nPlease check it!"), - QMessageBox::Ok); - delete radarProxy->channel_reader_; - radarProxy->channel_reader_ = nullptr; - - radarProxy->action_item_button_.setChecked(false); - return; - } - } - - radarProxy->root_item_.setToolTip( - 0, radarProxy->channel_name_combobox_.currentText()); - - radarProxy->action_item_button_.setText("Stop"); - radarProxy->channel_name_combobox_.setEnabled(false); - - radarProxy->reader_mutex_.unlock(); - } else { - if (!radarProxy->channel_name_combobox_.isEnabled()) { - radarProxy->reader_mutex_.lock(); - radarProxy->action_item_button_.setText("Play"); - radarProxy->channel_name_combobox_.setEnabled(true); - } - } - ui_->treeWidget->setCurrentItem(nullptr); - ui_->treeWidget->clearFocus(); -} - -void MainWindow::RadarRenderCallback( - const std::shared_ptr& rawData, - RadarData* radar) { - radar->reader_mutex_.lock(); - radar->reader_mutex_.unlock(); - - std::cout << "-------MainWindow::RadarRenderCallback()-------" << std::endl; - - if (rawData != nullptr) { - RadarPoints* r = new RadarPoints(radar_points_shader_); - if (r) { - if (!r->FillData(rawData) || - !ui_->sceneWidget->AddTempRenderableObj( - radar->root_item_.text(0).toStdString(), r)) { - delete r; - } - } else { - std::cerr << "cannot create RadarPoints Renderable Object" << std::endl; - } - } -} - -void MainWindow::ActionOpenPointCloud(void) { - if (pointcloud_shader_ == nullptr) { - pointcloud_shader_ = - RenderableObject::CreateShaderProgram(tr(pcVertexPath), tr(pcFragPath)); - if (pointcloud_shader_ != nullptr) { - ui_->sceneWidget->AddNewShaderProg("pointcloud", pointcloud_shader_); - } else { - QMessageBox::warning(this, tr("NO Shader"), - tr("There is no suitable shader for Pointcloud!!!"), - QMessageBox::Ok); - return; - } - } - - if (pointcloud_top_item_ == nullptr) { - pointcloud_top_item_ = new QTreeWidgetItem(ui_->treeWidget); - if (pointcloud_top_item_ == nullptr) { - return; - } - - pointcloud_top_item_->setText(0, "PointCloud2"); - pointcloud_top_item_->setText(1, ""); - - QTreeWidgetItem* item = new QTreeWidgetItem(pointcloud_top_item_); - if (item == nullptr) { - QMessageBox::warning(this, tr("NO Enough Memory"), - tr("Cannot create tree item for channel name!!!"), - QMessageBox::Ok); - return; - } - - item->setText(0, "ChannelName"); - ui_->treeWidget->setItemWidget(item, 1, pointcloud_comboBox_); - - item = new QTreeWidgetItem(pointcloud_top_item_); - if (item == nullptr) { - QMessageBox::warning(this, tr("NO Enough Memory"), - tr("Cannot create tree item for channel Action!!!"), - QMessageBox::Ok); - return; - } - - item->setText(0, "Action"); - - pointcloud_button_->setText("Play"); - ui_->treeWidget->setItemWidget(item, 1, pointcloud_button_); - - ui_->treeWidget->setVisible(true); - ui_->actionGlobal->setChecked(true); - } -} - -void MainWindow::ActionOpenImages(void) { - if (open_images_dialog_ == nullptr) { - open_images_dialog_ = new VideoImagesDialog(this); - if (open_images_dialog_ == nullptr) { - QMessageBox::warning(this, tr("No Enough Memory"), - tr("There is no enough memory!!!"), QMessageBox::Ok); - return; - } else { - connect(open_images_dialog_, SIGNAL(accepted()), this, - SLOT(AddVideoImages())); - } - } - - open_images_dialog_->show(); -} - -void MainWindow::AddVideoImages(void) { - int count = open_images_dialog_->count(); - while (count) { - ActionOpenImage(); - --count; - } -} - -void MainWindow::ActionOpenImage(void) { - VideoImgProxy* videoImgProxy; - - if (closed_video_image_viewer_list_.empty()) { - videoImgProxy = AddVideoImgViewer(); - - if (videoImgProxy == nullptr) { - QMessageBox::warning(this, tr("No Enough Memory"), - tr("There is no enough memory!!!\nCannot add new " - "image or video channel!"), - QMessageBox::Ok); - return; - } - - videoImgProxy->video_image_viewer_.setParent(ui_->videoImageWidget); - - ui_->treeWidget->addTopLevelItem(&videoImgProxy->root_item_); - ui_->treeWidget->setItemWidget(&videoImgProxy->channel_name_item_, 1, - &videoImgProxy->channel_name_combobox_); - ui_->treeWidget->setItemWidget(&videoImgProxy->action_item_, 1, - &videoImgProxy->action_item_button_); - - for (int i = 0; i < all_channel_root_->childCount(); ++i) { - QTreeWidgetItem* child = all_channel_root_->child(i); - QString channel = child->text(0); - if (channel.contains("camera")) { - videoImgProxy->channel_name_combobox_.addItem(channel); - } - } - } else { - videoImgProxy = closed_video_image_viewer_list_.takeFirst(); - } - - connect(&videoImgProxy->action_item_button_, SIGNAL(clicked(bool)), this, - SLOT(PlayVideoImage(bool))); - connect(&videoImgProxy->channel_name_combobox_, - SIGNAL(currentIndexChanged(int)), this, - SLOT(ChangeVideoImgChannel())); - connect(&videoImgProxy->video_image_viewer_, - SIGNAL(focusOnThis(FixedAspectRatioWidget*)), this, - SLOT(SelectCurrentTreeItem(FixedAspectRatioWidget*))); - - video_image_viewer_list_.append(videoImgProxy); - videoImgProxy->video_image_viewer_.setVisible(true); - - calculateWH(); - - videoImgProxy->video_image_viewer_.StartOrStopUpdate(true); - videoImgProxy->root_item_.setHidden(false); - - ui_->videoImageWidget->setVisible(true); - - ui_->treeWidget->setVisible(true); - ui_->actionGlobal->setChecked(true); - - repaint(); -} - -void MainWindow::ActionDelVideoImage(void) { - QTreeWidgetItem* topItem = ui_->treeWidget->currentItem(); - VideoImgProxy* proxy = - StructPtrByMemberPtr(topItem, VideoImgProxy, root_item_); - - DoDeleteVideoImg(proxy); - ui_->actionDelImage->setEnabled(false); -} - -void MainWindow::CloseVideoImgViewer(bool b) { - if (!b) { - VideoImgViewer* dock = static_cast(sender()); - DoDeleteVideoImg( - StructPtrByMemberPtr(dock, VideoImgProxy, video_image_viewer_)); - } -} - -void MainWindow::DoDeleteVideoImg(VideoImgProxy* proxy) { - disconnect(&proxy->action_item_button_, SIGNAL(clicked(bool)), this, - SLOT(PlayVideoImage(bool))); - disconnect(&proxy->channel_name_combobox_, SIGNAL(currentIndexChanged(int)), - this, SLOT(ChangeVideoImgChannel())); - disconnect(&proxy->video_image_viewer_, - SIGNAL(focusOnThis(FixedAspectRatioWidget*)), this, - SLOT(SelectCurrentTreeItem(FixedAspectRatioWidget*))); - - proxy->action_item_button_.setChecked(false); - DoPlayVideoImage(false, proxy); - - proxy->video_image_viewer_.StartOrStopUpdate(false); - proxy->root_item_.setHidden(true); - proxy->video_image_viewer_.setVisible(false); - ui_->videoImageGridLayout->removeWidget(&proxy->video_image_viewer_); - - video_image_viewer_list_.removeOne(proxy); - closed_video_image_viewer_list_.append(proxy); - - if (video_image_viewer_list_.count()) { - calculateWH(); - } else { - ui_->videoImageWidget->setVisible(false); - } -} - -void MainWindow::UpdateActions(void) { - QTreeWidgetItem* item = ui_->treeWidget->currentItem(); - ui_->actionDelImage->setEnabled(false); - if (item) { - if (!item->parent() && item != pointcloud_top_item_ && - item != all_channel_root_ && item != grid_root_item_) { - ui_->actionDelImage->setEnabled(true); - } - } -} - -void MainWindow::PointCloudReaderCallback( - const std::shared_ptr& pdata) { - pointcloud_reader_mutex_.lock(); - pointcloud_reader_mutex_.unlock(); - PointCloud* pc = new PointCloud(pdata->point_size(), 4, pointcloud_shader_); - if (pc) { - if (!pc->FillData(pdata) || - !ui_->sceneWidget->AddTempRenderableObj(pcTempObjGroupName, pc)) { - delete pc; - } - } else { - std::cerr << "-----Cannot create PointCloud----------" << std::endl; - } -} - -void MainWindow::PlayRenderableObject(bool b) { - if (b) { - if (pointcloud_comboBox_->currentText().isEmpty()) { - QMessageBox::warning( - this, tr("Setup Channel Name"), - tr("Channel Name cannot be empty!!!\nPlease Select it!"), - QMessageBox::Ok); - pointcloud_button_->setChecked(false); - return; - } - - if (!pointcloud_channel_Reader_) { - pointcloud_channel_Reader_ = - new CyberChannReader(); - - if (!pointcloud_channel_Reader_) { - QMessageBox::warning(this, tr("Create Cyber Channel Reader"), - tr("There is no enough memory!!!\nCannot create " - "cyber channel reader!"), - QMessageBox::Ok); - pointcloud_button_->setChecked(false); - return; - } - - auto pointCallback = - [this](const std::shared_ptr& pdata) { - this->PointCloudReaderCallback(pdata); - }; - std::string nodeName("Visualizer-"); - nodeName.append(pointcloud_top_item_->text(0).toStdString()); - if (!pointcloud_channel_Reader_->InstallCallbackAndOpen( - pointCallback, pointcloud_comboBox_->currentText().toStdString(), - nodeName)) { - QMessageBox::warning( - this, tr("Setup Channel Callback"), - tr("Channel Callback cannot be installed!!!\nPlease check it!"), - QMessageBox::Ok); - delete pointcloud_channel_Reader_; - pointcloud_channel_Reader_ = nullptr; - - pointcloud_button_->setChecked(false); - return; - } - } - - ui_->sceneWidget->setToolTip(pointcloud_comboBox_->currentText()); - pointcloud_top_item_->setToolTip(0, pointcloud_comboBox_->currentText()); - pointcloud_comboBox_->setEnabled(false); - pointcloud_button_->setText(tr("Stop")); - - pointcloud_reader_mutex_.unlock(); - } else { - if (!pointcloud_comboBox_->isEnabled()) { - pointcloud_reader_mutex_.lock(); - pointcloud_comboBox_->setEnabled(true); - pointcloud_button_->setText(tr("Show")); - } - } - - ui_->treeWidget->setCurrentItem(nullptr); - ui_->treeWidget->clearFocus(); -} - -void MainWindow::ImageReaderCallback( - const std::shared_ptr& imgData, - VideoImgProxy* theVideoImgProxy) { - theVideoImgProxy->reader_mutex_.lock(); - if (theVideoImgProxy->dynamic_texture_ != nullptr && imgData != nullptr) { - if (theVideoImgProxy->dynamic_texture_->UpdateData(imgData)) { - theVideoImgProxy->video_image_viewer_.SetupDynamicTexture( - theVideoImgProxy->dynamic_texture_); - } else { - std::cerr << "--------Cannot update dynamic Texture Data--------" - << std::endl; - } - } else { - std::cerr - << "----Dynamic Texture is nullptr or apollo.drivers.Image is nullptr" - << std::endl; - } - theVideoImgProxy->reader_mutex_.unlock(); -} - -void MainWindow::ImageReaderCallback( - const std::shared_ptr& imgData, - VideoImgProxy* theVideoImgProxy) { - theVideoImgProxy->reader_mutex_.lock(); - if (theVideoImgProxy->dynamic_texture_ != nullptr && imgData != nullptr) { - QImage img; - const std::string& data = imgData->data(); - if (img.loadFromData(reinterpret_cast(data.c_str()), - static_cast(data.size()))) { - if (theVideoImgProxy->dynamic_texture_->UpdateData(img)) { - theVideoImgProxy->video_image_viewer_.SetupDynamicTexture( - theVideoImgProxy->dynamic_texture_); - } else { - std::cerr << "--------Cannot update dynamic Texture Data--------" - << std::endl; - } - } else { - std::cerr - << "-----------Cannot load compressed image from data with QImage" - << std::endl; - } - } else { - std::cerr - << "----Dynamic Texture is nullptr or apollo.drivers.Image is nullptr" - << std::endl; - } - theVideoImgProxy->reader_mutex_.unlock(); -} - -void MainWindow::PlayVideoImage(bool b) { - QPushButton* obj = static_cast(QObject::sender()); - VideoImgProxy* theVideoImg = - StructPtrByMemberPtr(obj, VideoImgProxy, action_item_button_); - DoPlayVideoImage(b, theVideoImg); -} - -void MainWindow::DoPlayVideoImage(bool b, VideoImgProxy* theVideoImg) { - if (b) { - if (theVideoImg->channel_name_combobox_.currentText().isEmpty()) { - QMessageBox::warning( - this, tr("Setup Channel Name"), - tr("Channel Name cannot be empty!!!\nPlease select one!"), - QMessageBox::Ok); - theVideoImg->action_item_button_.setChecked(false); - return; - } - - const std::string channelName = - theVideoImg->channel_name_combobox_.currentText().toStdString(); - if (_channelName2TypeMap[channelName] == CompressedImageType) - theVideoImg->isCompressedImage_ = true; - - if (!theVideoImg->image_reader_) { - if (theVideoImg->isCompressedImage_) { - theVideoImg->compressed_image_reader_ = - new CyberChannReader(); - } else { - theVideoImg->image_reader_ = - new CyberChannReader(); - } - - if (!theVideoImg->image_reader_) { - QMessageBox::warning(this, tr("Create cyber Channel Reader"), - tr("There is no enough memory!!!\nCannot create " - "cyber channel reader!"), - QMessageBox::Ok); - return; - } - - std::string nodeName("Visualizer-"); - nodeName.append(theVideoImg->root_item_.text(0).toStdString()); - - bool ret = false; - - if (theVideoImg->isCompressedImage_) { - auto videoCallback = - [this, theVideoImg]( - const std::shared_ptr& - pdata) { this->ImageReaderCallback(pdata, theVideoImg); }; - - ret = theVideoImg->compressed_image_reader_->InstallCallbackAndOpen( - videoCallback, channelName, nodeName); - } else { - auto videoCallback = - [this, theVideoImg]( - const std::shared_ptr& pdata) { - this->ImageReaderCallback(pdata, theVideoImg); - }; - ret = theVideoImg->image_reader_->InstallCallbackAndOpen( - videoCallback, channelName, nodeName); - } - if (!ret) { - QMessageBox::warning( - this, tr("Setup Channel Callback"), - tr("Channel Callback cannot be installed!!!\nPlease check it!"), - QMessageBox::Ok); - - theVideoImg->deleteReader(); - theVideoImg->action_item_button_.setChecked(false); - return; - } - } - - theVideoImg->root_item_.setToolTip( - 0, theVideoImg->channel_name_combobox_.currentText()); - theVideoImg->video_image_viewer_.setToolTip( - theVideoImg->channel_name_combobox_.currentText()); - - theVideoImg->action_item_button_.setText("Stop"); - theVideoImg->channel_name_combobox_.setEnabled(false); - - theVideoImg->reader_mutex_.unlock(); - } else { - if (!theVideoImg->channel_name_combobox_.isEnabled()) { - theVideoImg->reader_mutex_.lock(); - theVideoImg->action_item_button_.setText("Play"); - theVideoImg->channel_name_combobox_.setEnabled(true); - } - } - ui_->treeWidget->setCurrentItem(nullptr); - ui_->treeWidget->clearFocus(); -} - -void MainWindow::ChangePointCloudChannel() { - if (pointcloud_channel_Reader_ != nullptr) { - pointcloud_channel_Reader_->CloseChannel(); - std::string nodeName("Visualizer-"); - nodeName.append(pointcloud_top_item_->text(0).toStdString()); - pointcloud_channel_Reader_->OpenChannel( - pointcloud_comboBox_->currentText().toStdString(), nodeName); - } -} - -void MainWindow::ChangeVideoImgChannel() { - QComboBox* obj = static_cast(QObject::sender()); - VideoImgProxy* theVideoImg = - StructPtrByMemberPtr(obj, VideoImgProxy, channel_name_combobox_); - - if (theVideoImg->image_reader_ != nullptr) { - theVideoImg->deleteReader(); - } -} - -void MainWindow::ChangeRadarChannel(void) { - QComboBox* obj = static_cast(QObject::sender()); - RadarData* radar = - StructPtrByMemberPtr(obj, RadarData, channel_name_combobox_); - - if (radar->channel_reader_ != nullptr) { - radar->channel_reader_->CloseChannel(); - std::string nodeName("Visualizer-"); - nodeName.append(radar->root_item_.text(0).toStdString()); - radar->channel_reader_->OpenChannel(obj->currentText().toStdString(), - nodeName); - } -} - -void MainWindow::SelectCurrentTreeItem(FixedAspectRatioWidget* dock) { - if (dock) { - VideoImgProxy* theVideoImg = - StructPtrByMemberPtr(dock, VideoImgProxy, video_image_viewer_); - theVideoImg->root_item_.setExpanded(true); - if (ui_->treeWidget->currentItem() == &theVideoImg->root_item_) { - ui_->actionDelImage->setEnabled(true); - } else { - ui_->treeWidget->setCurrentItem(&theVideoImg->root_item_); - } - ui_->treeWidget->setFocus(); - } -} - -void MainWindow::TopologyChanged( - const apollo::cyber::proto::ChangeMsg& changeMsg) { - if (apollo::cyber::proto::ChangeType::CHANGE_CHANNEL == - changeMsg.change_type() && - apollo::cyber::proto::RoleType::ROLE_WRITER == changeMsg.role_type() && - apollo::cyber::proto::OperateType::OPT_JOIN == changeMsg.operate_type()) { - AddNewWriter(changeMsg.role_attr()); - } -} - -void MainWindow::AddNewWriter( - const apollo::cyber::proto::RoleAttributes& role) { - const std::string& channelName = role.channel_name(); - if (_channelName2TypeMap.find(channelName) != _channelName2TypeMap.end()) { - return; - } - const std::string& msgTypeName = role.message_type(); - _channelName2TypeMap[channelName] = msgTypeName; - - QTreeWidgetItem* child = new QTreeWidgetItem(); - if (child == nullptr) { - QMessageBox::warning(this, tr("Error"), tr("No Enough for New Channel!!!"), - QMessageBox::Ok); - return; - } - - QString str(channelName.c_str()); - child->setText(0, str); - child->setToolTip(0, str); - - bool b = true; - for (int i = 0; i < all_channel_root_->childCount(); ++i) { - if (str < all_channel_root_->child(i)->text(0)) { - all_channel_root_->insertChild(i, child); - b = false; - } - } - - if (b) { - all_channel_root_->addChild(child); - } - ui_->treeWidget->setRootIsDecorated(true); - - QString msgType(msgTypeName.c_str()); - if (msgType.contains("camera", Qt::CaseInsensitive)) { - for (VideoImgProxy* item : video_image_viewer_list_) { - item->channel_name_combobox_.addItem(str); - } - - for (VideoImgProxy* item : closed_video_image_viewer_list_) { - item->channel_name_combobox_.addItem(str); - } - } - - if (msgType.contains("pointcloud", Qt::CaseInsensitive)) { - pointcloud_comboBox_->addItem(str); - } - - if (msgType.contains("radar", Qt::CaseInsensitive)) { - for (RadarData* item : radarData_list_) { - item->channel_name_combobox_.addItem(str); - } - - for (RadarData* item : closed_radarData_list_) { - item->channel_name_combobox_.addItem(str); - } - } -} - -void MainWindow::PlayPause(void) { - QObject* obj = QObject::sender(); - bool b = true; - if (obj == ui_->actionPause) { - b = false; - } - if (pointcloud_top_item_) { - pointcloud_button_->setChecked(b); - PlayRenderableObject(b); - } - for (VideoImgProxy* p : video_image_viewer_list_) { - p->action_item_button_.setChecked(b); - DoPlayVideoImage(b, p); - } - for (RadarData* item : radarData_list_) { - item->action_item_button_.setChecked(b); - DoOpenRadarChannel(b, item); - } -} - -void MainWindow::resizeEvent(QResizeEvent* event) { - QMainWindow::resizeEvent(event); - calculateWH(); -} - -void MainWindow::showMessage() { - QObject* obj = QObject::sender(); - - if (obj == ui_->actionAbout) { - msg_dialog_->setWindowTitle(tr("About")); - msg_dialog_->setMessage(aboutMessage); - goto showMsgLabel; - } - - if (obj == ui_->actionLicense) { - msg_dialog_->setWindowTitle(tr("License")); - msg_dialog_->setMessage(licenseMessage); - - showMsgLabel: - msg_dialog_->adjustSize(); - msg_dialog_->show(); - } -} diff --git a/modules/tools/visualizer/main_window.h b/modules/tools/visualizer/main_window.h deleted file mode 100644 index 850473c1cba..00000000000 --- a/modules/tools/visualizer/main_window.h +++ /dev/null @@ -1,149 +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 "modules/common_msgs/sensor_msgs/pointcloud.pb.h" -#include "modules/common_msgs/sensor_msgs/radar.pb.h" -#include "modules/common_msgs/sensor_msgs/sensor_image.pb.h" -#include "modules/tools/visualizer/channel_reader.h" -#include "modules/tools/visualizer/msg_dialog.h" - -class FixedAspectRatioWidget; -class Texture; -class Grid; -class QAction; -class QComboBox; -class QTreeWidgetItem; -class QOpenGLShaderProgram; -class QCheckBox; -class QColorDialog; -class VideoImagesDialog; - -namespace Ui { -class MainWindow; -} - -class MainWindow : public QMainWindow { - Q_OBJECT - - public: - explicit MainWindow(QWidget* parent = nullptr); - ~MainWindow(); - - void TopologyChanged(const apollo::cyber::proto::ChangeMsg& change_msg); - void AddNewWriter(const apollo::cyber::proto::RoleAttributes& role); - - protected: - void resizeEvent(QResizeEvent*) override; - - private slots: // NOLINT - void ActionAddGrid(void); - - void ActionOpenPointCloud(void); - void PlayRenderableObject(bool); - void ChangePointCloudChannel(void); - - void ActionOpenImage(void); - void PlayVideoImage(bool b); - void ChangeVideoImgChannel(void); - void SelectCurrentTreeItem(FixedAspectRatioWidget*); - - void ActionDelVideoImage(void); - - void CloseVideoImgViewer(bool b); - - void UpdateActions(void); - void EnableGrid(bool b); - - void EditGridColor(QTreeWidgetItem* item, int column); - void ChangeGridCellCountBySize(int v); - - void ActionOpenImages(void); - void AddVideoImages(void); - - void ActionOpenRadarChannel(void); - void openRadarChannel(bool b); - void EnableRadarPoints(bool b); - void ChangeRadarChannel(void); - - void showMessage(void); - - void PlayPause(void); - - private: - struct VideoImgProxy; - struct RadarData; - - void PointCloudReaderCallback( - const std::shared_ptr& pdata); - void ImageReaderCallback( - const std::shared_ptr& imgData, - VideoImgProxy* proxy); - void ImageReaderCallback( - const std::shared_ptr& imgData, - VideoImgProxy* proxy); - - void InsertAllChannelNames(void); - VideoImgProxy* AddVideoImgViewer(void); - void DoDeleteVideoImg(VideoImgProxy*); - void DoPlayVideoImage(bool, VideoImgProxy*); - void calculateWH(void); - - RadarData* createRadarData(void); - void DoOpenRadarChannel(bool b, RadarData* radarProxy); - void RadarRenderCallback( - const std::shared_ptr& rawData, - RadarData* radar); - - Ui::MainWindow* ui_; - MessageDialog* msg_dialog_; - VideoImagesDialog* open_images_dialog_; - - QTreeWidgetItem* all_channel_root_; - - Grid* grid_; - QCheckBox* enable_grid_checkBox_; - QTreeWidgetItem* grid_root_item_; - - QTreeWidgetItem* pointcloud_top_item_; - QComboBox* pointcloud_comboBox_; - QPushButton* pointcloud_button_; - CyberChannReader* pointcloud_channel_Reader_; - - QMutex pointcloud_reader_mutex_; - - QMenu right_menu_; - - std::shared_ptr pointcloud_shader_; - std::shared_ptr grid_shader_; - std::shared_ptr radar_points_shader_; - - QList video_image_viewer_list_; - QList closed_video_image_viewer_list_; - - QList radarData_list_; - QList closed_radarData_list_; - - std::map _channelName2TypeMap; -}; diff --git a/modules/tools/visualizer/msg_dialog.cc b/modules/tools/visualizer/msg_dialog.cc deleted file mode 100644 index 4bd3eb0f359..00000000000 --- a/modules/tools/visualizer/msg_dialog.cc +++ /dev/null @@ -1,29 +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/tools/visualizer/msg_dialog.h" -#include "modules/tools/visualizer/ui_msg_dialog.h" - -MessageDialog::MessageDialog(QWidget *parent) - : QDialog(parent), ui_(new Ui::MessageDialog) { - ui_->setupUi(this); -} - -MessageDialog::~MessageDialog() { delete ui_; } - -void MessageDialog::setMessage(const QString &msg) { - ui_->msgLabel->setText(msg); -} diff --git a/modules/tools/visualizer/msg_dialog.h b/modules/tools/visualizer/msg_dialog.h deleted file mode 100644 index 95bf553a89b..00000000000 --- a/modules/tools/visualizer/msg_dialog.h +++ /dev/null @@ -1,37 +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 - -namespace Ui { -class MessageDialog; -} - -class MessageDialog : public QDialog { - Q_OBJECT - - public: - explicit MessageDialog(QWidget* parent = nullptr); - ~MessageDialog(); - - void setMessage(const QString& msg); - void setMessage(const char* msg) { setMessage(QString(msg)); } - - private: - Ui::MessageDialog* ui_; -}; diff --git a/modules/tools/visualizer/plane.cc b/modules/tools/visualizer/plane.cc deleted file mode 100644 index a6a4d9ae0e6..00000000000 --- a/modules/tools/visualizer/plane.cc +++ /dev/null @@ -1,109 +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/tools/visualizer/plane.h" - -std::shared_ptr Plane::NullTextureObj; - -Plane::Plane(const std::shared_ptr& t) - : RenderableObject(4, 4), texture_id_(0), texture_(t) {} - -bool Plane::FillVertexBuffer(GLfloat* pBuffer) { - if (texture_ == nullptr || !texture_->isDirty()) { - return false; - } - glGenTextures(1, &texture_id_); - - glBindTexture(GL_TEXTURE_2D, texture_id_); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_BORDER); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_BORDER); - - glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA8, texture_->width(), - texture_->height(), 0, texture_->texture_format(), - GL_UNSIGNED_BYTE, texture_->data()); - - glBindTexture(GL_TEXTURE_2D, 0); - - texture_->removeDirty(); - - pBuffer[0] = -1.0f; - pBuffer[1] = -1.0f; - pBuffer[2] = 0.0f; - pBuffer[3] = 0.0f; - pBuffer[4] = 1.0f; - pBuffer[5] = -1.0f; - pBuffer[6] = 1.0f; - pBuffer[7] = 0.0f; - pBuffer[8] = 1.0f; - pBuffer[9] = 1.0f; - pBuffer[10] = 1.0f; - pBuffer[11] = 1.0f; - pBuffer[12] = -1.0f; - pBuffer[13] = 1.0f; - pBuffer[14] = 0.0f; - pBuffer[15] = 1.0f; - - return true; -} - -void Plane::SetupAllAttrPointer(void) { - glEnableVertexAttribArray(0); - glVertexAttribPointer( - 0, 2, GL_FLOAT, GL_FALSE, - static_cast(sizeof(GLfloat)) * vertex_element_count(), 0); - - glEnableVertexAttribArray(1); - glVertexAttribPointer( - 1, 2, GL_FLOAT, GL_FALSE, - static_cast(sizeof(GLfloat)) * vertex_element_count(), - reinterpret_cast(sizeof(GLfloat) * 2)); -} - -void Plane::Draw(void) { - if (texture_->data()) { - if (texture_->isSizeChanged()) { - glGenTextures(1, &texture_id_); - - glBindTexture(GL_TEXTURE_2D, texture_id_); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_BORDER); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_BORDER); - - glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA8, texture_->width(), - texture_->height(), 0, texture_->texture_format(), - GL_UNSIGNED_BYTE, texture_->data()); - - glBindTexture(GL_TEXTURE_2D, 0); - - texture_->removeDirty(); - } else if (texture_->isDirty()) { - glBindTexture(GL_TEXTURE_2D, texture_id_); - glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, texture_->width(), - texture_->height(), texture_->texture_format(), - GL_UNSIGNED_BYTE, texture_->data()); - glBindTexture(GL_TEXTURE_2D, 0); - texture_->removeDirty(); - } - } - - glActiveTexture(GL_TEXTURE0); - glBindTexture(GL_TEXTURE_2D, texture_id_); - RenderableObject::Draw(); - glBindTexture(GL_TEXTURE_2D, 0); -} diff --git a/modules/tools/visualizer/plane.h b/modules/tools/visualizer/plane.h deleted file mode 100644 index e2761315a82..00000000000 --- a/modules/tools/visualizer/plane.h +++ /dev/null @@ -1,58 +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 "modules/tools/visualizer/renderable_object.h" -#include "modules/tools/visualizer/texture.h" - -class Plane : public RenderableObject { - /* - * struct Vertex - * { - * GLfloat _vert[2]; - * GLfloat _texCoor[2]; - * }; - * - */ - - public: - static std::shared_ptr NullTextureObj; - - explicit Plane(const std::shared_ptr& t = NullTextureObj); - virtual ~Plane(void) { texture_.reset(); } - - void set_texture(const std::shared_ptr& t) { - if (t != texture_) { - texture_ = t; - } - } - - GLenum GetPrimitiveType(void) const override { return GL_QUADS; } - GLsizei texWidth(void) const { return texture_->width(); } - GLsizei texHeight(void) const { return texture_->height(); } - - protected: - bool FillVertexBuffer(GLfloat* pBuffer) override; - void Draw(void) override; - void SetupAllAttrPointer(void) override; - - private: - GLuint texture_id_; - std::shared_ptr texture_; -}; diff --git a/modules/tools/visualizer/pointcloud.cc b/modules/tools/visualizer/pointcloud.cc deleted file mode 100644 index 07167c9c19c..00000000000 --- a/modules/tools/visualizer/pointcloud.cc +++ /dev/null @@ -1,64 +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/tools/visualizer/pointcloud.h" - -#include - -PointCloud::PointCloud( - int pointCount, int vertexElementCount, - const std::shared_ptr& shaderProgram) - : RenderableObject(pointCount, vertexElementCount, shaderProgram), - buffer_(nullptr) {} - -PointCloud::~PointCloud(void) { - if (buffer_) { - delete[] buffer_; - buffer_ = nullptr; - } -} - -bool PointCloud::FillVertexBuffer(GLfloat* pBuffer) { - if (buffer_ && pBuffer) { - memcpy(pBuffer, buffer_, VertexBufferSize()); - delete[] buffer_; - buffer_ = nullptr; - return true; - } else { - std::cout << "---Error!!! cannot upload data to Graphics Card----" - << std::endl; - return false; - } -} - -bool PointCloud::FillData( - const std::shared_ptr& pdata) { - assert(vertex_count() == pdata->point_size()); - buffer_ = new GLfloat[vertex_count() * vertex_element_count()]; - if (buffer_) { - GLfloat* tmp = buffer_; - - for (int i = 0; i < vertex_count(); ++i, tmp += vertex_element_count()) { - const apollo::drivers::PointXYZIT& point = pdata->point(i); - tmp[0] = point.x(); - tmp[1] = point.z(); - tmp[2] = -point.y(); - tmp[3] = static_cast(point.intensity()); - } - return true; - } - return false; -} diff --git a/modules/tools/visualizer/pointcloud.h b/modules/tools/visualizer/pointcloud.h deleted file mode 100644 index a447ce307ca..00000000000 --- a/modules/tools/visualizer/pointcloud.h +++ /dev/null @@ -1,42 +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 "modules/common_msgs/sensor_msgs/pointcloud.pb.h" -#include "modules/tools/visualizer/renderable_object.h" - -class QOpenGLShaderProgram; - -class PointCloud : public RenderableObject { - public: - explicit PointCloud(int pointCount = 1, int vertex_element_count = 3, - const std::shared_ptr& - shaderProgram = NullRenderableObj); - ~PointCloud(void); - - virtual GLenum GetPrimitiveType(void) const { return GL_POINTS; } - - bool FillData( - const std::shared_ptr& pData); - - private: - virtual bool FillVertexBuffer(GLfloat* vertexBuffer); - - GLfloat* buffer_; -}; diff --git a/modules/tools/visualizer/radarpoints.cc b/modules/tools/visualizer/radarpoints.cc deleted file mode 100644 index 3fd6ea87786..00000000000 --- a/modules/tools/visualizer/radarpoints.cc +++ /dev/null @@ -1,69 +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 "radarpoints.h" -#include - -#include - -RadarPoints::RadarPoints( - const std::shared_ptr& shaderProgram) - : RenderableObject(1, 3, shaderProgram), - color_(1.0f, 0.0f, 0.0f), - buffer_(nullptr) {} - -bool RadarPoints::FillData( - const std::shared_ptr& rawData) { - bool ret = false; - - set_vertex_count(rawData->radar_obstacle_size()); - buffer_ = new GLfloat[vertex_count() * vertex_element_count()]; - - if (buffer_) { - GLfloat* ptr = buffer_; - const ::google::protobuf::Map<::google::protobuf::int32, - apollo::drivers::RadarObstacle>& - radarObstacles = rawData->radar_obstacle(); - for (::google::protobuf::Map<::google::protobuf::int32, - apollo::drivers::RadarObstacle>::const_iterator - iter = radarObstacles.cbegin(); - iter != radarObstacles.cend(); ++iter, ptr += vertex_element_count()) { - const apollo::common::Point2D& position = - iter->second.absolute_position(); - - ptr[0] = static_cast(position.x()); - ptr[1] = static_cast(position.y()); - ptr[2] = std::pow(10.0f, static_cast(iter->second.rcs() / 20.0)); - } // end for - - ret = true; - } - - return ret; -} - -bool RadarPoints::FillVertexBuffer(GLfloat* pBuffer) { - if (buffer_ && pBuffer) { - memcpy(pBuffer, buffer_, VertexBufferSize()); - delete[] buffer_; - buffer_ = nullptr; - return true; - } else { - std::cout << "---Error!!! cannot upload data to Graphics Card----" - << std::endl; - return false; - } -} diff --git a/modules/tools/visualizer/radarpoints.h b/modules/tools/visualizer/radarpoints.h deleted file mode 100644 index 5a076ffdbd6..00000000000 --- a/modules/tools/visualizer/radarpoints.h +++ /dev/null @@ -1,75 +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 "modules/common_msgs/sensor_msgs/radar.pb.h" -#include "modules/tools/visualizer/renderable_object.h" - -class QOpenGLShaderProgram; - -class RadarPoints : public RenderableObject { - /* struct Point{ - * GLfloat x, // raw data from radar - * GLfloat y, - * GLfloat r - * }; - */ - - public: - explicit RadarPoints( - const std::shared_ptr& shaderProgram = nullptr); - ~RadarPoints(void) { - if (buffer_) { - delete[] buffer_; - buffer_ = nullptr; - } - } - - virtual GLenum GetPrimitiveType(void) const { return GL_POINTS; } - - void SetupExtraUniforms(void) { - shader_program_->setUniformValue("color", color_); - } - - GLfloat red(void) const { return color_.x(); } - GLfloat green(void) const { return color_.y(); } - GLfloat blue(void) const { return color_.z(); } - - const QVector3D& color(void) const { return color_; } - - void set_color(const QRgb& rgb) { set_color(QColor(rgb)); } - - void set_color(const QColor& color) { - color_.setX(static_cast(color.redF())); - color_.setY(static_cast(color.greenF())); - color_.setZ(static_cast(color.blueF())); - } - - bool FillData( - const std::shared_ptr& pData); - - protected: - bool FillVertexBuffer(GLfloat* pBuffer) override; - - private: - QVector3D color_; // r, g, b - GLfloat* buffer_; -}; diff --git a/modules/tools/visualizer/renderable_object.cc b/modules/tools/visualizer/renderable_object.cc deleted file mode 100644 index 6050b22af24..00000000000 --- a/modules/tools/visualizer/renderable_object.cc +++ /dev/null @@ -1,134 +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/tools/visualizer/renderable_object.h" - -#include - -std::shared_ptr RenderableObject::NullRenderableObj; - -std::shared_ptr RenderableObject::CreateShaderProgram( - const QString& vertexShaderFileName, const QString& fragShaderFileName) { - std::shared_ptr shaderProg(new QOpenGLShaderProgram()); - if (shaderProg != nullptr) { - shaderProg->addShaderFromSourceFile(QOpenGLShader::Vertex, - vertexShaderFileName); - shaderProg->addShaderFromSourceFile(QOpenGLShader::Fragment, - fragShaderFileName); - if (!shaderProg->link()) { - std::cerr << "----cannot link shader programm, log:(" - << shaderProg->log().toStdString() << ")\n"; - - shaderProg.reset(); - } - } - return shaderProg; -} - -RenderableObject::RenderableObject( - int vertexCount, int vertexElementCount, - const std::shared_ptr& shaderProgram) - : QOpenGLFunctions(), - is_init_(false), - is_renderable_(true), - vertex_count_(vertexCount), - vertex_element_count_(vertexElementCount), - shader_program_(shaderProgram), - vao_(), - vbo_(QOpenGLBuffer::VertexBuffer) {} - -RenderableObject::~RenderableObject() { Destroy(); } - -void RenderableObject::Destroy(void) { - if (is_init_) { - is_renderable_ = false; - is_init_ = false; - shader_program_.reset(); - vbo_.destroy(); - vao_.destroy(); - } -} - -bool RenderableObject::Init( - std::shared_ptr& shaderProgram) { - if (is_init_) { - return true; - } - - if (vertex_count() < 1) { - return false; - } - if (vertex_element_count() < 1) { - return false; - } - - if (shaderProgram != nullptr) { - shader_program_ = shaderProgram; - } - - if (shader_program_ == nullptr) { - return false; - } - - initializeOpenGLFunctions(); - - if (!vao_.create()) { - return false; - } - vao_.bind(); - - if (!vbo_.create()) { - vao_.destroy(); - return false; - } - vbo_.setUsagePattern(QOpenGLBuffer::StaticDraw); - vbo_.bind(); - - vbo_.allocate(VertexBufferSize()); - GLfloat* pBuffer = static_cast(vbo_.map(QOpenGLBuffer::WriteOnly)); - bool ret = FillVertexBuffer(pBuffer); - vbo_.unmap(); - - if (!ret) { - return ret; - } - - SetupAllAttrPointer(); - - vbo_.release(); - vao_.release(); - is_init_ = true; - - return true; -} - -void RenderableObject::Render(const QMatrix4x4* mvp) { - if (is_init_) { - if (is_renderable()) { - shader_program_->bind(); - if (mvp) { - shader_program_->setUniformValue("mvp", *mvp); - } - SetupExtraUniforms(); - vao_.bind(); - Draw(); - vao_.release(); - shader_program_->release(); - } - } else { - std::cerr << "Please initialize the object" << std::endl; - } -} diff --git a/modules/tools/visualizer/renderable_object.h b/modules/tools/visualizer/renderable_object.h deleted file mode 100644 index fd6eb455e48..00000000000 --- a/modules/tools/visualizer/renderable_object.h +++ /dev/null @@ -1,91 +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 - -class RenderableObject : protected QOpenGLFunctions { - public: - static std::shared_ptr NullRenderableObj; - static std::shared_ptr CreateShaderProgram( - const QString& vertexShaderFileName, const QString& fragShaderFileName); - - explicit RenderableObject(int vertex_count = 1, int vertex_element_count = 3, - const std::shared_ptr& - shaderProgram = NullRenderableObj); - virtual ~RenderableObject(void); - - virtual GLenum GetPrimitiveType(void) const = 0; - virtual void SetupExtraUniforms(void) {} - - bool is_renderable(void) const { return is_renderable_; } - void set_is_renderable(bool b) { is_renderable_ = b; } - - int vertex_count(void) const { return vertex_count_; } - void set_vertex_count(int vertexCount) { vertex_count_ = vertexCount; } - - int vertex_element_count(void) const { return vertex_element_count_; } - void set_vertex_element_count(int vertexElementCount) { - vertex_element_count_ = vertexElementCount; - } - - int VertexBufferSize(void) const { - return vertex_count() * vertex_element_count() * - static_cast(sizeof(GLfloat)); - } - - void set_shader_program( - const std::shared_ptr& shaderProgram) { - shader_program_ = shaderProgram; - } - - bool haveShaderProgram(void) { return shader_program_ != nullptr; } - - bool Init( - std::shared_ptr& shaderProgram = - NullRenderableObj); // initial vao, vbo and call fillVertexBuffer - void Destroy(void); - - void Render(const QMatrix4x4* mvp = nullptr); - - protected: - virtual bool FillVertexBuffer(GLfloat* pBuffer) = 0; - virtual void Draw(void) { - glDrawArrays(GetPrimitiveType(), 0, vertex_count()); - } - - virtual void SetupAllAttrPointer(void) { - glEnableVertexAttribArray(0); - glVertexAttribPointer( - 0, vertex_element_count(), GL_FLOAT, GL_FALSE, - static_cast(sizeof(GLfloat)) * vertex_element_count(), 0); - } - - bool is_init_; - bool is_renderable_; - - int vertex_count_; - int vertex_element_count_; - - std::shared_ptr shader_program_; - QOpenGLVertexArrayObject vao_; - QOpenGLBuffer vbo_; -}; diff --git a/modules/tools/visualizer/res.qrc b/modules/tools/visualizer/res.qrc deleted file mode 100644 index d76a4a750ad..00000000000 --- a/modules/tools/visualizer/res.qrc +++ /dev/null @@ -1,20 +0,0 @@ - - - images/app.ico - images/closeimage.png - images/grid.png - images/image.png - images/images.png - images/no_image.png - images/pause.png - images/play.png - images/pointcloud.png - shaders/grid.vert - shaders/grid_pointcloud.frag - shaders/pointcloud.vert - shaders/video_image_plane.frag - shaders/video_image_plane.vert - shaders/radarpoints.frag - shaders/radarpoints.vert - - diff --git a/modules/tools/visualizer/scene_camera_dialog.cc b/modules/tools/visualizer/scene_camera_dialog.cc deleted file mode 100644 index 46bbb5248a8..00000000000 --- a/modules/tools/visualizer/scene_camera_dialog.cc +++ /dev/null @@ -1,83 +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/tools/visualizer/scene_camera_dialog.h" - -#include - -#include "modules/tools/visualizer/ui_scene_camera_dialog.h" - -SceneCameraDialog::SceneCameraDialog(QWidget* parent) - : QDialog(parent), ui(new Ui::SceneCameraDialog) { - ui->setupUi(this); - ui->cameraX->setEnabled(false); - ui->cameraY->setEnabled(false); - ui->cameraZ->setEnabled(false); - - connect(ui->resetButton, SIGNAL(clicked()), this, SIGNAL(resetcamera())); - connect(ui->cameraTypeComboBox, SIGNAL(currentIndexChanged(int)), this, - SLOT(onCameraTypeChanged(int))); - connect(ui->cameraX, SIGNAL(valueChanged(double)), this, - SIGNAL(xValueChanged(double))); - connect(ui->cameraY, SIGNAL(valueChanged(double)), this, - SIGNAL(yValueChanged(double))); - connect(ui->cameraZ, SIGNAL(valueChanged(double)), this, - SIGNAL(zValueChanged(double))); - connect(ui->cameraYaw, SIGNAL(valueChanged(double)), this, - SIGNAL(yawValueChanged(double))); - connect(ui->cameraPitch, SIGNAL(valueChanged(double)), this, - SIGNAL(pitchValueChanged(double))); - connect(ui->cameraRoll, SIGNAL(valueChanged(double)), this, - SIGNAL(rollValueChanged(double))); - connect(ui->stepSlider, SIGNAL(valueChanged(int)), this, - SLOT(OnStepSlideChanged(int))); -} - -SceneCameraDialog::~SceneCameraDialog() { delete ui; } - -void SceneCameraDialog::updateCameraAttitude(const QVector3D& attitude) { - ui->cameraYaw->setValue(attitude.x()); - ui->cameraPitch->setValue(attitude.y()); - ui->cameraRoll->setValue(attitude.z()); -} - -void SceneCameraDialog::updateCameraPos(const QVector3D& pos) { - ui->cameraX->setValue(pos.x()); - ui->cameraY->setValue(pos.y()); - ui->cameraZ->setValue(pos.z()); -} - -void SceneCameraDialog::OnStepSlideChanged(int v) { - const float step = - static_cast(v) / static_cast(ui->stepSlider->maximum()); - - emit sensitivityChanged(step); - - ui->cameraX->setSingleStep(step); - ui->cameraY->setSingleStep(step); - ui->cameraZ->setSingleStep(step); - - ui->cameraYaw->setSingleStep(step); - ui->cameraPitch->setSingleStep(step); - ui->cameraRoll->setSingleStep(step); -} - -void SceneCameraDialog::onCameraTypeChanged(int index) { - emit cameraTypeChanged(index); - ui->cameraX->setEnabled(index); - ui->cameraY->setEnabled(index); - ui->cameraZ->setEnabled(index); -} diff --git a/modules/tools/visualizer/scene_camera_dialog.h b/modules/tools/visualizer/scene_camera_dialog.h deleted file mode 100644 index bd8bbe0de70..00000000000 --- a/modules/tools/visualizer/scene_camera_dialog.h +++ /dev/null @@ -1,57 +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 - -namespace Ui { -class SceneCameraDialog; -} - -class QVector3D; - -class SceneCameraDialog : public QDialog { - Q_OBJECT - - public: - explicit SceneCameraDialog(QWidget *parent = nullptr); - ~SceneCameraDialog(); - - signals: - void resetcamera(); - - void sensitivityChanged(float); - void cameraTypeChanged(int); - - void xValueChanged(double); - void yValueChanged(double); - void zValueChanged(double); - void yawValueChanged(double); - void pitchValueChanged(double); - void rollValueChanged(double); - - public slots: // NOLINT - void updateCameraAttitude(const QVector3D &); - void updateCameraPos(const QVector3D &); - - private slots: // NOLINT - void OnStepSlideChanged(int v); - void onCameraTypeChanged(int); - - private: - Ui::SceneCameraDialog *ui; -}; diff --git a/modules/tools/visualizer/scene_viewer.cc b/modules/tools/visualizer/scene_viewer.cc deleted file mode 100644 index 57e66d2524f..00000000000 --- a/modules/tools/visualizer/scene_viewer.cc +++ /dev/null @@ -1,479 +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/tools/visualizer/scene_viewer.h" - -#include -#include -#include - -#include "modules/tools/visualizer/scene_camera_dialog.h" - -struct SceneViewer::TempRenderableObjGroup { - bool isEnabled_; - QList objGroupList_; - - TempRenderableObjGroup(void) : isEnabled_(true), objGroupList_() {} - ~TempRenderableObjGroup(void) { - while (!objGroupList_.isEmpty()) { - delete objGroupList_.takeFirst(); - } - - objGroupList_.clear(); - } - - bool isEmpty(void) const { return objGroupList_.isEmpty(); } - - bool isEnabled(void) const { return isEnabled_; } - - void append(RenderableObject *obj) { objGroupList_.append(obj); } - RenderableObject *takeFirst(void) { return objGroupList_.takeFirst(); } - RenderableObject *takeLast(void) { return objGroupList_.takeLast(); } -}; - -SceneViewer::SceneViewer(QWidget *parent) - : QOpenGLWidget(parent), - QOpenGLFunctions(), - is_init_(false), - right_key_is_moved_(false), - sensitivity_(0.08f), - refreshTimer_(nullptr), - left_key_last_pos_(), - right_key_last_y_(0), - camera_dialog_(nullptr), - current_cameraPtr_(nullptr), - free_camera_(), - target_camera_(), - managed_shader_prog_(), - tmp_renderable_obj_list_(), - permanent_renderable_obj_list_() { - current_cameraPtr_ = &target_camera_; -} - -SceneViewer::~SceneViewer() { - if (is_init_) { - is_init_ = false; - - refreshTimer_->stop(); - delete refreshTimer_; - - makeCurrent(); - - auto iter = managed_shader_prog_.begin(); - for (; iter != managed_shader_prog_.end(); ++iter) { - iter->second->destroyed(); - iter->second.reset(); - } - - managed_shader_prog_.clear(); - - for (auto &iter : tmp_renderable_obj_list_) { - delete iter.second; - } - - tmp_renderable_obj_list_.clear(); - - while (!permanent_renderable_obj_list_.isEmpty()) { - delete permanent_renderable_obj_list_.takeFirst(); - } - - doneCurrent(); - } -} - -void SceneViewer::setTempObjGroupEnabled(const std::string &tmpObjGroupName, - bool b) { - auto iter = tmp_renderable_obj_list_.find(tmpObjGroupName); - if (iter != tmp_renderable_obj_list_.cend()) { - iter->second->isEnabled_ = b; - } -} - -bool SceneViewer::AddTempRenderableObj(const std::string &tmpObjGroupName, - RenderableObject *renderObj) { - bool ret = false; - if (renderObj && renderObj->haveShaderProgram() && is_init_) { - auto iter = tmp_renderable_obj_list_.find(tmpObjGroupName); - if (iter == tmp_renderable_obj_list_.cend()) { - TempRenderableObjGroup *objGroup = new TempRenderableObjGroup(); - if (objGroup) { - objGroup->append(renderObj); - tmp_renderable_obj_list_.insert( - std::make_pair(tmpObjGroupName, objGroup)); - ret = true; - } - } else { - iter->second->objGroupList_.append(renderObj); - ret = true; - } - } - - return ret; -} - -void SceneViewer::AddNewShaderProg( - const std::string &shaderProgName, - const std::shared_ptr &newShaderProg) { - if (newShaderProg == nullptr) { - return; - } - - auto iter = managed_shader_prog_.find(shaderProgName); - if (iter != managed_shader_prog_.end()) { - iter->second.reset(); - } - - QMatrix4x4 mvp = current_cameraPtr_->projection_matrix() * - current_cameraPtr_->model_view_matrix(); - - newShaderProg->bind(); - newShaderProg->setUniformValue("mvp", mvp); - newShaderProg->release(); - - managed_shader_prog_[shaderProgName] = newShaderProg; -} - -void SceneViewer::initializeGL() { - initializeOpenGLFunctions(); - - glPointSize(1.0f); - glEnable(GL_PROGRAM_POINT_SIZE); - glClearColor(0.0f, 0.0f, 0.0f, 1.0f); - - refreshTimer_ = new QTimer(this); - if (!refreshTimer_) { - return; - } - - refreshTimer_->setObjectName(tr("_refreshTimer")); - refreshTimer_->setInterval(40); - refreshTimer_->start(); - connect(refreshTimer_, SIGNAL(timeout()), this, SLOT(repaint())); - - free_camera_.SetUpProjection(45.0f, GLfloat(width()), GLfloat(height())); - target_camera_.SetUpProjection(45.0f, GLfloat(width()), GLfloat(height())); - ResetCameraPosAttitude(); - - is_init_ = true; -} - -void SceneViewer::resizeGL(int width, int height) { - glViewport(0, 0, (GLsizei)width, (GLsizei)height); - - if (is_init_) { - free_camera_.set_near_plane_width(GLfloat(width)); - free_camera_.set_near_plane_height(GLfloat(height)); - free_camera_.UpdateProjection(); - - target_camera_.set_near_plane_width(GLfloat(width)); - target_camera_.set_near_plane_height(GLfloat(height)); - target_camera_.UpdateProjection(); - - QMatrix4x4 mvp = current_cameraPtr_->projection_matrix() * - current_cameraPtr_->model_view_matrix(); - - UpdateAllShaderProgMVP(mvp); - } -} - -void SceneViewer::paintGL() { - if (is_init_) { - for (RenderableObject *item : permanent_renderable_obj_list_) { - if (item->Init()) { - item->Render(); - } - } - - for (auto &iter : tmp_renderable_obj_list_) { - if (!iter.second->isEmpty()) { - RenderableObject *lastItem = nullptr; - - if (iter.second->isEnabled()) { - lastItem = iter.second->takeLast(); - if (lastItem->Init()) { - lastItem->Render(); - } - } - - while (!iter.second->isEmpty()) { - delete iter.second->takeFirst(); - } - - if (lastItem) { - iter.second->append(lastItem); - } - } - } - } -} - -void SceneViewer::ChangeCameraType(int index) { - if (index < TARGET || index > FREE) { - return; - } - if (index == FREE) { - current_cameraPtr_ = &free_camera_; - } else { - current_cameraPtr_ = &target_camera_; - } - ResetCameraPosAttitude(); -} - -void SceneViewer::ResetCameraPosAttitude(void) { - free_camera_.set_position(0.0f, 48.0f, -48.0f); - free_camera_.SetAttitude(0.0f, 45.0f, 0.0f); - - target_camera_.set_position(-21.0f, 21.0f, 0.0f); - target_camera_.Rotate(-45.0f, -90.0f, 0.0f); - target_camera_.set_target_pos(0.0f, 0.0f, 0.0f); - - emit CameraPosChanged(current_cameraPtr_->position()); - emit CameraAttitudeChanged(current_cameraPtr_->attitude()); - - UpdateCameraWorld(); -} - -void SceneViewer::UpdateCameraX(double x) { - free_camera_.set_x(static_cast(x)); - target_camera_.set_x(static_cast(x)); - UpdateCameraWorld(); -} - -void SceneViewer::UpdateCameraY(double y) { - free_camera_.set_y(static_cast(y)); - target_camera_.set_y(static_cast(y)); - UpdateCameraWorld(); -} - -void SceneViewer::UpdateCameraZ(double z) { - free_camera_.set_z(static_cast(z)); - target_camera_.set_y(static_cast(z)); - UpdateCameraWorld(); -} - -void SceneViewer::UpdateCameraYaw(double yawInDegrees) { - if (yawInDegrees > 360.0) { - yawInDegrees -= 360.0; - } - if (yawInDegrees < -360.0) { - yawInDegrees += 360.0; - } - - free_camera_.set_yaw(static_cast(yawInDegrees)); - target_camera_.set_yaw(static_cast(yawInDegrees)); - UpdateCameraWorld(); -} - -void SceneViewer::UpdateCameraPitch(double pitchInDegrees) { - if (pitchInDegrees > 90.0) { - pitchInDegrees = 90.0; - } - if (pitchInDegrees < -90.0) { - pitchInDegrees = -90.0; - } - - free_camera_.set_pitch(static_cast(pitchInDegrees)); - target_camera_.set_pitch(static_cast(pitchInDegrees)); - UpdateCameraWorld(); -} -void SceneViewer::UpdateCameraRoll(double rollInDegrees) { - if (rollInDegrees > 360.0) { - rollInDegrees -= 360.0; - } - if (rollInDegrees < -360.0) { - rollInDegrees += 360.0; - } - - free_camera_.set_roll(static_cast(rollInDegrees)); - free_camera_.set_roll(static_cast(rollInDegrees)); - UpdateCameraWorld(); -} - -void SceneViewer::UpdateCameraWorld(void) { - free_camera_.UpdateWorld(); - target_camera_.UpdateWorld(); - - QMatrix4x4 mvp = current_cameraPtr_->projection_matrix() * - current_cameraPtr_->model_view_matrix(); - - UpdateAllShaderProgMVP(mvp); - - update(); -} - -void SceneViewer::UpdateAllShaderProgMVP(const QMatrix4x4 &mvp) { - for (auto iter = managed_shader_prog_.begin(); - iter != managed_shader_prog_.end(); ++iter) { - iter->second->bind(); - iter->second->setUniformValue("mvp", mvp); - iter->second->release(); - } -} - -void SceneViewer::enterEvent(QEvent *event) { - setCursor(Qt::SizeAllCursor); - QOpenGLWidget::enterEvent(event); -} - -void SceneViewer::leaveEvent(QEvent *event) { - unsetCursor(); - QOpenGLWidget::leaveEvent(event); -} - -void SceneViewer::mousePressEvent(QMouseEvent *event) { - if (event->button() == Qt::LeftButton) { - left_key_last_pos_ = QCursor::pos(); - } else if (event->button() == Qt::RightButton) { - right_key_is_moved_ = false; - right_key_last_y_ = static_cast(QCursor::pos().y()); - } - - QOpenGLWidget::mousePressEvent(event); -} - -void SceneViewer::mouseMoveEvent(QMouseEvent *mouseEvent) { - if (mouseEvent->buttons() == Qt::LeftButton) { - QPoint tmp = QCursor::pos(); - QPoint dd = tmp - left_key_last_pos_; - left_key_last_pos_ = tmp; - - float x = static_cast(dd.x()) * sensitivity(); - float y = static_cast(dd.y()) * sensitivity(); - - if (IsFreeCamera()) { - free_camera_.Starfe(-x); - free_camera_.Lift(y); - - emit CameraPosChanged(free_camera_.position()); - } else { - x = target_camera_.yaw() - x; - y = target_camera_.pitch() - y; - - if (x > 360.0f) { - x -= 360.0f; - } - if (x < -360.0f) { - x += 360.0f; - } - - if (y > 90.0f) { - y = 90.0f; - } - if (y < -90.0f) { - y = 90.0f; - } - - target_camera_.set_yaw(x); - target_camera_.set_pitch(y); - - emit CameraAttitudeChanged(target_camera_.attitude()); - } - - goto _label1; - } else if (mouseEvent->buttons() == Qt::RightButton) { - right_key_is_moved_ = true; - if (IsFreeCamera()) { - { - float tmp = static_cast(QCursor::pos().y()); - float dd = right_key_last_y_ - tmp; - right_key_last_y_ = tmp; - - float z = dd * sensitivity(); - - free_camera_.Walk(z); - - emit CameraPosChanged(free_camera_.position()); - } - - _label1: - UpdateCameraWorld(); - update(); - } - } - QOpenGLWidget::mousePressEvent(mouseEvent); -} - -void SceneViewer::wheelEvent(QWheelEvent *event) { - float delta = static_cast(event->angleDelta().y()); - delta *= sensitivity(); - - target_camera_.set_distance(target_camera_.distance() + delta); - - delta += free_camera_.pitch(); - if (delta > 90.0f) { - delta = 90.0f; - } - if (delta < -90.0f) { - delta = -90.0f; - } - free_camera_.set_pitch(delta); - - if (IsFreeCamera()) { - emit CameraAttitudeChanged(free_camera_.attitude()); - } else { - emit CameraPosChanged(target_camera_.position()); - } - UpdateCameraWorld(); - update(); - - QOpenGLWidget::wheelEvent(event); -} - -void SceneViewer::mouseReleaseEvent(QMouseEvent *event) { - if (!right_key_is_moved_ && event->button() == Qt::RightButton) { - if (camera_dialog_ == nullptr) { - camera_dialog_ = new SceneCameraDialog(this); - if (!camera_dialog_) { - QMessageBox::warning(this, tr("Error"), - tr("No Enough for creating Camera Dialog!!!"), - QMessageBox::Ok); - goto retLabel; - } else { - connect(camera_dialog_, SIGNAL(resetcamera()), this, - SLOT(ResetCameraPosAttitude())); - connect(camera_dialog_, SIGNAL(xValueChanged(double)), this, - SLOT(UpdateCameraX(double))); - connect(camera_dialog_, SIGNAL(yValueChanged(double)), this, - SLOT(UpdateCameraY(double))); - connect(camera_dialog_, SIGNAL(zValueChanged(double)), this, - SLOT(UpdateCameraZ(double))); - connect(camera_dialog_, SIGNAL(yawValueChanged(double)), this, - SLOT(UpdateCameraYaw(double))); - connect(camera_dialog_, SIGNAL(pitchValueChanged(double)), this, - SLOT(UpdateCameraPitch(double))); - connect(camera_dialog_, SIGNAL(rollValueChanged(double)), this, - SLOT(UpdateCameraRoll(double))); - connect(camera_dialog_, SIGNAL(cameraTypeChanged(int)), this, - SLOT(ChangeCameraType(int))); - connect(camera_dialog_, SIGNAL(sensitivityChanged(float)), this, - SLOT(set_sensitivity(float))); - - connect(this, SIGNAL(CameraAttitudeChanged(QVector3D)), camera_dialog_, - SLOT(updateCameraAttitude(QVector3D))); - connect(this, SIGNAL(CameraPosChanged(QVector3D)), camera_dialog_, - SLOT(updateCameraPos(QVector3D))); - } - } - camera_dialog_->updateCameraPos(current_cameraPtr_->position()); - camera_dialog_->updateCameraAttitude(current_cameraPtr_->attitude()); - - camera_dialog_->move(event->globalPos()); - camera_dialog_->show(); - } - -retLabel: - QOpenGLWidget::mouseReleaseEvent(event); -} diff --git a/modules/tools/visualizer/scene_viewer.h b/modules/tools/visualizer/scene_viewer.h deleted file mode 100644 index d887c45cff8..00000000000 --- a/modules/tools/visualizer/scene_viewer.h +++ /dev/null @@ -1,141 +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 "modules/tools/visualizer/free_camera.h" -#include "modules/tools/visualizer/plane.h" -#include "modules/tools/visualizer/target_camera.h" - -class QTimer; -class SceneCameraDialog; - -class SceneViewer : public QOpenGLWidget, protected QOpenGLFunctions { - Q_OBJECT - - public: - enum CameraType { - TARGET, - FREE, - }; - - explicit SceneViewer(QWidget* parent = nullptr); - ~SceneViewer(); - - bool is_init(void) const { return is_init_; } - bool IsFreeCamera(void) const { return current_cameraPtr_ == &free_camera_; } - - bool AddTempRenderableObj(const std::string& tmpObjGroupName, - RenderableObject* renderObj); - bool AddPermanentRenderObj(RenderableObject* obj) { - if (obj && obj->haveShaderProgram() && is_init_) { - permanent_renderable_obj_list_.append(obj); - return true; - } else { - return false; - } - } - - void setTempObjGroupEnabled(const std::string& tmpObjGroupName, bool b); - - const QVector3D& CameraPos(void) const { - return current_cameraPtr_->position(); - } - const QVector3D& CamerAttitude(void) const { - return current_cameraPtr_->attitude(); - } - - float sensitivity(void) const { return sensitivity_; } - - void AddNewShaderProg( - const std::string& shaderProgName, - const std::shared_ptr& newShaderProg); - - std::shared_ptr FindShaderProg( - const std::string& shaderProgName) { - if (managed_shader_prog_.find(shaderProgName) != - managed_shader_prog_.end()) { - return managed_shader_prog_[shaderProgName]; - } else { - return std::shared_ptr(); - } - } - - signals: // NOLINT - void CameraPosChanged(const QVector3D& pos); - void CameraAttitudeChanged(const QVector3D& attitude); - - public slots: // NOLINT - void ChangeCameraType(int index); - // void ChangeCameraMode(int index); - - void ResetCameraPosAttitude(void); - - void UpdateCameraX(double x); - void UpdateCameraY(double Y); - void UpdateCameraZ(double Z); - - void UpdateCameraYaw(double yawInDegrees); - void UpdateCameraPitch(double pitchInDegrees); - void UpdateCameraRoll(double rollInDegrees); - - void set_sensitivity(float s) { sensitivity_ = s; } - - protected: - void initializeGL() override; - void resizeGL(int w, int h) override; - void paintGL() override; - - void enterEvent(QEvent* event) override; - void leaveEvent(QEvent* event) override; - - void mousePressEvent(QMouseEvent* mouseEvent) override; - void mouseMoveEvent(QMouseEvent* mouseEvent) override; - void mouseReleaseEvent(QMouseEvent* event) override; - void wheelEvent(QWheelEvent* event) override; - - private: - void UpdateCameraWorld(void); - void UpdateAllShaderProgMVP(const QMatrix4x4& mvp); - - bool is_init_; - bool right_key_is_moved_; - - float sensitivity_; - QTimer* refreshTimer_; - - QPoint left_key_last_pos_; - float right_key_last_y_; - - SceneCameraDialog* camera_dialog_; - AbstractCamera* current_cameraPtr_; - - FreeCamera free_camera_; - TargetCamera target_camera_; - - std::map> - managed_shader_prog_; - - struct TempRenderableObjGroup; - - std::map tmp_renderable_obj_list_; - QList permanent_renderable_obj_list_; -}; diff --git a/modules/tools/visualizer/shaders/grid.vert b/modules/tools/visualizer/shaders/grid.vert deleted file mode 100644 index 55548f5b39b..00000000000 --- a/modules/tools/visualizer/shaders/grid.vert +++ /dev/null @@ -1,28 +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. - *****************************************************************************/ - -#version 330 core - -layout(location = 0) in vec2 vertPos; -uniform mat4 mvp; -uniform vec3 color; -out vec3 Color; - -void main(void) -{ - gl_Position = mvp * vec4(vertPos.x, 0.0, vertPos.y, 1.0); - Color = color; -} diff --git a/modules/tools/visualizer/shaders/grid_pointcloud.frag b/modules/tools/visualizer/shaders/grid_pointcloud.frag deleted file mode 100644 index 161575e0ffb..00000000000 --- a/modules/tools/visualizer/shaders/grid_pointcloud.frag +++ /dev/null @@ -1,25 +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. - *****************************************************************************/ - -#version 330 core - -in vec3 Color; -out vec4 FragColor; - -void main(void) -{ - FragColor = vec4(Color, 1.0); -} \ No newline at end of file diff --git a/modules/tools/visualizer/shaders/pointcloud.vert b/modules/tools/visualizer/shaders/pointcloud.vert deleted file mode 100644 index 6db1bcebeb4..00000000000 --- a/modules/tools/visualizer/shaders/pointcloud.vert +++ /dev/null @@ -1,49 +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. - *****************************************************************************/ - -#version 330 core - -layout(location = 0) in vec4 vertPos; -uniform mat4 mvp; -out vec3 Color; - -void main(void) -{ - gl_Position = mvp * vec4(vertPos.xyz, 1.0); - - float g = smoothstep(0.0, 256, vertPos.w); - float r = 0.0; - float b = 0.0; - - if(g <= 0.25) - { - r = g * 4.0; - g = 0.0; - } - if(g > 0.75) - { - g = 0.0; - b = g * 4.0 - 3.0; // b = g; - } - else - { - // g = g + 0.25; -// g = g + 0.45; - g = g + 0.35; - } - - Color = vec3(r,g,b); -} diff --git a/modules/tools/visualizer/shaders/radarpoints.frag b/modules/tools/visualizer/shaders/radarpoints.frag deleted file mode 100644 index e843972f428..00000000000 --- a/modules/tools/visualizer/shaders/radarpoints.frag +++ /dev/null @@ -1,26 +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. - *****************************************************************************/ - -#version 330 core - -in vec3 Color; -out vec4 FragColor; - -void main(void) -{ - FragColor = vec4(Color, 1.0); -} - diff --git a/modules/tools/visualizer/shaders/radarpoints.vert b/modules/tools/visualizer/shaders/radarpoints.vert deleted file mode 100644 index 709ee0a2002..00000000000 --- a/modules/tools/visualizer/shaders/radarpoints.vert +++ /dev/null @@ -1,30 +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. - *****************************************************************************/ - -#version 330 core - -layout(location = 0) in vec3 vertPos; -uniform mat4 mvp; -uniform vec3 color; -out vec3 Color; - -void main(void) -{ - gl_Position = mvp * vec4(vertPos.x, 0.0, vertPos.y, 1.0); - gl_PointSize = 2.8f; - Color = color; -} - diff --git a/modules/tools/visualizer/shaders/video_image_plane.frag b/modules/tools/visualizer/shaders/video_image_plane.frag deleted file mode 100644 index a0d23b61ead..00000000000 --- a/modules/tools/visualizer/shaders/video_image_plane.frag +++ /dev/null @@ -1,26 +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. - *****************************************************************************/ - -#version 330 core - -in vec2 TexCoord; -out vec4 FragColor; - -uniform sampler2D texture; - -void main(void) { - FragColor = texture2D(texture, TexCoord); -} diff --git a/modules/tools/visualizer/shaders/video_image_plane.vert b/modules/tools/visualizer/shaders/video_image_plane.vert deleted file mode 100644 index 3d91cb00b3c..00000000000 --- a/modules/tools/visualizer/shaders/video_image_plane.vert +++ /dev/null @@ -1,28 +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. - *****************************************************************************/ - -#version 330 core - -layout(location = 0) in vec2 vertPos; -layout(location = 1) in vec2 texCoord; - -out vec2 TexCoord; - -void main(void) -{ - gl_Position = vec4(vertPos.x, vertPos.y, 0.0, 1.0); - TexCoord = vec2(texCoord.x, 1.0 - texCoord.y); -} diff --git a/modules/tools/visualizer/target_camera.cc b/modules/tools/visualizer/target_camera.cc deleted file mode 100644 index 6a58be539ee..00000000000 --- a/modules/tools/visualizer/target_camera.cc +++ /dev/null @@ -1,35 +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/tools/visualizer/target_camera.h" - -TargetCamera::TargetCamera() - : AbstractCamera(), target_pos_(0.0, 0.0, 0.0), distance_(10.0) {} - -void TargetCamera::UpdateWorld() { - QMatrix4x4 R = YawPitchRoll(yaw(), pitch(), roll()); - QVector3D T{0, 0, distance_}; - T = QVector3D(R * QVector4D(T, 0.0f)); - position_ = target_pos_ + T; - look_ = target_pos_ - position_; - look_.normalize(); - - up_ = QVector3D(R * QVector4D(UP, 0.0f)); - right_ = QVector3D::crossProduct(look_, up_); - - model_view_mat_.setToIdentity(); - model_view_mat_.lookAt(position_, target_pos_, up_); -} diff --git a/modules/tools/visualizer/target_camera.h b/modules/tools/visualizer/target_camera.h deleted file mode 100644 index d20c0657204..00000000000 --- a/modules/tools/visualizer/target_camera.h +++ /dev/null @@ -1,58 +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 "modules/tools/visualizer/abstract_camera.h" - -class TargetCamera : public AbstractCamera { - public: - TargetCamera(); - - virtual void UpdateWorld(); - - const QVector3D& target_pos(void) const { return target_pos_; } - void set_target_pos(float x, float y, float z) { - target_pos_.setX(x); - target_pos_.setY(y); - target_pos_.setZ(z); - - distance_ = position_.distanceToPoint(target_pos_); - } - - void set_target_pos(const QVector3D& tgt) { - target_pos_ = tgt; - distance_ = position_.distanceToPoint(target_pos_); - } - - float distance(void) const { return distance_; } - void set_distance(float distance) { - if (distance < 0.0f) { - distance = 0.0f; - } - distance_ = distance; - } - - void Rotate(float xRotateDegrees, float yRotateDegrees, - float zRotateDegrees) { - SetAttitude(yRotateDegrees, xRotateDegrees, zRotateDegrees); - } - - private: - QVector3D target_pos_; - - float distance_; -}; diff --git a/modules/tools/visualizer/texture.cc b/modules/tools/visualizer/texture.cc deleted file mode 100644 index 103dd10f5f0..00000000000 --- a/modules/tools/visualizer/texture.cc +++ /dev/null @@ -1,117 +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/tools/visualizer/texture.h" - -#include - -Texture::Texture() - : is_size_changed_(false), - is_dirty_(false), - texture_format_(0), - image_width_(0), - image_height_(0), - data_size_(0), - data_(nullptr) {} - -bool Texture::UpdateData(const QImage& img) { - if (data_size_ < img.byteCount()) { - if (!data_) { - delete[] data_; - } - - data_ = new GLubyte[img.byteCount()]; - if (data_ == nullptr) { - data_size_ = 0; - return false; - } - data_size_ = img.byteCount(); - is_size_changed_ = true; - } - - image_height_ = img.height(); - image_width_ = img.width(); - - memcpy(data_, img.bits(), img.byteCount()); - is_dirty_ = true; - - texture_format_ = GL_RGBA; - return true; -} - -bool Texture::UpdateData( - const std::shared_ptr& imgData) { - std::size_t imgSize = imgData->width() * imgData->height() * 3; - - if (static_cast(data_size_) < imgSize) { - if (!data_) { - delete[] data_; - } - - data_ = new GLubyte[imgSize]; - if (data_ == nullptr) { - data_size_ = 0; - return false; - } - data_size_ = static_cast(imgSize); - is_size_changed_ = true; - } - - texture_format_ = GL_RGB; - if (imgData->encoding() == std::string("yuyv")) { - const GLubyte* src = - reinterpret_cast(imgData->data().c_str()); - - GLubyte* dst = data_; - for (std::size_t i = 0; i < imgData->data().size(); i += 4) { - int y = 298 * (src[i] - 16); - int u = src[i + 1] - 128; - int u1 = 516 * u; - int v = src[i + 3] - 128; - int v1 = 208 * v; - - u *= 100; - v *= 409; - -#define CLAMP(v) static_cast((v) > 255 ? 255 : ((v) < 0 ? 0 : v)) - *dst++ = CLAMP((y + v + 128) >> 8); - *dst++ = CLAMP((y - u - v1 + 128) >> 8); - *dst++ = CLAMP((y + u1 + 128) >> 8); - - y = 298 * (src[i + 2] - 16); - - *dst++ = CLAMP((y + v + 128) >> 8); - *dst++ = CLAMP((y - u - v1 + 128) >> 8); - *dst++ = CLAMP((y + u1 + 128) >> 8); -#undef CLAMP - } - } else if (imgData->encoding() == std::string("rgb8")) { - memcpy(data_, imgData->data().c_str(), imgSize); - } else if (imgData->encoding() == std::string("bgr8")) { - memcpy(data_, imgData->data().c_str(), imgSize); - texture_format_ = GL_BGR; - } else { - memset(data_, 0, imgSize); - std::cerr << "Cannot support this format (" << imgData->encoding() - << ") image" << std::endl; - } - is_dirty_ = true; - - image_height_ = imgData->height(); - image_width_ = imgData->width(); - - return true; -} diff --git a/modules/tools/visualizer/texture.h b/modules/tools/visualizer/texture.h deleted file mode 100644 index f84b040e68a..00000000000 --- a/modules/tools/visualizer/texture.h +++ /dev/null @@ -1,61 +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 "modules/common_msgs/sensor_msgs/sensor_image.pb.h" - -class Texture { - public: - Texture(void); - ~Texture() { - if (data_) { - delete[] data_; - data_ = nullptr; - } - } - - bool isSizeChanged(void) const { return is_size_changed_; } - bool isDirty(void) const { return is_dirty_; } - void removeDirty(void) { is_size_changed_ = is_dirty_ = false; } - void setDirty(void) { is_dirty_ = true; } - void setSizeChanged(void) { is_size_changed_ = is_dirty_ = true; } - - GLsizei width(void) const { return image_width_; } - GLsizei height(void) const { return image_height_; } - GLenum texture_format(void) const { return texture_format_; } - GLsizei data_size(void) const { return data_size_; } - - bool UpdateData(const QImage& img); - bool UpdateData(const std::shared_ptr&); - const GLubyte* data(void) const { return data_; } - - private: - struct { - int : 30; - bool is_size_changed_ : 1; - bool is_dirty_ : 1; - }; - GLenum texture_format_; - GLsizei image_width_; - GLsizei image_height_; - GLsizei data_size_; - GLubyte* data_; -}; diff --git a/modules/tools/visualizer/treewidget.cc b/modules/tools/visualizer/treewidget.cc deleted file mode 100644 index d37fe652acf..00000000000 --- a/modules/tools/visualizer/treewidget.cc +++ /dev/null @@ -1,40 +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/tools/visualizer/treewidget.h" - -#include - -TreeWidget::TreeWidget(QWidget *parent) : QTreeWidget(parent) {} - -void TreeWidget::resizeEvent(QResizeEvent *event) { - QTreeWidget::resizeEvent(event); - int cw = width() / columnCount(); - for (int i = 0; i < columnCount(); ++i) { - setColumnWidth(i, cw); - } -} - -bool TreeWidget::event(QEvent *e) { - bool b = QTreeWidget::event(e); - if (e->type() == QEvent::Hide) { - emit visibilityChanged(false); - } - if (e->type() == QEvent::Show) { - emit visibilityChanged(true); - } - return b; -} diff --git a/modules/tools/visualizer/treewidget.h b/modules/tools/visualizer/treewidget.h deleted file mode 100644 index d0f03612853..00000000000 --- a/modules/tools/visualizer/treewidget.h +++ /dev/null @@ -1,34 +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 - -class TreeWidget : public QTreeWidget { - Q_OBJECT - - public: - explicit TreeWidget(QWidget *parent = nullptr); - ~TreeWidget() {} - - signals: - void visibilityChanged(bool); - - protected: - void resizeEvent(QResizeEvent *); - bool event(QEvent *e); -}; diff --git a/modules/tools/visualizer/uis/main_window.ui b/modules/tools/visualizer/uis/main_window.ui deleted file mode 100644 index f044d92f9cd..00000000000 --- a/modules/tools/visualizer/uis/main_window.ui +++ /dev/null @@ -1,508 +0,0 @@ - - - MainWindow - - - - 0 - 0 - 1139 - 754 - - - - - 0 - 0 - - - - CyberVisualizer - - - - :/images/app.ico:/images/app.ico - - - - - 0 - 0 - - - - - 100 - 100 - - - - - 16777215 - 16777215 - - - - - - - - 0 - 0 - - - - Qt::Horizontal - - - - true - - - - 0 - 0 - - - - - 320 - 16777215 - - - - Qt::ScrollBarAlwaysOff - - - Qt::ScrollBarAlwaysOff - - - QAbstractScrollArea::AdjustIgnored - - - false - - - QAbstractItemView::ScrollPerItem - - - - Title - - - - - Description - - - - - - Qt::Vertical - - - - - 0 - 0 - - - - - - - 0 - 0 - - - - - 0 - - - 0 - - - 0 - - - 0 - - - - - - - - - - - - 0 - 0 - 1139 - 25 - - - - - File - - - - - - - - - - - Help - - - - - - - View - - - - - - - - - Actions - - - - - - - - - - - - false - - - Qt::ToolButtonTextBesideIcon - - - false - - - TopToolBarArea - - - false - - - - - Exit - - - F10 - - - - - About - - - - - - :/images/pointcloud.png:/images/pointcloud.png - - - Show PointCloud - - - F4 - - - - - true - - - true - - - Global - - - F2 - - - - - false - - - - :/images/closeimage.png:/images/closeimage.png - - - Del Image - - - F7 - - - - - - :/images/grid.png:/images/grid.png - - - Show Grid - - - F3 - - - - - - :/images/images.png:/images/images.png - - - Add Images - - - F6 - - - - - - :/images/image.png:/images/image.png - - - Add Image - - - F5 - - - - - License - - - - - - :/images/play.png:/images/play.png - - - Play - - - F8 - - - - - true - - - - :/images/pause.png:/images/pause.png - - - Pause - - - F9 - - - - - - - - SceneViewer - QWidget -
scene_viewer.h
- 1 - - ChangeCameraType(int) - ResetCameraPosAttitude() - -
- - TreeWidget - QTreeWidget -
treewidget.h
-
-
- - - - - - actionExit - triggered() - MainWindow - close() - - - -1 - -1 - - - 199 - 149 - - - - - actionOpenImage - triggered() - MainWindow - ActionOpenImage() - - - -1 - -1 - - - 579 - 409 - - - - - actionPointCloud - triggered() - MainWindow - ActionOpenPointCloud() - - - -1 - -1 - - - 579 - 409 - - - - - actionDelImage - triggered() - MainWindow - ActionDelVideoImage() - - - -1 - -1 - - - 423 - 350 - - - - - actionAddGrid - triggered() - MainWindow - ActionAddGrid() - - - -1 - -1 - - - 423 - 350 - - - - - actionOpenImages - triggered() - MainWindow - ActionOpenImages() - - - -1 - -1 - - - 471 - 379 - - - - - actionDelImage - toggled(bool) - MainWindow - CloseVideoImgViewer(bool) - - - -1 - -1 - - - 489 - 400 - - - - - actionGlobal - triggered(bool) - treeWidget - setVisible(bool) - - - -1 - -1 - - - 148 - 413 - - - - - - - ActionOpenImage() - ActionOpenPointCloud() - ActionDelVideoImage() - ActionAddGrid() - ActionOpenImages() - CloseVideoImgViewer(bool) - - -
diff --git a/modules/tools/visualizer/uis/msg_dialog.ui b/modules/tools/visualizer/uis/msg_dialog.ui deleted file mode 100644 index d7539ed5460..00000000000 --- a/modules/tools/visualizer/uis/msg_dialog.ui +++ /dev/null @@ -1,78 +0,0 @@ - - - MessageDialog - - - Qt::ApplicationModal - - - - 0 - 0 - 438 - 172 - - - - Dialog - - - - - - CyberVisualizer - -One Visualization Tool for Presenting Cyber Channel Data - -F5 Play | Pause -Main View PointCloud view -Other Views have right button Menu - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - close - - - - - - - - - - - closePushButton - clicked() - MessageDialog - close() - - - 416 - 232 - - - 456 - 250 - - - - - diff --git a/modules/tools/visualizer/uis/scene_camera_dialog.ui b/modules/tools/visualizer/uis/scene_camera_dialog.ui deleted file mode 100644 index af57a8cdab7..00000000000 --- a/modules/tools/visualizer/uis/scene_camera_dialog.ui +++ /dev/null @@ -1,326 +0,0 @@ - - - SceneCameraDialog - - - Qt::NonModal - - - - 0 - 0 - 287 - 214 - - - - - 0 - 0 - - - - - 287 - 214 - - - - Qt::DefaultContextMenu - - - SceneCamera - - - - - - Type - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - 5 - - - 5 - - - true - - - - Target - - - - - FREE - - - - - - - - Step - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - 1 - - - 100 - - - 1 - - - 5 - - - 8 - - - Qt::Horizontal - - - - - - - X: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - -1000.000000000000000 - - - 1000.000000000000000 - - - 0.000000000000000 - - - - - - - Y: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - -1000.000000000000000 - - - 1000.000000000000000 - - - - - - - Z: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - -1000.000000000000000 - - - 1000.000000000000000 - - - - - - - Yaw: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - 3 - - - -360.000000000000000 - - - 360.000000000000000 - - - 0.050000000000000 - - - - - - - Pitch: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - 3 - - - -90.000000000000000 - - - 90.000000000000000 - - - 0.050000000000000 - - - - - - - Roll: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - false - - - 3 - - - -90.000000000000000 - - - 90.000000000000000 - - - 0.050000000000000 - - - 0.000000000000000 - - - - - - - Qt::Horizontal - - - - 36 - 20 - - - - - - - - - 0 - 0 - - - - &Reset - - - - - - - Qt::Horizontal - - - - 29 - 20 - - - - - - - - - 0 - 0 - - - - &Ok - - - true - - - - - - - - - okButton - clicked() - SceneCameraDialog - close() - - - 210 - 192 - - - 188 - 210 - - - - - - resetcamera() - - diff --git a/modules/tools/visualizer/uis/video_images_dialog.ui b/modules/tools/visualizer/uis/video_images_dialog.ui deleted file mode 100644 index 3b81c55ca1e..00000000000 --- a/modules/tools/visualizer/uis/video_images_dialog.ui +++ /dev/null @@ -1,115 +0,0 @@ - - - VideoImagesDialog - - - - 0 - 0 - 194 - 78 - - - - - 0 - 0 - - - - - 194 - 78 - - - - Video Image Count Dialog - - - - - - Count: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - 1 - - - 10 - - - - - - - &Cancel - - - - - - - &Ok - - - false - - - false - - - true - - - - - - - - - cancelPushButton - clicked() - VideoImagesDialog - reject() - - - 72 - 71 - - - 141 - 8 - - - - - okPushButton - clicked() - VideoImagesDialog - accept() - - - 171 - 71 - - - 219 - 36 - - - - - diff --git a/modules/tools/visualizer/video_image_viewer.cc b/modules/tools/visualizer/video_image_viewer.cc deleted file mode 100644 index b8d9b7dbb96..00000000000 --- a/modules/tools/visualizer/video_image_viewer.cc +++ /dev/null @@ -1,120 +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/tools/visualizer/video_image_viewer.h" - -#include - -VideoImgViewer::VideoImgViewer(QWidget* parent) - : QOpenGLWidget(parent), - QOpenGLFunctions(), - is_init_(false), - mvp_id_(), - plane_(), - ortho_camera_(), - default_image_(nullptr), - video_image_shader_prog_(nullptr) {} - -VideoImgViewer::~VideoImgViewer() { - if (is_init_) { - is_init_ = false; - - makeCurrent(); - - plane_.Destroy(); - video_image_shader_prog_->destroyed(); - video_image_shader_prog_.reset(); - default_image_.reset(); - - doneCurrent(); - } -} - -void VideoImgViewer::initializeGL() { - initializeOpenGLFunctions(); - - glPointSize(1.0f); - glClearColor(0.0f, 0.0f, 0.0f, 1.0f); - - QImage noImage; - if (!noImage.load(tr(":/images/no_image.png"))) { - std::cout << "--------can not load the default texture------------" - << std::endl; - return; - } - - default_image_ = std::make_shared(); - if (default_image_ == nullptr || !default_image_->UpdateData(noImage)) { - std::cout << "--------can not create the default texture------------" - << std::endl; - return; - } - - video_image_shader_prog_ = RenderableObject::CreateShaderProgram( - tr(":/shaders/video_image_plane.vert"), - tr(":/shaders/video_image_plane.frag")); - if (video_image_shader_prog_ == nullptr) { - return; - } - - plane_.set_texture(default_image_); - if (!plane_.Init(video_image_shader_prog_)) { - return; - } - - ortho_camera_.set_near_plane_width(GLfloat(width())); - ortho_camera_.set_near_plane_height(GLfloat(height())); - - ortho_camera_.set_fov(static_cast(height())); - ortho_camera_.set_camera_mode(AbstractCamera::CameraMode::OrthoMode); - ortho_camera_.set_position(0.0f, 0.0f, 0.0f); - - ortho_camera_.UpdateWorld(); - ortho_camera_.UpdateProjection(); - - QMatrix4x4 mvp = - ortho_camera_.projection_matrix() * ortho_camera_.model_view_matrix(); - - video_image_shader_prog_->bind(); - video_image_shader_prog_->setUniformValue(mvp_id_, mvp); - video_image_shader_prog_->release(); - - is_init_ = true; -} - -void VideoImgViewer::resizeGL(int width, int height) { - glViewport(0, 0, (GLsizei)width, (GLsizei)height); - - if (is_init_) { - ortho_camera_.set_fov(static_cast(height)); - ortho_camera_.set_near_plane_width(GLfloat(width)); - ortho_camera_.set_near_plane_height(GLfloat(height)); - ortho_camera_.UpdateProjection(); - - QMatrix4x4 mvp = - ortho_camera_.projection_matrix() * ortho_camera_.model_view_matrix(); - - video_image_shader_prog_->bind(); - video_image_shader_prog_->setUniformValue(mvp_id_, mvp); - video_image_shader_prog_->release(); - } -} - -void VideoImgViewer::paintGL() { - if (is_init_) { - plane_.Render(); - } -} diff --git a/modules/tools/visualizer/video_image_viewer.h b/modules/tools/visualizer/video_image_viewer.h deleted file mode 100644 index 287e6054370..00000000000 --- a/modules/tools/visualizer/video_image_viewer.h +++ /dev/null @@ -1,48 +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 "modules/tools/visualizer/free_camera.h" -#include "modules/tools/visualizer/plane.h" - -class Texture; -class FixedAspectRatioWidget; - -class VideoImgViewer : public QOpenGLWidget, protected QOpenGLFunctions { - public: - explicit VideoImgViewer(QWidget* parent = nullptr); - ~VideoImgViewer(); - - protected: - void initializeGL() override; - void resizeGL(int w, int h) override; - void paintGL() override; - - private: - bool is_init_; - int mvp_id_; - - Plane plane_; - FreeCamera ortho_camera_; - std::shared_ptr default_image_; - - std::shared_ptr video_image_shader_prog_; - friend class FixedAspectRatioWidget; -}; diff --git a/modules/tools/visualizer/video_images_dialog.cc b/modules/tools/visualizer/video_images_dialog.cc deleted file mode 100644 index 61c44deeb55..00000000000 --- a/modules/tools/visualizer/video_images_dialog.cc +++ /dev/null @@ -1,27 +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/tools/visualizer/video_images_dialog.h" -#include "modules/tools/visualizer/ui_video_images_dialog.h" - -VideoImagesDialog::VideoImagesDialog(QWidget *parent) - : QDialog(parent), ui(new Ui::VideoImagesDialog) { - ui->setupUi(this); -} - -VideoImagesDialog::~VideoImagesDialog() { delete ui; } - -int VideoImagesDialog::count(void) const { return ui->spinBox->value(); } diff --git a/modules/tools/visualizer/video_images_dialog.h b/modules/tools/visualizer/video_images_dialog.h deleted file mode 100644 index e9dd06bbe76..00000000000 --- a/modules/tools/visualizer/video_images_dialog.h +++ /dev/null @@ -1,36 +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 - -namespace Ui { -class VideoImagesDialog; -} - -class VideoImagesDialog : public QDialog { - Q_OBJECT - - public: - explicit VideoImagesDialog(QWidget *parent = nullptr); - ~VideoImagesDialog(); - - int count(void) const; - - private: - Ui::VideoImagesDialog *ui; -}; diff --git a/modules/transform/BUILD b/modules/transform/BUILD index a8619be2266..e10c196d656 100644 --- a/modules/transform/BUILD +++ b/modules/transform/BUILD @@ -111,7 +111,6 @@ install( library_dest = "transform/lib", data = [ ":runtime_data", - "cyberfile.xml", "transform.BUILD", ], targets = [ diff --git a/modules/transform/cyberfile.xml b/modules/transform/cyberfile.xml deleted file mode 100644 index 414412799dd..00000000000 --- a/modules/transform/cyberfile.xml +++ /dev/null @@ -1,25 +0,0 @@ - - transform - local - - Apollo transform module. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - - common-dev - common-msgs-dev - 3rd-gtest-dev - 3rd-absl-dev - 3rd-yaml-cpp-dev - 3rd-tf2-dev - - //modules/transform - - diff --git a/modules/v2x/BUILD b/modules/v2x/BUILD deleted file mode 100644 index b604516454e..00000000000 --- a/modules/v2x/BUILD +++ /dev/null @@ -1,85 +0,0 @@ -load("//tools/install:install.bzl", "install", "install_files", "install_src_files") - -package(default_visibility = ["//visibility:public"]) - -filegroup( - name = "v2x_testdata", - srcs = glob(["fusion/test_data/*"]), -) - -install( - name = "testdata", - data = [ - ":v2x_testdata" - ], - data_dest = "v2x/addition_data" -) - - -install( - name = "install", - data_dest = "v2x", - data = [ - ":runtime_data", - ":cyberfile.xml", - ":v2x.BUILD", - ], - deps = [ - "//modules/v2x/fusion/apps:install", - ":pb_hdrs", - "//modules/v2x/v2x_proxy/app:install", - "testdata", - "//modules/v2x/proto:py_pb_v2x" - ], -) - -install( - name = "pb_hdrs", - data_dest = "v2x/include", - data = [ - "//modules/v2x/proto:fusion_params_cc_proto", - "//modules/v2x/proto:v2x_car_status_cc_proto", - "//modules/v2x/proto:v2x_junction_cc_proto", - "//modules/v2x/proto:v2x_monitor_cc_proto", - "//modules/v2x/proto:v2x_obstacles_cc_proto", - "//modules/v2x/proto:v2x_obu_rsi_cc_proto", - "//modules/v2x/proto:v2x_obu_traffic_light_cc_proto", - "//modules/v2x/proto:v2x_rsi_cc_proto", - "//modules/v2x/proto:v2x_service_car_to_obu_cc_proto", - "//modules/v2x/proto:v2x_service_obu_to_car_cc_proto", - "//modules/v2x/proto:v2x_traffic_light_policy_cc_proto", - ], -) - -install_src_files( - name = "install_src", - deps = [ - ":install_v2x_src", - ":install_v2x_hdrs" - ], -) - -install_src_files( - name = "install_v2x_src", - src_dir = ["."], - dest = "v2x/src", - filter = "*", -) - -install_src_files( - name = "install_v2x_hdrs", - src_dir = ["."], - dest = "v2x/include", - filter = "*.h", -) - -filegroup( - name = "runtime_data", - srcs = glob([ - "conf/*.conf", - "dag/*.dag", - "data/**", - "launch/*.launch", - "fusion/test_data/**", - ]), -) diff --git a/modules/v2x/common/BUILD b/modules/v2x/common/BUILD deleted file mode 100644 index 7d092424590..00000000000 --- a/modules/v2x/common/BUILD +++ /dev/null @@ -1,15 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_library") -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -cc_library( - name = "v2x_proxy_gflags", - srcs = ["v2x_proxy_gflags.cc"], - hdrs = ["v2x_proxy_gflags.h"], - deps = [ - "@com_github_gflags_gflags//:gflags", - ], -) - -cpplint() diff --git a/modules/v2x/common/v2x_proxy_gflags.cc b/modules/v2x/common/v2x_proxy_gflags.cc deleted file mode 100644 index 568766e7ec7..00000000000 --- a/modules/v2x/common/v2x_proxy_gflags.cc +++ /dev/null @@ -1,55 +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. - *****************************************************************************/ - -/** - * @file v2x_proxy_gflags.cc - * @brief The gflags used by v2x proxy module - */ - -#include "modules/v2x/common/v2x_proxy_gflags.h" - -namespace apollo { -namespace v2x { - -// IP & PORT -DEFINE_string(grpc_client_host, "127.0.0.1", "grpc client host ip"); -DEFINE_string(grpc_server_host, "127.0.0.1", "grpc server host ip"); -DEFINE_string(grpc_client_port, "50100", "grpc client port"); -DEFINE_string(grpc_server_port, "50101", "grpc server port"); -DEFINE_string(grpc_debug_server_port, "50102", "grpc server debug port"); - -// Other Flags -DEFINE_int64(x2v_traffic_light_timer_frequency, 10, - "x2v traffic_light timer frequency"); -DEFINE_int64(v2x_car_status_timer_frequency, 10, - "v2x car_status timer frequency"); -DEFINE_double(traffic_light_distance, 250.0, "traffic light distance in m"); -DEFINE_double(heading_difference, 30.0 / 180.0, - "max heading difference in rad"); -DEFINE_int64(list_size, 6, "size of list which stores the traffic light data"); -DEFINE_int64(msg_timeout, 250, "timeout value which getting the msg from OBU"); -DEFINE_int64(sim_sending_num, 10, "the max sending times"); -DEFINE_bool(use_nearest_flag, true, - "use the hdmap interface get_forward_nearest_signals_on_lane flag"); -DEFINE_int64(spat_period, 150, "SPAT message period in ms"); -DEFINE_double(check_time, 0.5, "SPAT message period in s"); -DEFINE_int64(rsu_whitelist_period, 3 * 1000, - "get whitelist period in ms"); // 3s -DEFINE_string(rsu_whitelist_name, "/apollo/modules/v2x/conf/rsu_whitelist.txt", - "file name for RSU whitelist"); - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/common/v2x_proxy_gflags.h b/modules/v2x/common/v2x_proxy_gflags.h deleted file mode 100644 index fdb2c601b6c..00000000000 --- a/modules/v2x/common/v2x_proxy_gflags.h +++ /dev/null @@ -1,51 +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. - *****************************************************************************/ - -/** - * @file v2x_proxy_gflags.h - * @brief The gflags used by v2x proxy module - */ - -#pragma once - -#include "gflags/gflags.h" - -namespace apollo { -namespace v2x { - -// IP & PORT -DECLARE_string(grpc_client_host); -DECLARE_string(grpc_server_host); -DECLARE_string(grpc_client_port); -DECLARE_string(grpc_server_port); -DECLARE_string(grpc_debug_server_port); - -// Other Flags -DECLARE_int64(x2v_traffic_light_timer_frequency); -DECLARE_int64(v2x_car_status_timer_frequency); -DECLARE_double(traffic_light_distance); -DECLARE_double(heading_difference); -DECLARE_int64(list_size); -DECLARE_int64(msg_timeout); -DECLARE_int64(sim_sending_num); -DECLARE_bool(use_nearest_flag); -DECLARE_int64(spat_period); -DECLARE_double(check_time); -DECLARE_int64(rsu_whitelist_period); -DECLARE_string(rsu_whitelist_name); - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/conf/v2x.conf b/modules/v2x/conf/v2x.conf deleted file mode 100644 index 2a3358f1f04..00000000000 --- a/modules/v2x/conf/v2x.conf +++ /dev/null @@ -1,7 +0,0 @@ ---x2v_traffic_light_timer_frequency=10 ---v2x_car_status_timer_frequency=10 ---grpc_client_host=192.168.10.21 ---grpc_server_host=192.168.10.6 ---hdmap_file_name=/apollo/modules/map/data/sunnyvale_big_loop/base_map.bin ---rsu_whitelist_name=/apollo/modules/v2x/conf/rsu_whitelist.txt - diff --git a/modules/v2x/conf/v2x_fusion_tracker.conf b/modules/v2x/conf/v2x_fusion_tracker.conf deleted file mode 100644 index b5b05135db6..00000000000 --- a/modules/v2x/conf/v2x_fusion_tracker.conf +++ /dev/null @@ -1,3 +0,0 @@ ---config_path=/apollo/modules/v2x/data ---fusion_conf_file=fusion_params.pt ---input_conf_file=app_config.pt diff --git a/modules/v2x/cyberfile.xml b/modules/v2x/cyberfile.xml deleted file mode 100644 index ecb25eec528..00000000000 --- a/modules/v2x/cyberfile.xml +++ /dev/null @@ -1,30 +0,0 @@ - - v2x - local - - Apollo v2x module. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //modules/v2x - - cyber-dev - common-dev - common-msgs-dev - bazel-extend-tools-dev - map-dev - perception-dev - 3rd-gflags-dev - 3rd-gtest-dev - 3rd-boost-dev - 3rd-absl-dev - 3rd-eigen3-dev - - - diff --git a/modules/v2x/dag/v2x_perception_fusion.dag b/modules/v2x/dag/v2x_perception_fusion.dag deleted file mode 100644 index 6a594a12915..00000000000 --- a/modules/v2x/dag/v2x_perception_fusion.dag +++ /dev/null @@ -1,17 +0,0 @@ -# Define all coms in DAG streaming. -module_config { - module_library : "/apollo/bazel-bin/modules/v2x/fusion/apps/libv2x_fusion_component.so" - - components { - class_name : "V2XFusionComponent" - config { - name : "v2x_fusion" - flag_file_path : "/apollo/modules/v2x/conf/v2x_fusion_tracker.conf" - readers: [ - { - channel: "/perception/vehicle/obstacles" - } - ] - } - } -} diff --git a/modules/v2x/data/fusion_params.pt b/modules/v2x/data/fusion_params.pt deleted file mode 100644 index 19a1d3bceff..00000000000 --- a/modules/v2x/data/fusion_params.pt +++ /dev/null @@ -1,9 +0,0 @@ -score_params { - prob_scale: 0.125 - max_match_distance: 10 - min_score: 0 - use_mahalanobis_distance: true - check_type: false - confidence_level: C99P -} - diff --git a/modules/v2x/fusion/apps/BUILD b/modules/v2x/fusion/apps/BUILD deleted file mode 100644 index 683e9929a4f..00000000000 --- a/modules/v2x/fusion/apps/BUILD +++ /dev/null @@ -1,53 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library", "cc_test") -load("//tools/install:install.bzl", "install") -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -install( - name = "install", - library_dest = "v2x/lib/fusion/apps", - targets = [ - ":libv2x_fusion_component.so", - ] -) - -cc_library( - name = "v2x_fusion_component_lib", - srcs = ["v2x_fusion_component.cc"], - hdrs = ["v2x_fusion_component.h"], - copts = [ - "-DMODULE_NAME=\\\"v2x_fusion\\\"", - ], - deps = [ - "//cyber", - "//modules/common/adapters:adapter_gflags", - "//modules/v2x/fusion/apps/common:trans_tools", - "//modules/v2x/fusion/configs:ft_config_manager", - "//modules/v2x/fusion/configs:fusion_tracker_gflags", - "//modules/v2x/fusion/libs/fusion", - ], - alwayslink = True, -) - -cc_binary( - name = "libv2x_fusion_component.so", - linkshared = True, - linkstatic = True, - deps = [":v2x_fusion_component_lib"], -) - -cc_test( - name = "v2x_fusion_component_test", - size = "small", - srcs = ["v2x_fusion_component_test.cc"], - linkopts = [ - "-lgomp", - ], - deps = [ - ":v2x_fusion_component_lib", - "@com_google_googletest//:gtest_main", - ], -) - -cpplint() diff --git a/modules/v2x/fusion/apps/common/BUILD b/modules/v2x/fusion/apps/common/BUILD deleted file mode 100644 index bb360b4ac08..00000000000 --- a/modules/v2x/fusion/apps/common/BUILD +++ /dev/null @@ -1,27 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_library") -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -cc_library( - name = "ft_definitions", - hdrs = ["ft_definitions.h"], - deps = [ - "//modules/common_msgs/localization_msgs:localization_cc_proto", - "//modules/common_msgs/perception_msgs:perception_camera_cc_proto", - "//modules/v2x/fusion/libs/common:v2x_object", - "//modules/v2x/proto:v2x_obstacles_cc_proto", - ], -) - -cc_library( - name = "trans_tools", - srcs = ["trans_tools.cc"], - hdrs = ["trans_tools.h"], - copts = ['-DMODULE_NAME=\\"v2x_fusion\\"'], - deps = [ - ":ft_definitions", - ], -) - -cpplint() diff --git a/modules/v2x/fusion/apps/common/ft_definitions.h b/modules/v2x/fusion/apps/common/ft_definitions.h deleted file mode 100644 index 00b7c32f8c7..00000000000 --- a/modules/v2x/fusion/apps/common/ft_definitions.h +++ /dev/null @@ -1,44 +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/common_msgs/localization_msgs/localization.pb.h" -#include "modules/common_msgs/perception_msgs/perception_obstacle.pb.h" -#include "modules/v2x/proto/v2x_obstacles.pb.h" - -#include "modules/v2x/fusion/libs/common/v2x_object.h" - -namespace apollo { -namespace v2x { -namespace ft { - -using apollo::localization::LocalizationEstimate; -using apollo::perception::PerceptionObstacle; -using apollo::perception::PerceptionObstacles; -using apollo::v2x::V2XObstacle; -using apollo::v2x::V2XObstacles; -using apollo::v2x::ft::base::Object; - -using PerceptionObstaclesPtr = std::shared_ptr; -using V2XObstaclesPtr = std::shared_ptr; -using StatusPtr = std::shared_ptr; - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/apps/common/trans_tools.cc b/modules/v2x/fusion/apps/common/trans_tools.cc deleted file mode 100644 index f06f9b16d5b..00000000000 --- a/modules/v2x/fusion/apps/common/trans_tools.cc +++ /dev/null @@ -1,526 +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/v2x/fusion/apps/common/trans_tools.h" - -#include - -namespace apollo { -namespace v2x { -namespace ft { - -void Pb2Object(const PerceptionObstacle &obstacle, base::Object *object, - const std::string &frame_id, double timestamp_object) { - Eigen::Vector3d value; - Eigen::Matrix3d variance; - variance.setIdentity(); - object->type_probs.push_back(0.85); - object->sub_type_probs.push_back(0.85); - object->type = static_cast(obstacle.type()); - variance = variance * 1; - switch (obstacle.sub_type()) { - case PerceptionObstacle::ST_UNKNOWN: - object->sub_type = base::ObjectSubType::UNKNOWN; - variance = variance * 3; - break; - - case PerceptionObstacle::ST_UNKNOWN_MOVABLE: - object->sub_type = base::ObjectSubType::UNKNOWN_MOVABLE; - variance = variance * 2; - break; - - case PerceptionObstacle::ST_CAR: - object->sub_type = base::ObjectSubType::CAR; - variance = variance * 0.8; - break; - - case PerceptionObstacle::ST_VAN: - object->sub_type = base::ObjectSubType::VAN; - variance = variance * 1; - break; - - case PerceptionObstacle::ST_TRUCK: - object->sub_type = base::ObjectSubType::TRUCK; - variance = variance * 3; - break; - - case PerceptionObstacle::ST_BUS: - object->sub_type = base::ObjectSubType::BUS; - variance = variance * 3; - break; - - case PerceptionObstacle::ST_CYCLIST: - object->sub_type = base::ObjectSubType::CYCLIST; - variance = variance * 0.8; - break; - - case PerceptionObstacle::ST_MOTORCYCLIST: - object->sub_type = base::ObjectSubType::MOTORCYCLIST; - variance = variance * 0.8; - break; - - case PerceptionObstacle::ST_TRICYCLIST: - object->sub_type = base::ObjectSubType::TRICYCLIST; - variance = variance * 0.8; - break; - - case PerceptionObstacle::ST_PEDESTRIAN: - object->sub_type = base::ObjectSubType::PEDESTRIAN; - variance = variance * 0.8; - break; - - case PerceptionObstacle::ST_TRAFFICCONE: - object->sub_type = base::ObjectSubType::TRAFFICCONE; - variance = variance * 0.8; - break; - - default: - break; - } - if (obstacle.has_timestamp()) { - object->timestamp = obstacle.timestamp(); - } else { - object->timestamp = timestamp_object; - } - value << obstacle.position().x(), obstacle.position().y(), 0.0; - object->position.Set(value, variance); - value << obstacle.velocity().x(), obstacle.velocity().y(), - obstacle.velocity().z(); - object->velocity.Set(value, variance); - object->theta.Set(obstacle.theta(), 0.5); - object->sensor_type = base::SensorType::MONOCULAR_CAMERA; - object->track_id = obstacle.id(); - object->frame_id = frame_id; - variance.setIdentity(); - value << obstacle.length(), obstacle.width(), obstacle.height(); - object->size.Set(value, variance); - std::vector polygon_info3d; - for (auto &polygon_point : obstacle.polygon_point()) { - base::Info3d point; - value << polygon_point.x(), polygon_point.y(), polygon_point.z(); - point.Set(value, variance); - polygon_info3d.push_back(point); - } - object->polygon = polygon_info3d; -} - -void V2xPb2Object(const apollo::v2x::V2XObstacle &obstacle, - base::Object *object, const std::string &frame_id, - double timestamp_object) { - Pb2Object(obstacle.perception_obstacle(), object, frame_id, timestamp_object); - if (obstacle.has_v2x_info() && obstacle.v2x_info().v2x_type_size() > 0 && - obstacle.v2x_info().v2x_type(0) == - ::apollo::v2x::V2XInformation::ZOMBIES_CAR) { - object->v2x_type = base::V2xType::ZOMBIES_CAR; - } -} - -base::Object Pb2Object(const PerceptionObstacle &obstacle, - const std::string &frame_id) { - base::Object object; - Eigen::Vector3d value; - Eigen::Matrix3d variance; - variance.setIdentity(); - object.timestamp = obstacle.timestamp(); - // object - value << obstacle.position().x(), obstacle.position().y(), - obstacle.position().z(); - - object.position.Set(value, variance); - value << obstacle.velocity().x(), obstacle.velocity().y(), - obstacle.velocity().z(); - object.velocity.Set(value, variance); - object.theta.Set(obstacle.theta(), 0.5); - object.sensor_type = base::SensorType::MONOCULAR_CAMERA; - object.track_id = obstacle.id(); - object.frame_id = frame_id; - value << obstacle.length(), obstacle.width(), obstacle.height(); - object.size.Set(value, variance); - object.type_probs.push_back(0.85); - object.sub_type_probs.push_back(0.85); - object.type = static_cast(obstacle.type()); - switch (obstacle.sub_type()) { - case PerceptionObstacle::ST_UNKNOWN: - object.sub_type = base::ObjectSubType::UNKNOWN; - break; - - case PerceptionObstacle::ST_UNKNOWN_MOVABLE: - object.sub_type = base::ObjectSubType::UNKNOWN_MOVABLE; - break; - - case PerceptionObstacle::ST_CAR: - object.sub_type = base::ObjectSubType::CAR; - break; - - case PerceptionObstacle::ST_VAN: - object.sub_type = base::ObjectSubType::VAN; - break; - - case PerceptionObstacle::ST_TRUCK: - object.sub_type = base::ObjectSubType::TRUCK; - break; - - case PerceptionObstacle::ST_BUS: - object.sub_type = base::ObjectSubType::BUS; - break; - - case PerceptionObstacle::ST_CYCLIST: - object.sub_type = base::ObjectSubType::CYCLIST; - break; - - case PerceptionObstacle::ST_MOTORCYCLIST: - object.sub_type = base::ObjectSubType::MOTORCYCLIST; - break; - - case PerceptionObstacle::ST_TRICYCLIST: - object.sub_type = base::ObjectSubType::TRICYCLIST; - break; - - case PerceptionObstacle::ST_PEDESTRIAN: - object.sub_type = base::ObjectSubType::PEDESTRIAN; - break; - - case PerceptionObstacle::ST_TRAFFICCONE: - object.sub_type = base::ObjectSubType::TRAFFICCONE; - break; - - default: - break; - } - return object; -} - -PerceptionObstacle Object2Pb(const base::Object &object) { - PerceptionObstacle obstacle; - // times - obstacle.set_timestamp(object.timestamp); - // id - obstacle.set_id(object.track_id); - // position - obstacle.mutable_position()->set_x(object.position.x()); - obstacle.mutable_position()->set_y(object.position.y()); - obstacle.mutable_position()->set_z(object.position.z()); - // velocity - obstacle.mutable_velocity()->set_x(object.velocity.x()); - obstacle.mutable_velocity()->set_y(object.velocity.y()); - obstacle.mutable_velocity()->set_z(object.velocity.z()); - // yaw - obstacle.set_theta(object.theta.Value()); - // lwh - obstacle.set_length(object.size.length()); - obstacle.set_width(object.size.width()); - obstacle.set_height(object.size.height()); - obstacle.set_type(static_cast(object.type)); - switch (object.sub_type) { - case base::ObjectSubType::UNKNOWN: - obstacle.set_sub_type(PerceptionObstacle::ST_UNKNOWN); - break; - - case base::ObjectSubType::UNKNOWN_MOVABLE: - obstacle.set_sub_type(PerceptionObstacle::ST_UNKNOWN_MOVABLE); - break; - - case base::ObjectSubType::CAR: - obstacle.set_sub_type(PerceptionObstacle::ST_CAR); - break; - - case base::ObjectSubType::VAN: - obstacle.set_sub_type(PerceptionObstacle::ST_VAN); - break; - - case base::ObjectSubType::TRUCK: - obstacle.set_sub_type(PerceptionObstacle::ST_TRUCK); - break; - - case base::ObjectSubType::BUS: - obstacle.set_sub_type(PerceptionObstacle::ST_BUS); - break; - - case base::ObjectSubType::CYCLIST: - obstacle.set_sub_type(PerceptionObstacle::ST_CYCLIST); - break; - - case base::ObjectSubType::MOTORCYCLIST: - obstacle.set_sub_type(PerceptionObstacle::ST_MOTORCYCLIST); - break; - - case base::ObjectSubType::TRICYCLIST: - obstacle.set_sub_type(PerceptionObstacle::ST_TRICYCLIST); - break; - - case base::ObjectSubType::PEDESTRIAN: - obstacle.set_sub_type(PerceptionObstacle::ST_PEDESTRIAN); - break; - - case base::ObjectSubType::TRAFFICCONE: - obstacle.set_sub_type(PerceptionObstacle::ST_TRAFFICCONE); - break; - - default: - break; - } - return obstacle; -} - -void FillObjectPolygonFromBBox3D(PerceptionObstacle *object_ptr) { - struct PolygoPoint { - double x = 0.0; - double y = 0.0; - double z = 0.0; - }; - - if (!object_ptr) { - return; - } - const double length = object_ptr->length(); - const double width = object_ptr->width(); - double hl = length / 2; - double hw = width / 2; - double cos_theta = std::cos(object_ptr->theta()); - double sin_theta = std::sin(object_ptr->theta()); - PolygoPoint polygon[4]; - polygon[0].x = hl * cos_theta - hw * sin_theta + object_ptr->position().x(); - polygon[0].y = hl * sin_theta + hw * cos_theta + object_ptr->position().y(); - polygon[0].z = object_ptr->position().z(); - polygon[1].x = hl * cos_theta + hw * sin_theta + object_ptr->position().x(); - polygon[1].y = hl * sin_theta - hw * cos_theta + object_ptr->position().y(); - polygon[1].z = object_ptr->position().z(); - polygon[2].x = -hl * cos_theta + hw * sin_theta + object_ptr->position().x(); - polygon[2].y = -hl * sin_theta - hw * cos_theta + object_ptr->position().y(); - polygon[2].z = object_ptr->position().z(); - polygon[3].x = -hl * cos_theta - hw * sin_theta + object_ptr->position().x(); - polygon[3].y = -hl * sin_theta + hw * cos_theta + object_ptr->position().y(); - polygon[3].z = object_ptr->position().z(); - for (PolygoPoint point : polygon) { - auto polygon_point = object_ptr->add_polygon_point(); - polygon_point->set_x(point.x); - polygon_point->set_y(point.y); - polygon_point->set_z(point.z); - } -} - -void Object2Pb(const base::Object &object, PerceptionObstacle *obstacle) { - // times - obstacle->set_timestamp(object.timestamp); - // id - obstacle->set_id(object.track_id); - // position - obstacle->mutable_position()->set_x(object.position.x()); - obstacle->mutable_position()->set_y(object.position.y()); - obstacle->mutable_position()->set_z(object.position.z()); - // velocity - obstacle->mutable_velocity()->set_x(object.velocity.x()); - obstacle->mutable_velocity()->set_y(object.velocity.y()); - obstacle->mutable_velocity()->set_z(object.velocity.z()); - // yaw - obstacle->set_theta(object.theta.Value()); - // lwh - obstacle->set_length(object.size.length()); - obstacle->set_width(object.size.width()); - obstacle->set_height(object.size.height()); - FillObjectPolygonFromBBox3D(obstacle); - obstacle->set_type(static_cast(object.type)); - switch (object.sub_type) { - case base::ObjectSubType::UNKNOWN: - obstacle->set_sub_type(PerceptionObstacle::ST_UNKNOWN); - break; - - case base::ObjectSubType::UNKNOWN_MOVABLE: - obstacle->set_sub_type(PerceptionObstacle::ST_UNKNOWN_MOVABLE); - break; - - case base::ObjectSubType::UNKNOWN_UNMOVABLE: - obstacle->set_sub_type(PerceptionObstacle::ST_UNKNOWN_UNMOVABLE); - break; - - case base::ObjectSubType::CAR: - obstacle->set_sub_type(PerceptionObstacle::ST_CAR); - break; - - case base::ObjectSubType::VAN: - obstacle->set_sub_type(PerceptionObstacle::ST_VAN); - break; - - case base::ObjectSubType::TRUCK: - obstacle->set_sub_type(PerceptionObstacle::ST_TRUCK); - break; - - case base::ObjectSubType::BUS: - obstacle->set_sub_type(PerceptionObstacle::ST_BUS); - break; - - case base::ObjectSubType::CYCLIST: - obstacle->set_sub_type(PerceptionObstacle::ST_CYCLIST); - break; - - case base::ObjectSubType::MOTORCYCLIST: - obstacle->set_sub_type(PerceptionObstacle::ST_MOTORCYCLIST); - break; - - case base::ObjectSubType::TRICYCLIST: - obstacle->set_sub_type(PerceptionObstacle::ST_TRICYCLIST); - break; - - case base::ObjectSubType::PEDESTRIAN: - obstacle->set_sub_type(PerceptionObstacle::ST_PEDESTRIAN); - break; - - case base::ObjectSubType::TRAFFICCONE: - obstacle->set_sub_type(PerceptionObstacle::ST_TRAFFICCONE); - break; - - default: - break; - } - obstacle->set_source(PerceptionObstacle::HOST_VEHICLE); - if (object.v2x_type == base::V2xType::ZOMBIES_CAR) { - obstacle->mutable_v2x_info()->add_v2x_type( - ::apollo::perception::V2XInformation::ZOMBIES_CAR); - obstacle->set_source(PerceptionObstacle::V2X); - } - if (object.v2x_type == base::V2xType::BLIND_ZONE) { - obstacle->mutable_v2x_info()->add_v2x_type( - ::apollo::perception::V2XInformation::BLIND_ZONE); - obstacle->set_source(PerceptionObstacle::V2X); - } -} - -void Object2V2xPb(const base::Object &object, V2XObstacle *obstacle) { - PerceptionObstacle perception_obstacle; - Object2Pb(object, &perception_obstacle); - obstacle->mutable_perception_obstacle()->CopyFrom(perception_obstacle); -} - -double Pbs2Objects(const PerceptionObstacles &obstacles, - std::vector *objects, - const std::string &frame_id) { - double timestamp = std::numeric_limits::max(); - objects->clear(); - double timestamp_object = 0.0; - if (obstacles.perception_obstacle_size() > 0 && - obstacles.perception_obstacle(0).has_timestamp() == false) { - if (obstacles.header().has_camera_timestamp() && - obstacles.header().camera_timestamp() > 10.0) { - timestamp_object = obstacles.header().camera_timestamp() / 1.0e9; - } else { - timestamp_object = obstacles.header().lidar_timestamp() / 1.0e9; - } - } - for (int j = 0; j < obstacles.perception_obstacle_size(); ++j) { - base::Object object; - Pb2Object(obstacles.perception_obstacle(j), &object, frame_id, - timestamp_object); - objects->push_back(object); - if (timestamp > object.timestamp) { - timestamp = object.timestamp; - } - } - - return timestamp; -} - -void CarstatusPb2Object(const LocalizationEstimate &carstatus, - base::Object *object, const std::string &frame_id) { - Eigen::Vector3d value; - Eigen::Matrix3d variance; - variance.setIdentity(); - object->type_probs.push_back(0.85); - object->sub_type_probs.push_back(0.85); - object->type = base::ObjectType::VEHICLE; - object->sub_type = base::ObjectSubType::CAR; - object->v2x_type = base::V2xType::HOST_VEHICLE; - variance = variance * 0.8; - value << carstatus.pose().position().x(), carstatus.pose().position().y(), - 0.0; - object->position.Set(value, variance); - value << carstatus.pose().linear_velocity().x(), - carstatus.pose().linear_velocity().y(), - carstatus.pose().linear_velocity().z(); - object->velocity.Set(value, variance); - object->theta.Set(carstatus.pose().heading(), 0.5); - object->sensor_type = base::SensorType::MONOCULAR_CAMERA; - object->track_id = 0; - object->frame_id = frame_id; - variance.setIdentity(); - value << 5.02203, 2.13135, 2.17711; - object->size.Set(value, variance); - object->timestamp = carstatus.header().timestamp_sec(); -} - -double V2xPbs2Objects(const V2XObstacles &obstacles, - std::vector *objects, - const std::string &frame_id) { - double timestamp = std::numeric_limits::max(); - objects->clear(); - double timestamp_object = 0.0; - if (obstacles.v2x_obstacle_size() > 0 && - obstacles.v2x_obstacle(0).perception_obstacle().has_timestamp() == - false) { - if (obstacles.header().has_camera_timestamp()) { - timestamp_object = obstacles.header().camera_timestamp() / 1000000000.0; - } else { - timestamp_object = obstacles.header().lidar_timestamp() / 1000000000.0; - } - } - for (int j = 0; j < obstacles.v2x_obstacle_size(); ++j) { - base::Object object; - V2xPb2Object(obstacles.v2x_obstacle(j), &object, frame_id, - timestamp_object); - objects->push_back(object); - if (timestamp > object.timestamp) { - timestamp = object.timestamp; - } - } - - return timestamp; -} - -void Objects2Pbs(const std::vector &objects, - std::shared_ptr obstacles) { - obstacles->mutable_perception_obstacle()->Clear(); - if (objects.size() < 1) { - return; - } - // obstacles->mutable_header()->set_frame_id(objects[0].frame_id); - for (const auto &object : objects) { - if (object.v2x_type == base::V2xType::HOST_VEHICLE) { - continue; - } - PerceptionObstacle obstacle; - Object2Pb(object, &obstacle); - obstacles->add_perception_obstacle()->CopyFrom(obstacle); - } -} - -void Objects2V2xPbs(const std::vector &objects, - std::shared_ptr obstacles) { - obstacles->mutable_v2x_obstacle()->Clear(); - if (objects.size() < 1) { - return; - } - for (const auto &object : objects) { - if (object.v2x_type == base::V2xType::HOST_VEHICLE) { - continue; - } - V2XObstacle obstacle; - Object2V2xPb(object, &obstacle); - obstacles->add_v2x_obstacle()->CopyFrom(obstacle); - } -} - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/apps/common/trans_tools.h b/modules/v2x/fusion/apps/common/trans_tools.h deleted file mode 100644 index e21599bb46d..00000000000 --- a/modules/v2x/fusion/apps/common/trans_tools.h +++ /dev/null @@ -1,63 +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 "modules/v2x/fusion/apps/common/ft_definitions.h" - -namespace apollo { -namespace v2x { -namespace ft { - -base::Object Pb2Object(const PerceptionObstacle &obstacle, - const std::string &frame_id); -void Pb2Object(const PerceptionObstacle &obstacle, base::Object *object, - const std::string &frame_id, double timestamp_object = 0.0); - -void V2xPb2Object(const V2XObstacle &obstacle, base::Object *object, - const std::string &frame_id, double timestamp_object); - -void CarstatusPb2Object(const LocalizationEstimate &carstatus, - base::Object *object, const std::string &frame_id); - -double Pbs2Objects(const PerceptionObstacles &obstacles, - std::vector *objects, - const std::string &frame_id); - -double V2xPbs2Objects(const V2XObstacles &obstacles, - std::vector *objects, - const std::string &frame_id); - -PerceptionObstacle Object2Pb(const base::Object &object); -void FillObjectPolygonFromBBox3D(PerceptionObstacle *object_ptr); -void Object2Pb(const base::Object &object, PerceptionObstacle *obstacle); - -void Object2V2xPb(const base::Object &object, V2XObstacle *obstacle); -void Objects2Pbs(const std::vector &objects, - std::shared_ptr obstacles); - -void Objects2V2xPbs(const std::vector &objects, - std::shared_ptr obstacles); - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/apps/v2x_fusion_component.cc b/modules/v2x/fusion/apps/v2x_fusion_component.cc deleted file mode 100644 index 4c686111cdd..00000000000 --- a/modules/v2x/fusion/apps/v2x_fusion_component.cc +++ /dev/null @@ -1,101 +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/v2x/fusion/apps/v2x_fusion_component.h" - -namespace apollo { -namespace v2x { -namespace ft { - -V2XFusionComponent::~V2XFusionComponent() {} - -std::string V2XFusionComponent::Name() const { return FLAGS_v2x_module_name; } - -bool V2XFusionComponent::Init() { - v2x_obstacles_reader_ = - node_->CreateReader(FLAGS_v2x_obstacle_topic, nullptr); - localization_reader_ = node_->CreateReader( - FLAGS_localization_topic, nullptr); - perception_fusion_obstacles_writer_ = - node_->CreateWriter(FLAGS_perception_obstacle_topic); - return true; -} - -bool V2XFusionComponent::Proc( - const std::shared_ptr& perception_obstacles) { - if (FLAGS_use_v2x) { - return V2XMessageFusionProcess(perception_obstacles); - } - perception_fusion_obstacles_writer_->Write(*perception_obstacles); - return true; -} - -bool V2XFusionComponent::V2XMessageFusionProcess( - const std::shared_ptr& perception_obstacles) { - // Read localization info. and call OnLocalization to update - // the PoseContainer. - localization_reader_->Observe(); - auto localization_msg = localization_reader_->GetLatestObserved(); - if (localization_msg == nullptr) { - AERROR << "V2X: cannot receive any localization message."; - return false; - } - base::Object hv_obj; - CarstatusPb2Object(*localization_msg, &hv_obj, "VEHICLE"); - v2x_obstacles_reader_->Observe(); - auto v2x_obstacles_msg = v2x_obstacles_reader_->GetLatestObserved(); - if (v2x_obstacles_msg == nullptr) { - AERROR << "V2X: cannot receive any v2x obstacles message."; - perception_fusion_obstacles_writer_->Write(*perception_obstacles); - } else { - header_.CopyFrom(perception_obstacles->header()); - std::vector fused_objects; - std::vector v2x_fused_objects; - std::vector> fusion_result; - std::vector v2x_objects; - V2xPbs2Objects(*v2x_obstacles_msg, &v2x_objects, "V2X"); - std::vector perception_objects; - Pbs2Objects(*perception_obstacles, &perception_objects, "VEHICLE"); - perception_objects.push_back(hv_obj); - fusion_.CombineNewResource(perception_objects, &fused_objects, - &fusion_result); - fusion_.CombineNewResource(v2x_objects, &fused_objects, &fusion_result); - fusion_.GetV2xFusionObjects(fusion_result, &v2x_fused_objects); - auto output_msg = std::make_shared(); - SerializeMsg(v2x_fused_objects, output_msg); - perception_fusion_obstacles_writer_->Write(*output_msg); - } - return true; -} - -void V2XFusionComponent::SerializeMsg( - const std::vector& objects, - std::shared_ptr output_msg) { - static int seq_num = 0; - Objects2Pbs(objects, output_msg); - apollo::common::Header* header = output_msg->mutable_header(); - header->set_timestamp_sec(apollo::cyber::Time::Now().ToSecond()); - header->set_module_name("v2x_fusion"); - header->set_sequence_num(seq_num++); - header->set_lidar_timestamp(header_.lidar_timestamp()); - header->set_camera_timestamp(header_.camera_timestamp()); - header->set_radar_timestamp(header_.radar_timestamp()); - output_msg->set_error_code(apollo::common::ErrorCode::PERCEPTION_ERROR_NONE); -} - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/apps/v2x_fusion_component.h b/modules/v2x/fusion/apps/v2x_fusion_component.h deleted file mode 100644 index 45134b7e31a..00000000000 --- a/modules/v2x/fusion/apps/v2x_fusion_component.h +++ /dev/null @@ -1,71 +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 - */ - -#include -#include -#include -#include -#include -#include -#include - -#include "cyber/component/component.h" -#include "modules/common/adapters/adapter_gflags.h" -#include "modules/v2x/fusion/apps/common/trans_tools.h" -#include "modules/v2x/fusion/configs/ft_config_manager.h" -#include "modules/v2x/fusion/configs/fusion_tracker_gflags.h" -#include "modules/v2x/fusion/libs/fusion/fusion.h" - -namespace apollo { -namespace v2x { -namespace ft { - -class V2XFusionComponent - : public apollo::cyber::Component { - public: - ~V2XFusionComponent(); - - std::string Name() const; - - bool Init() override; - - bool Proc(const std::shared_ptr& perception_obstacles) - override; - - private: - bool V2XMessageFusionProcess( - const std::shared_ptr& perception_obstacles); - void SerializeMsg(const std::vector& objects, - std::shared_ptr obstacles); - Fusion fusion_; - - std::shared_ptr> - localization_reader_; - std::shared_ptr> v2x_obstacles_reader_; - std::shared_ptr> - perception_fusion_obstacles_writer_; - apollo::common::Header header_; -}; - -CYBER_REGISTER_COMPONENT(V2XFusionComponent) - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/apps/v2x_fusion_component_test.cc b/modules/v2x/fusion/apps/v2x_fusion_component_test.cc deleted file mode 100644 index 8ea9d69079f..00000000000 --- a/modules/v2x/fusion/apps/v2x_fusion_component_test.cc +++ /dev/null @@ -1,34 +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/v2x/fusion/apps/v2x_fusion_component.h" - -#include "gtest/gtest.h" - -#include "cyber/init.h" - -namespace apollo { -namespace v2x { -namespace ft { - -TEST(V2XFusionComponentTest, Simple) { - cyber::Init("v2x_fusion_component_test"); - V2XFusionComponent v2x_fusion_component; - EXPECT_EQ(v2x_fusion_component.Name(), "v2x_fusion"); -} - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/configs/BUILD b/modules/v2x/fusion/configs/BUILD deleted file mode 100644 index cf4ec570a5f..00000000000 --- a/modules/v2x/fusion/configs/BUILD +++ /dev/null @@ -1,37 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -cc_library( - name = "fusion_tracker_gflags", - srcs = ["fusion_tracker_gflags.cc"], - hdrs = ["fusion_tracker_gflags.h"], - deps = [ - "@com_github_gflags_gflags//:gflags", - ], -) - -cc_library( - name = "ft_config_manager", - srcs = ["ft_config_manager.cc"], - hdrs = ["ft_config_manager.h"], - deps = [ - ":fusion_tracker_gflags", - "//cyber", - "//modules/v2x/proto:fusion_params_cc_proto", - "@boost", - ], -) - -cc_test( - name = "ft_config_manager_test", - size = "small", - srcs = ["ft_config_manager_test.cc"], - deps = [ - ":ft_config_manager", - "@com_google_googletest//:gtest_main", - ], -) - -cpplint() diff --git a/modules/v2x/fusion/configs/ft_config_manager.cc b/modules/v2x/fusion/configs/ft_config_manager.cc deleted file mode 100644 index ee126d85bac..00000000000 --- a/modules/v2x/fusion/configs/ft_config_manager.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/v2x/fusion/configs/ft_config_manager.h" - -namespace apollo { -namespace v2x { -namespace ft { - -FTConfigManager::FTConfigManager() {} - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/configs/ft_config_manager.h b/modules/v2x/fusion/configs/ft_config_manager.h deleted file mode 100644 index 0420db05e90..00000000000 --- a/modules/v2x/fusion/configs/ft_config_manager.h +++ /dev/null @@ -1,58 +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 "modules/v2x/proto/fusion_params.pb.h" - -#include "cyber/cyber.h" -#include "modules/v2x/fusion/configs/fusion_tracker_gflags.h" - -#define PLUGIN_PARAMS(classname, conf_file, prototype) \ - class classname { \ - public: \ - classname() { \ - file_path_ = FLAGS_config_path + "/" + conf_file; \ - cyber::common::GetProtoFromFile(file_path_, ¶ms); \ - } \ - ~classname() { cyber::common::SetProtoToASCIIFile(params, file_path_); } \ - prototype params; \ - \ - private: \ - std::string file_path_; \ - }; - -namespace apollo { -namespace v2x { -namespace ft { - -PLUGIN_PARAMS(FusionParams, FLAGS_fusion_conf_file, fusion::FusionParams) - -class FTConfigManager { - public: - DECLARE_SINGLETON(FTConfigManager) - public: - FusionParams fusion_params_; -}; - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/configs/ft_config_manager_test.cc b/modules/v2x/fusion/configs/ft_config_manager_test.cc deleted file mode 100644 index 86ecac2a082..00000000000 --- a/modules/v2x/fusion/configs/ft_config_manager_test.cc +++ /dev/null @@ -1,33 +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/v2x/fusion/configs/ft_config_manager.h" - -#include "gtest/gtest.h" - -namespace apollo { -namespace v2x { -namespace ft { - -TEST(FTConfigManager, read_and_write) { - FTConfigManager* ft_config_manager_ptr = FTConfigManager::Instance(); - auto& fusion_params = ft_config_manager_ptr->fusion_params_.params; - EXPECT_FALSE(fusion_params.score_params().check_type()); - EXPECT_EQ(fusion_params.score_params().prob_scale(), 0.125); -} - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/configs/fusion_tracker_gflags.cc b/modules/v2x/fusion/configs/fusion_tracker_gflags.cc deleted file mode 100644 index a170070b6f7..00000000000 --- a/modules/v2x/fusion/configs/fusion_tracker_gflags.cc +++ /dev/null @@ -1,42 +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: fusion_gflags.cpp - * Brief: Global flags definition. - */ - -#include "modules/v2x/fusion/configs/fusion_tracker_gflags.h" - -namespace apollo { -namespace v2x { -namespace ft { - -// config manager -DEFINE_string(config_path, "/apollo/modules/v2x/data", - "ADU shared data path, including maps, routings..."); -DEFINE_string(v2x_module_name, "v2x_fusion", "name"); -DEFINE_string(v2x_fusion_obstacles_topic, "/apollo/msf/obstacles", - "perception obstacle topic name"); -DEFINE_bool(use_v2x, false, "use v2x"); -// fusion -DEFINE_string(fusion_conf_file, "fusion_params.pt", "the roi conf path"); -// app -DEFINE_string(app_conf_file, "app_config.pt", "the inputs conf path"); - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/configs/fusion_tracker_gflags.h b/modules/v2x/fusion/configs/fusion_tracker_gflags.h deleted file mode 100644 index d711cec7089..00000000000 --- a/modules/v2x/fusion/configs/fusion_tracker_gflags.h +++ /dev/null @@ -1,42 +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: fusion_gflags.h - * Brief: Global flags definition. - */ - -#pragma once - -#include "gflags/gflags.h" - -namespace apollo { -namespace v2x { -namespace ft { - -// config manager -DECLARE_string(config_path); -DECLARE_string(v2x_module_name); -DECLARE_string(v2x_fusion_obstacles_topic); -DECLARE_bool(use_v2x); -// fusion -DECLARE_string(fusion_conf_file); -// app -DECLARE_string(app_conf_file); - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/libs/common/BUILD b/modules/v2x/fusion/libs/common/BUILD deleted file mode 100644 index a464c732204..00000000000 --- a/modules/v2x/fusion/libs/common/BUILD +++ /dev/null @@ -1,29 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -cc_library( - name = "v2x_object", - hdrs = [ - "v2x_object.h", - ], - deps = [ - "//modules/perception/base:base_type", - "//modules/perception/base:box", - "//modules/perception/base:object", - "@com_google_absl//:absl", - ], -) - -cc_test( - name = "v2x_object_test", - size = "small", - srcs = ["v2x_object_test.cc"], - deps = [ - ":v2x_object", - "@com_google_googletest//:gtest_main", - ], -) - -cpplint() diff --git a/modules/v2x/fusion/libs/common/v2x_object.h b/modules/v2x/fusion/libs/common/v2x_object.h deleted file mode 100644 index 6e8c2c09e01..00000000000 --- a/modules/v2x/fusion/libs/common/v2x_object.h +++ /dev/null @@ -1,262 +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 "absl/strings/str_cat.h" - -#include "modules/perception/base/object_supplement.h" -#include "modules/perception/base/object_types.h" -#include "modules/perception/base/sensor_meta.h" - -namespace apollo { -namespace v2x { -namespace ft { -namespace base { - -using apollo::perception::base::CameraObjectSupplement; -using apollo::perception::base::FusionObjectSupplement; -using apollo::perception::base::ObjectSubType; -using apollo::perception::base::ObjectType; -using apollo::perception::base::SensorType; - -enum class V2xType { - UNKNOWN = 0, - ZOMBIES_CAR = 1, - BLIND_ZONE = 2, - HOST_VEHICLE = 13, -}; - -enum class MessageType { - UNKNOWN_MESSAGE_TYPE = -1, - ROADSIDE = 0, - VEHICLE = 1, -}; - -// Value and Variance -template -class Info { - public: - Info() = default; - Info(Val val, Var var) { - value_ = val; - variance_ = var; - } - ~Info() = default; - // Info(const Info &) = delete; - Info(const Info &rhs) { - value_ = rhs.value_; - variance_ = rhs.variance_; - } - // Info &operator=(const Info &) = delete; - Info &operator=(const Info &rhs) { - value_ = rhs.value_; - variance_ = rhs.variance_; - return *this; - } - - void Set(Val value, Var variance) { - value_ = value; - variance_ = variance; - } - Val Value() const { return value_; } - - Var Variance() const { return variance_; } - - protected: - Val value_ = {}; - Var variance_ = {}; -}; - -class Info3f : public Info { - public: - Info3f() { - value_.setZero(); - variance_.setZero(); - } - ~Info3f() = default; - - float x() const { return value_(0); } - - float y() const { return value_(1); } - - float z() const { return value_(2); } - - float length() const { return value_(0); } - - float width() const { return value_(1); } - - float height() const { return value_(2); } -}; - -class Info3d : public Info { - public: - double x() const { return value_(0); } - - double y() const { return value_(1); } - - double z() const { return value_(2); } - - double length() const { return value_(0); } - - double width() const { return value_(1); } - - double height() const { return value_(2); } -}; - -struct alignas(16) Object { - typedef Info Infob; - typedef Info Infof; - typedef Info Infod; - typedef Info Info2f; - typedef Info Info2d; - typedef Eigen::Vector2f Point2f; - typedef Eigen::Vector3f Point3f; - Object() : is_temporary_lost(false, 0.0) {} - ~Object() = default; - Object(const Object &) = default; - Object &operator=(const Object &) = default; - bool operator<(const Object &rhs) const { return timestamp < rhs.timestamp; } - bool operator>(const Object &rhs) const { return timestamp > rhs.timestamp; } - bool operator==(const Object &rhs) const { - return timestamp == rhs.timestamp; - } - std::string ToString() const; - void Reset(); - // camera, lidar, radar and others - SensorType sensor_type = SensorType::UNKNOWN_SENSOR_TYPE; - // ROADSIDE - MessageType message_type = MessageType::UNKNOWN_MESSAGE_TYPE; - // @brief sensor-specific object supplements, optional - CameraObjectSupplement camera_supplement; - FusionObjectSupplement fusion_supplement; - // message timestamp - double timestamp = 0.0; - // original sensor timestamp - double sensor_timestamp = 0.0; - // @brief age of the tracked object, required - double tracking_time = 0.0; - // @brief timestamp of latest measurement, required - double latest_tracked_time = 0.0; - std::string frame_id = ""; - // @brief track id, required - int track_id = -1; - // @breif object id per frame, required - int global_id = -1; - // @brief center position of the boundingbox (x, y, z), required - Info3d position; - // @brief anchor point, required - Info3d anchor_point; - // 0-2Pi from east - Infod theta; - // @brief theta variance, required - Infod theta_variance; - // @brief main direction of the object, required - Info3d direction; - /* @brief size = [length, width, height] of boundingbox - length is the size of the main direction, required - */ - Info3d size; - // @brief convex hull of the object, required - // Point3f polygon; - // @brief object type, required - ObjectType type = ObjectType::UNKNOWN; - - V2xType v2x_type = V2xType::UNKNOWN; - // @brief type variance, required - double type_variance = 1.0; - // @brief probability for each type, required - std::vector type_probs; - // @brief object sub-type, optional - ObjectSubType sub_type = ObjectSubType::UNKNOWN; - // @brief probability for each sub-type, optional - std::vector sub_type_probs; - - std::vector> tentacles; - - std::vector polygon; - - // tracking information - // @brief the variance of tracked - Infod track_variance; - // @brief velocity of the object, required - Info3d velocity; - // @brief acceleration of the object, required - Info3d acceleration; - // @brief motion state of the tracked object, required - Infob is_stationary; - - Infob is_temporary_lost; - std::string DebugString() const { - return absl::StrCat("id: ", track_id, ", ", // - "time: ", timestamp, ", ", // - "sensor type: ", sensor_type, ", ", // - "x: ", position.x(), ", ", // - "y: ", position.y(), ", ", // - "vx: ", velocity.x(), ", ", // - "vy: ", velocity.y(), ", ", // - "yaw: ", theta.Value()); - } -}; - -typedef std::shared_ptr ObjectPtr; -typedef std::shared_ptr ObjectConstPtr; - -struct alignas(16) ObjectList { - ObjectList() = default; - ~ObjectList() = default; - ObjectList(const ObjectList &) = default; - ObjectList &operator=(const ObjectList &) = default; - bool operator<(const ObjectList &rhs) const { - return timestamp < rhs.timestamp; - } - bool operator>(const ObjectList &rhs) const { - return timestamp > rhs.timestamp; - } - bool operator==(const ObjectList &rhs) const { - return timestamp == rhs.timestamp; - } - - SensorType sensor_type; - // @brief sensor-specific object supplements, optional - CameraObjectSupplement camera_supplement; - // LidarObjectSupplement lidar_supplement; - // RadarObjectSupplement radar_supplement; - FusionObjectSupplement fusion_supplement; - - // message timestamp - double timestamp = 0.0; - // original sensor timestamp - double sensor_timestamp = 0.0; - // @brief age of the tracked object, require - std::string frame_id = ""; - - std::vector objects; -}; - -typedef std::shared_ptr ObjectListPtr; -typedef std::shared_ptr ObjectListConstPtr; - -} // namespace base -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/libs/common/v2x_object_test.cc b/modules/v2x/fusion/libs/common/v2x_object_test.cc deleted file mode 100644 index 26c769a1bd7..00000000000 --- a/modules/v2x/fusion/libs/common/v2x_object_test.cc +++ /dev/null @@ -1,47 +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/v2x/fusion/libs/common/v2x_object.h" - -#include "gtest/gtest.h" - -namespace apollo { -namespace v2x { -namespace ft { -namespace base { - -TEST(Object, operators) { - std::vector objects; - Object object; - object.timestamp = 4.1; - object.track_id = 0; - objects.push_back(object); - object.timestamp = 3.2; - object.track_id = 1; - objects.push_back(object); - object.timestamp = 2.3; - object.track_id = 2; - objects.push_back(object); - object.timestamp = 1.4; - object.track_id = 3; - objects.push_back(object); - sort(objects.begin(), objects.end(), std::less()); - EXPECT_EQ(objects.at(0).track_id, 3); -} - -} // namespace base -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/libs/fusion/BUILD b/modules/v2x/fusion/libs/fusion/BUILD deleted file mode 100644 index b61a3c0e8f0..00000000000 --- a/modules/v2x/fusion/libs/fusion/BUILD +++ /dev/null @@ -1,56 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -cc_library( - name = "fusion", - srcs = ["fusion.cc"], - hdrs = ["fusion.h"], - copts = ['-DMODULE_NAME=\\"v2x_fusion\\"'], - deps = [ - ":km", - "//modules/v2x/fusion/configs:ft_config_manager", - "//modules/v2x/fusion/libs/common:v2x_object", - "@eigen", - ], -) - -cc_library( - name = "km", - hdrs = ["km.h"], - deps = [ - "@eigen", - ], -) - -cc_library( - name = "test_tools", - hdrs = ["test_tools.h"], - deps = [ - "//modules/v2x/fusion/libs/common:v2x_object", - ], -) - -cc_test( - name = "fusion_test", - size = "small", - srcs = ["fusion_test.cc"], - deps = [ - ":fusion", - ":test_tools", - "@com_google_googletest//:gtest_main", - ], -) - -cc_test( - name = "km_test", - size = "small", - srcs = ["km_test.cc"], - deps = [ - ":km", - "@com_google_googletest//:gtest_main", - ], -) - -cpplint() diff --git a/modules/v2x/fusion/libs/fusion/fusion.cc b/modules/v2x/fusion/libs/fusion/fusion.cc deleted file mode 100644 index 6d4315fb593..00000000000 --- a/modules/v2x/fusion/libs/fusion/fusion.cc +++ /dev/null @@ -1,218 +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/v2x/fusion/libs/fusion/fusion.h" - -#include -#include - -namespace apollo { -namespace v2x { -namespace ft { - -Fusion::Fusion() { - ft_config_manager_ptr_ = FTConfigManager::Instance(); - - score_params_ = ft_config_manager_ptr_->fusion_params_.params.score_params(); - switch (score_params_.confidence_level()) { - case fusion::ConfidenceLevel::C90P: - m_matched_dis_limit_ = std::sqrt(4.605); - break; - case fusion::ConfidenceLevel::C95P: - m_matched_dis_limit_ = std::sqrt(5.991); - break; - case fusion::ConfidenceLevel::C975P: - m_matched_dis_limit_ = std::sqrt(7.378); - break; - case fusion::ConfidenceLevel::C99P: - m_matched_dis_limit_ = std::sqrt(9.210); - break; - default: - break; - } -} - -bool Fusion::Init() { - last_timestamp_ = -1.0; - return true; -} - -bool Fusion::Proc( - const std::vector> &input_objectlists, - double timestamp) { - fusion_result_.clear(); - updated_objects_.clear(); - for (unsigned int i = 0; i < input_objectlists.size(); ++i) { - CombineNewResource(input_objectlists[i]); - } - return true; -} - -bool Fusion::CombineNewResource(const std::vector &new_objects) { - return CombineNewResource(new_objects, &updated_objects_, &fusion_result_); -} - -bool Fusion::CombineNewResource( - const std::vector &new_objects, - std::vector *fused_objects, - std::vector> *fusion_result) { - if (new_objects.empty()) { - return false; - } - if (fused_objects->size() < 1) { - fused_objects->assign(new_objects.begin(), new_objects.end()); - for (unsigned int j = 0; j < new_objects.size(); ++j) { - std::vector matched_objects; - matched_objects.push_back(new_objects[j]); - fusion_result->push_back(matched_objects); - } - return true; - } - int u_num = fused_objects->size(); - int v_num = new_objects.size(); - Eigen::MatrixXf association_mat(u_num, v_num); - ComputeAssociateMatrix(*fused_objects, new_objects, &association_mat); - std::vector> match_cps; - if (u_num > v_num) { - km_matcher_.GetKMResult(association_mat.transpose(), &match_cps, true); - } else { - km_matcher_.GetKMResult(association_mat, &match_cps, false); - } - for (auto it = match_cps.begin(); it != match_cps.end(); it++) { - if (it->second != -1) { - if (it->first == -1) { - fused_objects->push_back(new_objects[it->second]); - std::vector matched_objects; - matched_objects.push_back(fused_objects->back()); - fusion_result->push_back(matched_objects); - } else { - (*fusion_result)[it->first].push_back(new_objects[it->second]); - } - } - } - return true; -} - -bool Fusion::GetV2xFusionObjects( - const std::vector> &fusion_result, - std::vector *fused_objects) { - for (const auto &objects : fusion_result) { - if (objects.size() == 1) { - fused_objects->push_back(objects.at(0)); - if (objects.at(0).frame_id == "V2X") { - fused_objects->back().v2x_type = base::V2xType::BLIND_ZONE; - } else { - fused_objects->back().v2x_type = base::V2xType::UNKNOWN; - } - } else { - fused_objects->push_back(objects.at(0)); - host_vehicle_ = false; - zom_vehicle_ = false; - for (const auto &object : objects) { - if (object.v2x_type == base::V2xType::HOST_VEHICLE) { - host_vehicle_ = true; - } else if (object.v2x_type == base::V2xType::ZOMBIES_CAR) { - zom_vehicle_ = true; - } - } - if (zom_vehicle_ == true) { - fused_objects->back().v2x_type = base::V2xType::ZOMBIES_CAR; - } - if (host_vehicle_ == true) { - fused_objects->back().v2x_type = base::V2xType::HOST_VEHICLE; - } - } - } - return true; -} - -double Fusion::CheckOdistance(const base::Object &in1_ptr, - const base::Object &in2_ptr) { - double xi = in1_ptr.position.x(); - double yi = in1_ptr.position.y(); - double xj = in2_ptr.position.x(); - double yj = in2_ptr.position.y(); - double distance = std::hypot(xi - xj, yi - yj); - return distance; -} - -bool Fusion::CheckDisScore(const base::Object &in1_ptr, - const base::Object &in2_ptr, double *score) { - double dis = CheckOdistance(in1_ptr, in2_ptr); - *score = 2.5 * std::max(0.0, score_params_.max_match_distance() - dis); - return true; -} - -bool Fusion::CheckTypeScore(const base::Object &in1_ptr, - const base::Object &in2_ptr, double *score) { - double same_prob = 0; - if (in1_ptr.sub_type == in2_ptr.sub_type) { - same_prob = - 1 - (1 - in1_ptr.sub_type_probs[0]) * (1 - in2_ptr.sub_type_probs[0]); - } else if (in1_ptr.type == in2_ptr.type || - in1_ptr.type == v2x::ft::base::ObjectType::UNKNOWN || - in2_ptr.type == v2x::ft::base::ObjectType::UNKNOWN) { - same_prob = - (1 - in1_ptr.sub_type_probs.at(0)) * in2_ptr.sub_type_probs.at(0) + - (1 - in2_ptr.sub_type_probs.at(0)) * in1_ptr.sub_type_probs.at(0); - same_prob *= score_params_.prob_scale(); - } - *score *= same_prob; - return true; -} - -bool Fusion::ComputeAssociateMatrix( - const std::vector &in1_objects, // fused - const std::vector &in2_objects, // new - Eigen::MatrixXf *association_mat) { - for (unsigned int i = 0; i < in1_objects.size(); ++i) { - for (unsigned int j = 0; j < in2_objects.size(); ++j) { - const base::Object &obj1_ptr = in1_objects[i]; - const base::Object &obj2_ptr = in2_objects[j]; - double score = 0; - if (!CheckDisScore(obj1_ptr, obj2_ptr, &score)) { - AERROR << "V2X Fusion: check dis score failed"; - } - if (score_params_.check_type() && - !CheckTypeScore(obj1_ptr, obj2_ptr, &score)) { - AERROR << "V2X Fusion: check type failed"; - } - (*association_mat)(i, j) = - (score >= score_params_.min_score()) ? score : 0; - } - } - return true; -} - -int Fusion::DeleteRedundant(std::vector *objects) { - std::vector to_be_deleted; - for (unsigned int i = 0; i < objects->size(); ++i) { - for (unsigned int j = i + 1; j < objects->size(); ++j) { - double distance = CheckOdistance(objects->at(i), objects->at(j)); - if (distance < 1) { - to_be_deleted.push_back(j); - } - } - } - for (auto iter = to_be_deleted.rbegin(); iter != to_be_deleted.rend(); - ++iter) { - objects->erase(objects->begin() + *iter); - } - return to_be_deleted.size(); -} -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/libs/fusion/fusion.h b/modules/v2x/fusion/libs/fusion/fusion.h deleted file mode 100644 index fc61f29280e..00000000000 --- a/modules/v2x/fusion/libs/fusion/fusion.h +++ /dev/null @@ -1,83 +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 - -#include - -#include "modules/v2x/fusion/configs/ft_config_manager.h" -#include "modules/v2x/fusion/libs/common/v2x_object.h" -#include "modules/v2x/fusion/libs/fusion/km.h" - -namespace apollo { -namespace v2x { -namespace ft { - -class Fusion { - public: - Fusion(); - ~Fusion() {} - bool Proc(const std::vector> &input_objectlists, - double timestamp); - bool Init(); - std::vector &get_fused_objects() { return updated_objects_; } - std::vector> &get_fusion_result() { - return fusion_result_; - } - bool CombineNewResource( - const std::vector &new_objects, - std::vector *fused_objects, - std::vector> *fusion_result); - bool GetV2xFusionObjects( - const std::vector> &fusion_result, - std::vector *fused_objects); - int DeleteRedundant(std::vector *objects); - - private: - bool CombineNewResource(const std::vector &new_objects); - bool ComputeAssociateMatrix(const std::vector &in1_objects, - const std::vector &in2_objects, - Eigen::MatrixXf *association_mat); - double CheckOdistance(const base::Object &in1_ptr, - const base::Object &in2_ptr); - bool CheckDisScore(const base::Object &in1_ptr, const base::Object &in2_ptr, - double *score); - bool CheckTypeScore(const base::Object &in1_ptr, const base::Object &in2_ptr, - double *score); - bool host_vehicle_ = false; - bool zom_vehicle_ = false; - double last_timestamp_; - const double MAX_SCORE = 250000; - float m_matched_dis_limit_; - FTConfigManager *ft_config_manager_ptr_; - KMkernal km_matcher_; - fusion::ScoreParams score_params_; - std::vector> fusion_result_; - std::vector updated_objects_; -}; - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/libs/fusion/fusion_test.cc b/modules/v2x/fusion/libs/fusion/fusion_test.cc deleted file mode 100644 index dd131404216..00000000000 --- a/modules/v2x/fusion/libs/fusion/fusion_test.cc +++ /dev/null @@ -1,61 +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/v2x/fusion/libs/fusion/fusion.h" - -#include -#include - -#include "gtest/gtest.h" - -#include "modules/v2x/fusion/libs/fusion/test_tools.h" - -namespace apollo { -namespace v2x { -namespace ft { - -TEST(Fusion, get_km_result) { - Fusion fusion; - std::vector fused_objects; - std::vector> fusion_result; - std::vector objects1; - std::vector objects2; - std::vector objects3; - std::vector objects4; - EXPECT_FALSE( - fusion.CombineNewResource(objects1, &fused_objects, &fusion_result)); - LoadData("/apollo/modules/v2x/fusion/test_data/fusion_object1", &objects1, - "camera1"); - LoadData("/apollo/modules/v2x/fusion/test_data/fusion_object2", &objects2, - "camera2"); - LoadData("/apollo/modules/v2x/fusion/test_data/fusion_object3", &objects3, - "camera3"); - LoadData("/apollo/modules/v2x/fusion/test_data/fusion_object4", &objects4, - "camera4"); - EXPECT_TRUE( - fusion.CombineNewResource(objects1, &fused_objects, &fusion_result)); - EXPECT_TRUE( - fusion.CombineNewResource(objects2, &fused_objects, &fusion_result)); - EXPECT_TRUE( - fusion.CombineNewResource(objects3, &fused_objects, &fusion_result)); - EXPECT_TRUE( - fusion.CombineNewResource(objects4, &fused_objects, &fusion_result)); - EXPECT_GE(fused_objects.size(), 9); - EXPECT_LE(fused_objects.size(), 12); -} - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/libs/fusion/km.h b/modules/v2x/fusion/libs/fusion/km.h deleted file mode 100644 index 3544aeb3e75..00000000000 --- a/modules/v2x/fusion/libs/fusion/km.h +++ /dev/null @@ -1,161 +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 -#include -#include - -#include - -#define USR_INF 999999999999 - -namespace apollo { -namespace v2x { -namespace ft { - -class KMkernal { - public: - KMkernal() = default; - ~KMkernal() = default; - template - bool GetKMResult(const T& association_mat, - std::vector>* match_cps, - bool need_reverse = false); - - private: - int u_size_; - int v_size_; - double* ex_u_; - double* ex_v_; - int* v_matched_; - double* v_slack_; - std::set used_u_; - std::set used_v_; - template - bool FindCP(const T& mat, int i); -}; -template -bool KMkernal::GetKMResult(const T& association_mat, - std::vector>* match_cps, - bool need_reverse) { - match_cps->clear(); - u_size_ = association_mat.rows(); - v_size_ = association_mat.cols(); - if (u_size_ > v_size_) return false; - ex_u_ = new double[u_size_]; - ex_v_ = new double[v_size_]; - v_matched_ = new int[v_size_]; - std::fill(v_matched_, v_matched_ + v_size_, -1); - memset(ex_v_, 0, v_size_ * sizeof(double)); - for (int i = 0; i < u_size_; ++i) { - ex_u_[i] = association_mat(i, 0); - for (int j = 1; j < v_size_; ++j) { - ex_u_[i] = std::max(static_cast(ex_u_[i]), association_mat(i, j)); - } - } - for (int i = 0; i < u_size_; ++i) { - if (ex_u_[i] <= 0) { - if (need_reverse) - match_cps->push_back(std::make_pair(-1, i)); - else - match_cps->push_back(std::make_pair(i, -1)); - continue; - } - v_slack_ = new double[v_size_]; - std::fill(v_slack_, v_slack_ + v_size_, USR_INF); - while (1) { - used_u_.clear(); - used_v_.clear(); - if (FindCP(association_mat, i)) break; - double d = USR_INF; - for (int j = 0; j < v_size_; ++j) - if (used_v_.find(j) == used_v_.end()) d = std::min(d, v_slack_[j]); - for (auto it = used_u_.begin(); it != used_u_.end(); it++) { - ex_u_[*it] -= d; - } - for (int j = 0; j < v_size_; ++j) { - if (used_v_.find(j) != used_v_.end()) - ex_v_[j] += d; - else - v_slack_[j] -= d; - } - } - delete[] v_slack_; - } - if (need_reverse) { - for (int j = 0; j < v_size_; ++j) { - if (v_matched_[j] == -1) { - match_cps->push_back(std::make_pair(j, -1)); - } else if (association_mat(v_matched_[j], j) > 0) { - match_cps->push_back(std::make_pair(j, v_matched_[j])); - } else { - match_cps->push_back(std::make_pair(-1, v_matched_[j])); - match_cps->push_back(std::make_pair(j, -1)); - } - } - } else { - for (int j = 0; j < v_size_; ++j) { - if (v_matched_[j] == -1) { - match_cps->push_back(std::make_pair(-1, j)); - } else if (association_mat(v_matched_[j], j) > 0) { - match_cps->push_back(std::make_pair(v_matched_[j], j)); - } else { - match_cps->push_back(std::make_pair(v_matched_[j], -1)); - match_cps->push_back(std::make_pair(-1, j)); - } - } - } - delete[] ex_u_; - delete[] ex_v_; - delete[] v_matched_; - return true; -} - -template -bool KMkernal::FindCP(const T& mat, int i) { - used_u_.insert(i); - for (int j = 0; j < v_size_; ++j) { - if (used_v_.find(j) != used_v_.end()) { - continue; - } - double gap = ex_u_[i] + ex_v_[j] - mat(i, j); - if (gap <= 0) { - // res = 0; - used_v_.insert(j); - bool match_success = v_matched_[j] == -1 || FindCP(mat, v_matched_[j]); - if (match_success) { - v_matched_[j] = i; - return true; - } - } else { - v_slack_[j] = std::min(v_slack_[j], gap); - } - } - return false; -} - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/libs/fusion/km_test.cc b/modules/v2x/fusion/libs/fusion/km_test.cc deleted file mode 100644 index f68a806b3fe..00000000000 --- a/modules/v2x/fusion/libs/fusion/km_test.cc +++ /dev/null @@ -1,37 +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/v2x/fusion/libs/fusion/km.h" - -#include "gtest/gtest.h" - -namespace apollo { -namespace v2x { -namespace ft { - -TEST(KMkernal, get_km_result) { - KMkernal km_matcher; - Eigen::MatrixXf association_mat(5, 4); - association_mat << 50, 34, 0, 0, 10, 0, 17, 0, 0, 31, 18, 10, 0, 0, 8, 17, 0, - 0, 0, 2; - std::vector> match_cps; - EXPECT_FALSE(km_matcher.GetKMResult(association_mat, &match_cps)); - EXPECT_TRUE( - km_matcher.GetKMResult(association_mat.transpose(), &match_cps, true)); -} - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/libs/fusion/test_tools.h b/modules/v2x/fusion/libs/fusion/test_tools.h deleted file mode 100644 index 6d1d5493440..00000000000 --- a/modules/v2x/fusion/libs/fusion/test_tools.h +++ /dev/null @@ -1,83 +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/v2x/fusion/libs/common/v2x_object.h" - -namespace apollo { -namespace v2x { -namespace ft { - -bool LoadData(const std::string& file, std::vector* objects, - const std::string& frame_id) { - std::fstream fin; - fin.open(file.c_str(), std::ios::in); - if (!fin) { - return false; - } - std::string line; - while (getline(fin, line)) { - std::istringstream iss(line); - float sub_type_probs, x, y, z, xx, xy, xz, yx, yy, yz, zx, zy, zz; - Eigen::Vector3d pos; - Eigen::Matrix3d var; - int type, sub_type; - iss >> type >> sub_type >> sub_type_probs >> x >> y >> z >> xx >> xy >> - xz >> yx >> yy >> yz >> zx >> zy >> zz; - pos << x, y, z; - var << xx, xy, xz, yx, yy, yz, zx, zy, zz; - base::Object obj; - obj.type = base::ObjectType::VEHICLE; - Eigen::Vector3d car_size, bus_size, van_size; - Eigen::Matrix3d id_var; - car_size << 4.2, 2.0, 1.8; - bus_size << 12, 2.2, 3; - van_size << 4.5, 2.1, 2; - id_var << 1, 0, 0, 0, 1, 0, 0, 0, 1; - switch (sub_type) { - case 3: - obj.sub_type = base::ObjectSubType::CAR; - obj.size.Set(car_size, id_var); - break; - case 4: - obj.sub_type = base::ObjectSubType::VAN; - obj.size.Set(van_size, id_var); - break; - case 5: - obj.sub_type = base::ObjectSubType::BUS; - obj.size.Set(bus_size, id_var); - break; - default: - break; - } - obj.sensor_type = base::SensorType::MONOCULAR_CAMERA; - obj.frame_id = frame_id; - obj.position.Set(pos, var); - obj.theta.Set(0, 1); - obj.type_probs.push_back(0.9f); - obj.sub_type_probs.push_back(sub_type_probs); - objects->push_back(obj); - } - return true; -} - -} // namespace ft -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/fusion/test_data/app_config.pt b/modules/v2x/fusion/test_data/app_config.pt deleted file mode 100644 index c53df19f26e..00000000000 --- a/modules/v2x/fusion/test_data/app_config.pt +++ /dev/null @@ -1,47 +0,0 @@ -input { - input_type: OLD - seq: 0 - channel_name: "/perception/obstacles_old" -} -input { - input_type: CAMERA - seq: 1 - channel_name: "/perception/obstacles_camera1" -} -input { - input_type: CAMERA - seq: 2 - channel_name: "/perception/obstacles_camera2" -} -input { - input_type: CAMERA - seq: 3 - channel_name: "/perception/obstacles_camera3" -} -input { - input_type: CAMERA - seq: 4 - channel_name: "/perception/obstacles_camera4" -} -input { - input_type: CAMERA - seq: 5 - channel_name: "/perception/obstacles_camera5" -} -input { - input_type: CAMERA - seq: 6 - channel_name: "/perception/obstacles_camera6" -} -input { - input_type: CAMERA - seq: 7 - channel_name: "/perception/obstacles_camera7" -} -input { - input_type: CAMERA - seq: 8 - channel_name: "/perception/obstacles_camera8" -} -output_name: "/perception/obstacles" - diff --git a/modules/v2x/fusion/test_data/benchmark b/modules/v2x/fusion/test_data/benchmark deleted file mode 100644 index 5aa7dedd5dd..00000000000 --- a/modules/v2x/fusion/test_data/benchmark +++ /dev/null @@ -1,10 +0,0 @@ -5 3 10 20 0 -5 3 20 20 0 -5 5 40 20 0 -5 3 40 28 0 -5 5 40 40 0 -5 3 50 30 0 -5 3 50 50 0 -5 3 52 58 0 -5 3 52 80 0 -5 3 62 60 0 diff --git a/modules/v2x/fusion/test_data/fusion_object1 b/modules/v2x/fusion/test_data/fusion_object1 deleted file mode 100644 index 56e8e67d35b..00000000000 --- a/modules/v2x/fusion/test_data/fusion_object1 +++ /dev/null @@ -1,8 +0,0 @@ -5 3 0.9 9.31946521 18.30961269 0 1.87197597 -0.43041365 0 -0.43041365 2.70802403 0 0 0 1 -5 3 0.92 19.89205768 19.74458419 0 1.87197597 -0.43041365 0 -0.43041365 2.70802403 0 0 0 1 -5 3 0.9 40.86857973 29.44662098 0 1.87197597 -0.43041365 0 -0.43041365 2.70802403 0 0 0 1 -5 4 0.2 48.96013459 30.90766418 0 1.87197597 -0.43041365 0 -0.43041365 2.70802403 0 0 0 1 -5 3 0.9 51.71806427 48.35927642 0 1.87197597 -0.43041365 0 -0.43041365 2.70802403 0 0 0 1 -5 3 0.9 53.62918569 57.52490467 0 1.87197597 -0.43041365 0 -0.43041365 2.70802403 0 0 0 1 -5 3 0.9 52.26166017 81.807556 0 1.87197597 -0.43041365 0 -0.43041365 2.70802403 0 0 0 1 -5 5 0.1 60.41045885 59.87098393 0 1.87197597 -0.43041365 0 -0.43041365 2.70802403 0 0 0 1 \ No newline at end of file diff --git a/modules/v2x/fusion/test_data/fusion_object2 b/modules/v2x/fusion/test_data/fusion_object2 deleted file mode 100644 index 42b8545e0a7..00000000000 --- a/modules/v2x/fusion/test_data/fusion_object2 +++ /dev/null @@ -1,7 +0,0 @@ -5 3 0.9 11.61865708 18.75230918 0 1.51751643 -0.49272486 0 -0.49272486 1.68748357 0 0 0 1 -5 3 0.9 21.48883758 17.21299772 0 1.51751643 -0.49272486 0 -0.49272486 1.68748357 0 0 0 1 -5 3 0.1 41.3889516 19.32466078 0 1.51751643 -0.49272486 0 -0.49272486 1.68748357 0 0 0 1 -5 3 0.9 42.67292524 27.95346616 0 1.51751643 -0.49272486 0 -0.49272486 1.68748357 0 0 0 1 -5 3 0.9 50.4440022 29.66052762 0 1.51751643 -0.49272486 0 -0.49272486 1.68748357 0 0 0 1 -5 3 0.9 49.87589212 50.78223584 0 1.51751643 -0.49272486 0 -0.49272486 1.68748357 0 0 0 1 -5 3 0.9 61.7858522 61.33488594 0 1.51751643 -0.49272486 0 -0.49272486 1.68748357 0 0 0 1 \ No newline at end of file diff --git a/modules/v2x/fusion/test_data/fusion_object3 b/modules/v2x/fusion/test_data/fusion_object3 deleted file mode 100644 index ae54efcaefc..00000000000 --- a/modules/v2x/fusion/test_data/fusion_object3 +++ /dev/null @@ -1,6 +0,0 @@ -5 3 0.9 7.51697628 20.11302683 0 4.80338629 -0.36491583 0 -0.36491583 1.20301371 0 0 0 1 -5 3 0.9 18.76581442 20.3855129 0 4.80338629 -0.36491583 0 -0.36491583 1.20301371 0 0 0 1 -5 3 0.1 40.26919145 39.59741714 0 4.80338629 -0.36491583 0 -0.36491583 1.20301371 0 0 0 1 -5 3 0.9 54.46195886 30.55647023 0 4.80338629 -0.36491583 0 -0.36491583 1.20301371 0 0 0 1 -5 3 0.9 51.48225631 58.84663973 0 4.80338629 -0.36491583 0 -0.36491583 1.20301371 0 0 0 1 -5 3 0.9 51.05921321 77.69595062 0 4.80338629 -0.36491583 0 -0.36491583 1.20301371 0 0 0 1 \ No newline at end of file diff --git a/modules/v2x/fusion/test_data/fusion_object4 b/modules/v2x/fusion/test_data/fusion_object4 deleted file mode 100644 index b21ab028a6c..00000000000 --- a/modules/v2x/fusion/test_data/fusion_object4 +++ /dev/null @@ -1,5 +0,0 @@ -5 3 0.9 19.45528984 20.64674959 0 1.89160066 1.5809713 0 1.5809713 3.12089934 0 0 0 1 -5 3 0.1 40.27277858 27.25332916 0 1.89160066 1.5809713 0 1.5809713 3.12089934 0 0 0 1 -5 5 0.1 48.94089065 29.8692135 0 1.89160066 1.5809713 0 1.5809713 3.12089934 0 0 0 1 -5 3 0.9 51.67702261 79.53939934 0 1.89160066 1.5809713 0 1.5809713 3.12089934 0 0 0 1 -5 3 0.9 60.15997698 59.60247437 0 1.89160066 1.5809713 0 1.5809713 3.12089934 0 0 0 1 \ No newline at end of file diff --git a/modules/v2x/fusion/test_data/fusion_params.pt b/modules/v2x/fusion/test_data/fusion_params.pt deleted file mode 100644 index cb4f71ff503..00000000000 --- a/modules/v2x/fusion/test_data/fusion_params.pt +++ /dev/null @@ -1,9 +0,0 @@ -score_params { - prob_scale: 0.125 - max_match_distance: 10 - min_score: 0 - use_mahalanobis_distance: true - check_type: true - confidence_level: C975P -} - diff --git a/modules/v2x/fusion/test_data/fusion_params_wrong.pt b/modules/v2x/fusion/test_data/fusion_params_wrong.pt deleted file mode 100644 index b604cb29447..00000000000 --- a/modules/v2x/fusion/test_data/fusion_params_wrong.pt +++ /dev/null @@ -1,8 +0,0 @@ -score_params { - prob_scales: 0.125 - max_match_distance: 10 - min_score: 0 - use_mahalanobis_distance: true - check_type: true -} - diff --git a/modules/v2x/launch/v2x.launch b/modules/v2x/launch/v2x.launch deleted file mode 100644 index b8a8a63847d..00000000000 --- a/modules/v2x/launch/v2x.launch +++ /dev/null @@ -1,11 +0,0 @@ - - - v2x - - binary - - /apollo/bazel-bin/modules/v2x/v2x_proxy/app/v2x --flagfile=/apollo/modules/v2x/conf/v2x.conf - - 1.0.0 - - diff --git a/modules/v2x/proto/BUILD b/modules/v2x/proto/BUILD deleted file mode 100644 index 347485a5528..00000000000 --- a/modules/v2x/proto/BUILD +++ /dev/null @@ -1,307 +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_grpc_library", "py_proto_library") -load("@com_github_grpc_grpc//bazel:cc_grpc_library.bzl", "cc_grpc_library") -load("//tools/install:install.bzl", "install", "install_files") - -package(default_visibility = ["//visibility:public"]) - -install_files( - name = "py_pb_v2x", - dest = "v2x/python/modules/v2x/proto", - files = [ - ":v2x_obstacles_py_pb2", - ":v2x_car_status_py_pb2", - ":v2x_rsi_py_pb2", - ":v2x_service_obu_to_car_py_pb2", - ":fusion_params_py_pb2", - ":v2x_obu_traffic_light_py_pb2", - ":v2x_obu_rsi_py_pb2", - ":v2x_service_car_to_obu_py_pb2", - ":v2x_monitor_py_pb2", - ":v2x_junction_py_pb2", - ":v2x_traffic_light_policy_py_pb2" - ] -) - -cc_proto_library( - name = "v2x_obstacles_cc_proto", - deps = [ - ":v2x_obstacles_proto", - ], -) - -proto_library( - name = "v2x_obstacles_proto", - srcs = ["v2x_obstacles.proto"], - deps = [ - "//modules/common_msgs/basic_msgs:header_proto", - "//modules/common_msgs/basic_msgs:error_code_proto", - "//modules/common_msgs/perception_msgs:perception_obstacle_proto", - ], -) - -py_proto_library( - name = "v2x_obstacles_py_pb2", - deps = [ - ":v2x_obstacles_proto", - "//modules/common_msgs/basic_msgs:header_py_pb2", - "//modules/common_msgs/basic_msgs:error_code_py_pb2", - "//modules/common_msgs/perception_msgs:perception_obstacle_py_pb2", - ], -) - -cc_proto_library( - name = "v2x_car_status_cc_proto", - deps = [ - ":v2x_car_status_proto", - ], -) - -proto_library( - name = "v2x_car_status_proto", - srcs = ["v2x_car_status.proto"], - deps = [ - "//modules/common_msgs/localization_msgs:localization_proto", - "//modules/common_msgs/chassis_msgs:chassis_detail_proto", - ":v2x_junction_proto", - ], -) - -py_proto_library( - name = "v2x_car_status_py_pb2", - deps = [ - ":v2x_car_status_proto", - "//modules/common_msgs/localization_msgs:localization_py_pb2", - "//modules/common_msgs/chassis_msgs:chassis_detail_py_pb2", - ":v2x_junction_py_pb2", - ], -) - -cc_proto_library( - name = "v2x_rsi_cc_proto", - deps = [ - ":v2x_rsi_proto", - ], -) - -proto_library( - name = "v2x_rsi_proto", - srcs = ["v2x_rsi.proto"], - deps = [ - "//modules/common_msgs/basic_msgs:header_proto", - ], -) - -py_proto_library( - name = "v2x_rsi_py_pb2", - deps = [ - ":v2x_rsi_proto", - "//modules/common_msgs/basic_msgs:header_py_pb2", - ], -) - -cc_grpc_library( - name = "v2x_service_obu_to_car_cc_grpc", - srcs = [":v2x_service_obu_to_car_proto"], - grpc_only = True, - deps = [":v2x_service_obu_to_car_cc_proto"], -) - -cc_proto_library( - name = "v2x_service_obu_to_car_cc_proto", - deps = [ - ":v2x_service_obu_to_car_proto", - ], -) - -proto_library( - name = "v2x_service_obu_to_car_proto", - srcs = ["v2x_service_obu_to_car.proto"], - deps = [ - ":v2x_obu_traffic_light_proto", - ":v2x_monitor_proto", - ":v2x_obu_rsi_proto", - ":v2x_obstacles_proto", - ], -) - -py_grpc_library( - name = "v2x_service_obu_to_car_py_pb2_grpc", - srcs = [":v2x_service_obu_to_car_proto"], - deps = [":v2x_service_obu_to_car_py_pb2"], -) - -py_proto_library( - name = "v2x_service_obu_to_car_py_pb2", - deps = [ - ":v2x_service_obu_to_car_proto", - ":v2x_obu_traffic_light_py_pb2", - ":v2x_monitor_py_pb2", - ":v2x_obu_rsi_py_pb2", - ":v2x_obstacles_py_pb2", - ], -) -cc_proto_library( - name = "fusion_params_cc_proto", - deps = [ - ":fusion_params_proto", - ], -) - -proto_library( - name = "fusion_params_proto", - srcs = ["fusion_params.proto"], -) - -py_proto_library( - name = "fusion_params_py_pb2", - deps = [ - ":fusion_params_proto", - ], -) -cc_proto_library( - name = "v2x_obu_traffic_light_cc_proto", - deps = [ - ":v2x_obu_traffic_light_proto", - ], -) - -proto_library( - name = "v2x_obu_traffic_light_proto", - srcs = ["v2x_obu_traffic_light.proto"], - deps = [ - "//modules/common_msgs/basic_msgs:header_proto", - "//modules/common_msgs/v2x_msgs:v2x_traffic_light_proto", - ], -) - -py_proto_library( - name = "v2x_obu_traffic_light_py_pb2", - deps = [ - ":v2x_obu_traffic_light_proto", - "//modules/common_msgs/basic_msgs:header_py_pb2", - "//modules/common_msgs/v2x_msgs:v2x_traffic_light_py_pb2", - ], -) - -cc_proto_library( - name = "v2x_obu_rsi_cc_proto", - deps = [ - ":v2x_obu_rsi_proto", - ], -) - -proto_library( - name = "v2x_obu_rsi_proto", - srcs = ["v2x_obu_rsi.proto"], - deps = [ - "//modules/common_msgs/basic_msgs:header_proto", - "//modules/common_msgs/basic_msgs:geometry_proto", - ], -) - -py_proto_library( - name = "v2x_obu_rsi_py_pb2", - deps = [ - ":v2x_obu_rsi_proto", - "//modules/common_msgs/basic_msgs:header_py_pb2", - "//modules/common_msgs/basic_msgs:geometry_py_pb2", - ], -) - -cc_grpc_library( - name = "v2x_service_car_to_obu_cc_grpc", - srcs = [":v2x_service_car_to_obu_proto"], - grpc_only = True, - deps = [":v2x_service_car_to_obu_cc_proto"], -) - -cc_proto_library( - name = "v2x_service_car_to_obu_cc_proto", - deps = [ - ":v2x_service_car_to_obu_proto", - ], -) - -proto_library( - name = "v2x_service_car_to_obu_proto", - srcs = ["v2x_service_car_to_obu.proto"], - deps = [ - ":v2x_car_status_proto", - ], -) - -py_grpc_library( - name = "v2x_service_car_to_obu_py_pb2_grpc", - srcs = [":v2x_service_car_to_obu_proto"], - deps = [":v2x_service_car_to_obu_py_pb2"], -) - -py_proto_library( - name = "v2x_service_car_to_obu_py_pb2", - deps = [ - ":v2x_service_car_to_obu_proto", - ":v2x_car_status_py_pb2", - ], -) -cc_proto_library( - name = "v2x_monitor_cc_proto", - deps = [ - ":v2x_monitor_proto", - ], -) - -proto_library( - name = "v2x_monitor_proto", - srcs = ["v2x_monitor.proto"], -) - -py_proto_library( - name = "v2x_monitor_py_pb2", - deps = [ - ":v2x_monitor_proto", - ], -) -cc_proto_library( - name = "v2x_junction_cc_proto", - deps = [ - ":v2x_junction_proto", - ], -) - -proto_library( - name = "v2x_junction_proto", - srcs = ["v2x_junction.proto"], - deps = [ - "//modules/common_msgs/basic_msgs:geometry_proto", - ], -) - -py_proto_library( - name = "v2x_junction_py_pb2", - deps = [ - ":v2x_junction_proto", - "//modules/common_msgs/basic_msgs:geometry_py_pb2", - ], -) - -cc_proto_library( - name = "v2x_traffic_light_policy_cc_proto", - deps = [ - ":v2x_traffic_light_policy_proto", - ], -) - -proto_library( - name = "v2x_traffic_light_policy_proto", - srcs = ["v2x_traffic_light_policy.proto"], -) - -py_proto_library( - name = "v2x_traffic_light_policy_py_pb2", - deps = [ - ":v2x_traffic_light_policy_proto", - ], -) diff --git a/modules/v2x/proto/fusion_params.proto b/modules/v2x/proto/fusion_params.proto deleted file mode 100644 index cc89ec3727a..00000000000 --- a/modules/v2x/proto/fusion_params.proto +++ /dev/null @@ -1,37 +0,0 @@ -syntax = "proto2"; - -package apollo.v2x.ft.fusion; - -message KMParams { - optional double min_score = 1; -} - -message Param { - optional double k = 1; - optional double b = 2; -} - -message SingleCameraParam { - optional int32 camera_id = 1; - repeated Param param = 2; -} -enum ConfidenceLevel { - C90P = 0; - C95P = 1; - C975P = 2; - C99P = 3; -} -message ScoreParams { - optional double prob_scale = 1; - optional double max_match_distance = 2; - optional double min_score = 3; - optional bool use_mahalanobis_distance = 4 [default = false]; - optional bool check_type = 5 [default = false]; - optional ConfidenceLevel confidence_level = 6 [default = C975P]; -} - -message FusionParams { - repeated SingleCameraParam fusion_params= 1; - optional KMParams km_params = 2; - required ScoreParams score_params = 3; -} diff --git a/modules/v2x/proto/v2x_car_status.proto b/modules/v2x/proto/v2x_car_status.proto deleted file mode 100644 index 48c9469b2b7..00000000000 --- a/modules/v2x/proto/v2x_car_status.proto +++ /dev/null @@ -1,14 +0,0 @@ -syntax = "proto2"; - -package apollo.v2x; - -import "modules/common_msgs/localization_msgs/localization.proto"; -import "modules/common_msgs/chassis_msgs/chassis_detail.proto"; -import "modules/v2x/proto/v2x_junction.proto"; - -message CarStatus { - optional apollo.localization.LocalizationEstimate localization = 1; - optional apollo.canbus.ChassisDetail chassis_detail = 2; - optional apollo.v2x.Junction junction = 3; - optional Id rsu_id = 4; -} diff --git a/modules/v2x/proto/v2x_junction.proto b/modules/v2x/proto/v2x_junction.proto deleted file mode 100644 index 77c5583cd03..00000000000 --- a/modules/v2x/proto/v2x_junction.proto +++ /dev/null @@ -1,38 +0,0 @@ -syntax = "proto2"; - -package apollo.v2x; - -import "modules/common_msgs/basic_msgs/geometry.proto"; - -message Id { - optional bytes id = 1; -} - -message Junction { - optional Id id = 1; - optional apollo.common.Polygon polygon = 2; - - // crosswalk in junction - repeated Id crosswalk_id = 3; - repeated Id overlap_id = 4; - - // The number of road segments (arms) that are involved. - // e.g 3-way junction indicates a T junction (two arms form one road) or a Y - // junction. - optional int32 num_road_segments = 5 [default = 4]; - // lanes in the junction - repeated Id lane_id = 6; - - enum Type { - UNKNOWN = 0; - IN_ROAD = 1; - CROSS_ROAD = 2; - }; - optional Type type = 7; - - enum EdgeType { - PHYSICAL = 0; - VIRTUAL = 1; - }; - repeated EdgeType edge_type = 8; -} diff --git a/modules/v2x/proto/v2x_monitor.proto b/modules/v2x/proto/v2x_monitor.proto deleted file mode 100644 index d4afaf3bf5a..00000000000 --- a/modules/v2x/proto/v2x_monitor.proto +++ /dev/null @@ -1,20 +0,0 @@ -syntax = "proto2"; - -package apollo.v2x; - -enum ErrorCode { - LTEV = 500; - NET = 501; - CPU = 502; - MEM = 503; - GPS = 504; - MAP = 510; - SPAT = 511; - OBUID = 999; -} - -message ObuAlarm { - required double mode_num = 1; - required ErrorCode error_num = 2; - required string error_msg = 3; -} diff --git a/modules/v2x/proto/v2x_obstacles.proto b/modules/v2x/proto/v2x_obstacles.proto deleted file mode 100644 index 9bd4fdb1fc6..00000000000 --- a/modules/v2x/proto/v2x_obstacles.proto +++ /dev/null @@ -1,52 +0,0 @@ -syntax = "proto2"; - -package apollo.v2x; - -import "modules/common_msgs/basic_msgs/header.proto"; -import "modules/common_msgs/basic_msgs/error_code.proto"; -import "modules/common_msgs/perception_msgs/perception_obstacle.proto"; - -message Point { - optional double x = 1; // in meters. - optional double y = 2; // in meters. - optional double z = 3; // height in meters. -} - -message MiniAreaMap { - optional bytes rscu_id = 1; // RSCU id. - optional Point feature_position = 2; // the centre of intersection or sstraight area - optional Point start_position = 3; // the centre of intersection or sstraight area - optional Point end_position = 4; // the centre of intersection or sstraight area -} - -message AbnormalInformation { - optional double average_speed = 1; - optional double vehicle_density = 2; -} - -message V2XInformation { - enum V2XType { - NONE = 0; - ZOMBIES_CAR = 1; - BLIND_ZONE = 2; - }; - repeated V2XType v2x_type = 1; // use case type - optional Point traffic_event_start = 3; // congestion or others initial position. - optional Point traffic_event_start_error = 4; // congestion or others initial position error. - optional Point traffic_event_end = 5; // congestion or others end position. - optional Point traffic_event_end_error = 6; // congestion or others end position error. - optional AbnormalInformation abnormal_info = 7; // abnormal info -} - -message V2XObstacle { - optional apollo.perception.PerceptionObstacle perception_obstacle = 1; // obstacle. - optional V2XInformation v2x_info = 2; // v2x use case info -} - -message V2XObstacles { - repeated V2XObstacle v2x_obstacle = 1; // An array of obstacles - optional MiniAreaMap area_map = 2; // Mini area map - optional double traffic_flow = 3; // Traffic flow - optional apollo.common.Header header = 4; // Header - optional apollo.common.ErrorCode error_code = 5 [default = OK]; // perception error code -} diff --git a/modules/v2x/proto/v2x_obu_rsi.proto b/modules/v2x/proto/v2x_obu_rsi.proto deleted file mode 100644 index 15ae40b8a37..00000000000 --- a/modules/v2x/proto/v2x_obu_rsi.proto +++ /dev/null @@ -1,18 +0,0 @@ -syntax = "proto2"; - -package apollo.v2x.obu; - -import "modules/common_msgs/basic_msgs/header.proto"; -import "modules/common_msgs/basic_msgs/geometry.proto"; - -message ObuRsi { - optional apollo.common.Header header = 1; - optional bytes rsu_id = 2; - optional int32 rsi_id = 3; - optional int32 alter_type = 4; - optional string description = 5; - optional apollo.common.Point2D ref_point = 6; - repeated apollo.common.Point2D points = 7; - optional int32 radius = 8; - optional int32 msg_cnt = 9; -} diff --git a/modules/v2x/proto/v2x_obu_traffic_light.proto b/modules/v2x/proto/v2x_obu_traffic_light.proto deleted file mode 100644 index e8633e9ed7f..00000000000 --- a/modules/v2x/proto/v2x_obu_traffic_light.proto +++ /dev/null @@ -1,47 +0,0 @@ -syntax = "proto2"; - -package apollo.v2x.obu; - -import "modules/common_msgs/basic_msgs/header.proto"; -import "modules/common_msgs/v2x_msgs/v2x_traffic_light.proto"; - -message SingleTrafficLight { - enum Type { - STRAIGHT = 1; - LEFT = 2; - RIGHT = 3; - U_TURN = 4; - }; - - optional apollo.v2x.SingleTrafficLight.Color color = 1; - optional int32 traffic_light_type = 2; - // Traffic light string-ID in the map data. - optional string id = 3; - optional int32 color_remaining_time_s = 4; - optional bool right_turn_light = 5; - // v2x next traffic light color - optional apollo.v2x.SingleTrafficLight.Color next_color = 6; - // v2x next traffic light remaining time - optional double next_remaining_time = 7; - // next 2nd traffic ligth color - optional apollo.v2x.SingleTrafficLight.Color next_2nd_color = 8; - optional double next_2nd_remaining_time = 9; -} - -message LaneTrafficLight { - // Feature points of lane in the map reference frame. - optional double gps_x_m = 1; - optional double gps_y_m = 2; - repeated SingleTrafficLight single_traffic_light = 3; -} - -message RoadTrafficLight { - repeated LaneTrafficLight lane_traffic_light = 1; - optional int32 road_direction = 2; -} -message ObuTrafficLight { - optional apollo.common.Header header = 1; - repeated RoadTrafficLight road_traffic_light = 2; - optional int32 intersection_id = 3; - optional bytes hdmap_junction_id = 4; -} diff --git a/modules/v2x/proto/v2x_rsi.proto b/modules/v2x/proto/v2x_rsi.proto deleted file mode 100644 index 008abc0428d..00000000000 --- a/modules/v2x/proto/v2x_rsi.proto +++ /dev/null @@ -1,21 +0,0 @@ -syntax = "proto2"; - -package apollo.v2x; - -import "modules/common_msgs/basic_msgs/header.proto"; - -message RsiPoint { - optional double x = 1; // in meters. - optional double y = 2; // in meters. -} -message RsiMsg { - optional apollo.common.Header header = 1; - repeated RsiPoint points = 2; - optional double speed = 3; - optional double low_speed = 4; - optional double high_speed = 5; - optional string description = 6; - optional int32 rsi_type = 7; - optional double radius = 8; - optional int32 priority = 9; -} diff --git a/modules/v2x/proto/v2x_service_car_to_obu.proto b/modules/v2x/proto/v2x_service_car_to_obu.proto deleted file mode 100644 index b7c3645f48a..00000000000 --- a/modules/v2x/proto/v2x_service_car_to_obu.proto +++ /dev/null @@ -1,13 +0,0 @@ -syntax = "proto2"; - -package apollo.v2x; - -import "modules/v2x/proto/v2x_car_status.proto"; - -service CarToObu { - rpc PushCarStatus(apollo.v2x.CarStatus) returns (UpdateStatus) {} -} - -message UpdateStatus { - required bool updated = 1 [default = false]; -} diff --git a/modules/v2x/proto/v2x_service_obu_to_car.proto b/modules/v2x/proto/v2x_service_obu_to_car.proto deleted file mode 100644 index ef99a151573..00000000000 --- a/modules/v2x/proto/v2x_service_obu_to_car.proto +++ /dev/null @@ -1,28 +0,0 @@ -syntax = "proto2"; - -package apollo.v2x; - -import "modules/v2x/proto/v2x_obu_traffic_light.proto"; -import "modules/v2x/proto/v2x_monitor.proto"; -import "modules/v2x/proto/v2x_obu_rsi.proto"; -import "modules/v2x/proto/v2x_obstacles.proto"; - -service ObuToCar { - // for onboard unit send perception obstacles (from rsu) results to car end - rpc SendPerceptionObstacles(apollo.v2x.V2XObstacles) - returns (StatusResponse) {} - // for onboard unit send v2x traffic_lights (from rsu) results to car end - rpc SendV2xTrafficLight(apollo.v2x.obu.ObuTrafficLight) - returns (StatusResponse) {} - // rsi message - rpc SendV2xRSI(apollo.v2x.obu.ObuRsi) returns (StatusResponse) {} - // v2x obu monitor - rpc SendObuAlarm(apollo.v2x.ObuAlarm) returns (StatusResponse) {} -} - -// The response message containing the status. -message StatusResponse { - required bool status = 1 [default = false]; - optional string info = 2; - optional int64 error_code = 3; -} diff --git a/modules/v2x/proto/v2x_traffic_light_policy.proto b/modules/v2x/proto/v2x_traffic_light_policy.proto deleted file mode 100644 index 840e5e833ec..00000000000 --- a/modules/v2x/proto/v2x_traffic_light_policy.proto +++ /dev/null @@ -1,75 +0,0 @@ -syntax = "proto2"; - -package apollo.v2x; - -message Position2D { - optional double x = 1; - optional double y = 2; -} - -message Connection { - enum Type { - STRAIGHT = 0; - LEFT = 1; - RIGHT = 2; - U_TURN = 3; - }; - optional Type allow_driving_behavior = 1; - optional int32 phase_id = 2; -} - -message Lane { - optional int32 lane_id = 1; - repeated Position2D position_offset = 2; - repeated Connection connections = 3; -} - -message Road { - optional int32 upstream_node_id = 1; - optional Position2D points = 2; - repeated Lane lanes = 3; -} - -message Intersection { - optional int32 id = 1; - optional Position2D position = 2; - repeated Road roads = 3; -} - -message Map { - optional double time_stamp = 1; - optional int32 msg_cnt = 2; - repeated Intersection intersections = 3; -} - -message Phase { - enum Color { - UNKNOWN = 0; - RED = 1; - YELLOW = 2; - GREEN = 3; - BLACK = 4; - FLASH_GREEN = 5; - }; - optional int32 id = 1; - optional Color color = 2; - optional int32 color_remaining_time_s = 3; -} - -message IntersectionState { - optional int32 intersection_id = 1; - repeated Phase Phases = 2; - optional int32 moy = 3; - optional int32 time_stamp_dsecond = 4; -} - -message Spat { - optional double time_stamp = 1; - optional int32 msg_cnt = 2; - repeated IntersectionState intersections = 3; -} - -message PolicyData { - optional Map map = 1; - optional Spat spat = 2; -} diff --git a/modules/v2x/v2x.BUILD b/modules/v2x/v2x.BUILD deleted file mode 100644 index b8c55ed633f..00000000000 --- a/modules/v2x/v2x.BUILD +++ /dev/null @@ -1,11 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_library") - -cc_library( - name = "v2x", - includes = ["include"], - hdrs = glob(["include/**/*.h"]), - srcs = glob(["lib/**/*.so*"]), - include_prefix = "modules/v2x", - strip_include_prefix = "include", - visibility = ["//visibility:public"], -) \ No newline at end of file diff --git a/modules/v2x/v2x_proxy/app/BUILD b/modules/v2x/v2x_proxy/app/BUILD deleted file mode 100644 index 9bc6469953a..00000000000 --- a/modules/v2x/v2x_proxy/app/BUILD +++ /dev/null @@ -1,78 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library", "cc_test") -load("//tools:cpplint.bzl", "cpplint") -load("//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - -install( - name = "install", - runtime_dest = "v2x/bin", - targets = [ - ":v2x", - ] -) - -cc_library( - name = "utils", - srcs = ["utils.cc"], - hdrs = ["utils.h"], - deps = [ - "//cyber", - "//modules/common/math", - "//modules/map/hdmap:hdmap_util", - "//modules/v2x/v2x_proxy/obu_interface:obu_interface_grpc_impl", - "//modules/v2x/v2x_proxy/os_interface", - "//modules/v2x/v2x_proxy/proto_adapter", - ], -) - -cc_library( - name = "v2x_proxy", - srcs = ["v2x_proxy.cc"], - hdrs = ["v2x_proxy.h"], - deps = [ - ":utils", - "//cyber", - "//modules/map/hdmap:hdmap_util", - "//modules/v2x/v2x_proxy/obu_interface:obu_interface_grpc_impl", - "//modules/v2x/v2x_proxy/os_interface", - "//modules/v2x/v2x_proxy/proto_adapter", - ], -) - -#cc_test( -# name = "v2x_proxy_test", -# srcs = [ -# "v2x_proxy_test.cc", -# ], -# deps = [ -# ":v2x_proxy", -# "@com_google_googletest//:gtest_main", -# ], -#) - -cc_binary( - name = "v2x", - srcs = ["main.cc"], - deps = [ - ":v2x_proxy", - ], -) - -cc_test( - name = "utils_test", - size = "small", - timeout = "short", - srcs = ["utils_test.cc"], - deps = [ - ":utils", - "//cyber", - "//modules/map/hdmap:hdmap_util", - "//modules/v2x/v2x_proxy/obu_interface:obu_interface_grpc_impl", - "//modules/v2x/v2x_proxy/os_interface", - "//modules/v2x/v2x_proxy/proto_adapter", - "@com_google_googletest//:gtest_main", - ], -) - -cpplint() diff --git a/modules/v2x/v2x_proxy/app/main.cc b/modules/v2x/v2x_proxy/app/main.cc deleted file mode 100644 index d0174acdcd2..00000000000 --- a/modules/v2x/v2x_proxy/app/main.cc +++ /dev/null @@ -1,34 +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. - *****************************************************************************/ - -/** - * @file main.cc - * @brief v2x proxy main function - */ -#include "modules/v2x/v2x_proxy/app/v2x_proxy.h" - -int main(int argc, char *argv[]) { - google::ParseCommandLineFlags(&argc, &argv, true); - ::apollo::cyber::Init(argv[0]); - ::apollo::v2x::V2xProxy v2x_proxy; - if (!v2x_proxy.InitFlag()) { - AERROR << "Failed to initialize v2x proxy"; - ::apollo::cyber::Clear(); - return -1; - } - ::apollo::cyber::WaitForShutdown(); - return 0; -} diff --git a/modules/v2x/v2x_proxy/app/utils.cc b/modules/v2x/v2x_proxy/app/utils.cc deleted file mode 100644 index d134c23781d..00000000000 --- a/modules/v2x/v2x_proxy/app/utils.cc +++ /dev/null @@ -1,532 +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 utils.cc - * @brief utils for v2x_proxy - */ - -#include "modules/v2x/v2x_proxy/app/utils.h" - -#include - -#include "modules/common/math/quaternion.h" - -namespace apollo { -namespace v2x { - -InternalData::InternalData() { - remaining_time_ = new int32_t[kBufferSize]; - msg_timestamp_ = new double[kBufferSize]; - CHECK_NOTNULL(remaining_time_); - CHECK_NOTNULL(msg_timestamp_); - obu_light_ = std::make_shared(); - this->reset(); -} - -InternalData::~InternalData() { - delete[] remaining_time_; - delete[] msg_timestamp_; -} - -void InternalData::reset() { - oslight_ = nullptr; - intersection_id_ = -1; - change_color_timestamp_ = 0.0; -} - -bool InternalData::TrafficLightProc( - const std::shared_ptr<::apollo::hdmap::HDMap> &hdmap, double distance, - ::apollo::v2x::RoadTrafficLight *msg) { - if (nullptr == msg) { - return false; - } - if (!msg->has_gps_x_m() || !msg->has_gps_y_m()) { - AERROR << "Error::v2x traffic_light ignore, gps point is null"; - return false; - } - ::apollo::common::PointENU point; - point.set_x(msg->gps_x_m()); - point.set_y(msg->gps_y_m()); - if (0 == msg->single_traffic_light_size()) { - AERROR << "Error::v2x traffic_light ignore, size of single light is 0."; - return false; - } - if (0 == msg->single_traffic_light(0).traffic_light_type_size()) { - return false; - } - ::apollo::hdmap::LaneInfoConstPtr laneinfo; - double dummy_s = 0, dummy_l = 0; - if (0 != hdmap->GetNearestLane(point, &laneinfo, &dummy_s, &dummy_l)) { - return false; - } - std::vector<::apollo::hdmap::SignalInfoConstPtr> signals; - if (0 != hdmap->GetForwardNearestSignalsOnLane(point, distance, &signals)) { - AERROR << "Error::v2x traffic_light ignore, hdmap get no signals." - << "traffic light size : " << signals.size() << " " - << std::setiosflags(std::ios::fixed) << std::setprecision(11) - << "Point:x=" << point.x() << ",y=" << point.y(); - return false; - } - if (signals.empty()) { - AERROR << "Get traffic light size : " << signals.size() << " " - << std::setiosflags(std::ios::fixed) << std::setprecision(11) - << "Point:x=" << point.x() << ",y=" << point.y(); - return false; - } - AINFO << "the size of traffic light from HDMap is: " << signals.size(); - auto tl_type = msg->single_traffic_light(0).traffic_light_type(0); - auto color = msg->single_traffic_light(0).color(); - auto remaining_time = msg->single_traffic_light(0).color_remaining_time_s(); - auto next_color = msg->single_traffic_light(0).next_color(); - auto next_remaining_time = - msg->single_traffic_light(0).next_remaining_time_s(); - msg->clear_single_traffic_light(); - for (size_t i = 0; i < signals.size(); i++) { - auto signal_info = signals[i]; - auto single = msg->add_single_traffic_light(); - single->set_id(signal_info->id().id()); - single->add_traffic_light_type(tl_type); - single->set_color(color); - single->set_color_remaining_time_s(remaining_time); - single->set_next_color(next_color); - single->set_next_remaining_time_s(next_remaining_time); - } - return true; -} - -bool IsRushHour() { - std::time_t local = std::time(nullptr); - std::tm now = {}; - localtime_r(&local, &now); - return now.tm_hour > 16; -} - -bool InternalData::ProcTrafficlight( - const std::shared_ptr<::apollo::hdmap::HDMap> &hdmap, - const ObuLight *x2v_traffic_light, const std::string &junction_id, - bool flag_u_turn, double distance, double check_time, - std::shared_ptr *os_light) { - if (nullptr == os_light) { - return false; - } - if (nullptr == *os_light) { - return false; - } - if (!x2v_traffic_light) { - if (junction_id == kUnknownJunctionId) { - return false; - } - return true; - } - if (junction_id != x2v_traffic_light->hdmap_junction_id()) { - AWARN << "current junction id " << junction_id - << ", received the junction id " - << x2v_traffic_light->hdmap_junction_id(); - return false; - } - std::shared_ptr os_traffic_light = nullptr; - if (!ProtoAdapter::LightObu2Sys(*x2v_traffic_light, &os_traffic_light)) { - return false; - } - int num_os_traffic_light = os_traffic_light->road_traffic_light_size(); - if (0 == num_os_traffic_light) { - AERROR << "Ignored no traffic light contained after conventor."; - return false; - } - std::shared_ptr sim_traffic_light_data = nullptr; - // enter the new intersection if the sim message is not null, clear - auto cur_junction_id = x2v_traffic_light->intersection_id(); - auto tmp_os_traffic_light = std::make_shared(); - tmp_os_traffic_light->CopyFrom(*os_traffic_light); - // clear road traffic light - tmp_os_traffic_light->clear_road_traffic_light(); - for (int i = 0; i < num_os_traffic_light; i++) { - auto os_current_light = os_traffic_light->mutable_road_traffic_light(i); - if (!TrafficLightProc(hdmap, distance, os_current_light)) { - AERROR << "Traffic light proc failed"; - continue; - } - if (os_current_light->single_traffic_light_size() > 0) { - auto tmp_os_current_light = - tmp_os_traffic_light->add_road_traffic_light(); - tmp_os_current_light->CopyFrom(*(os_current_light)); - } - } - tmp_os_traffic_light->set_confidence(IsRushHour() ? 0.5 : 1.0); - AINFO << "all traffic light send to os BEFORE is: " - << os_traffic_light->DebugString(); - if (0 == tmp_os_traffic_light->road_traffic_light_size()) { - return false; - } - cur_junction_id = x2v_traffic_light->intersection_id(); - tmp_os_traffic_light->set_intersection_id(cur_junction_id); - // enter a new junction, need to clear the list - if (cur_junction_id != intersection_id_) { - AINFO << "Enter New Juncion: " << cur_junction_id; - oslight_ = nullptr; - intersection_id_ = cur_junction_id; - int num_traffic_light = tmp_os_traffic_light->road_traffic_light_size(); - for (int i = 0; i < num_traffic_light; i++) { - auto remaining_time = tmp_os_traffic_light->road_traffic_light(i) - .single_traffic_light(0) - .color_remaining_time_s(); - remaining_time_[i] = remaining_time; - msg_timestamp_[i] = x2v_traffic_light->header().timestamp_sec(); - } - } else { - ADEBUG << "Same Juncion: " << cur_junction_id; - if (flag_u_turn) { - for (unsigned int i = 0; i < kBufferSize; i++) { - msg_timestamp_[i] = 0.0; - remaining_time_[i] = -1; - } - oslight_ = nullptr; - } - int num_traffic_light = tmp_os_traffic_light->road_traffic_light_size(); - for (int i = 0; i < num_traffic_light; i++) { - auto remaining_time = tmp_os_traffic_light->road_traffic_light(i) - .single_traffic_light(0) - .color_remaining_time_s(); - if ((remaining_time_[i] != remaining_time)) { - remaining_time_[i] = remaining_time; - msg_timestamp_[i] = x2v_traffic_light->header().timestamp_sec(); - } - } - if (!!oslight_) { - int road_valid_size = - std::min(oslight_->road_traffic_light_size(), - tmp_os_traffic_light->road_traffic_light_size()); - for (int i = 0; i < road_valid_size; i++) { - const auto &last_msg_road = oslight_->road_traffic_light(i); - auto current_msg_road = - tmp_os_traffic_light->mutable_road_traffic_light(i); - int single_valid_size = - std::min(last_msg_road.single_traffic_light_size(), - current_msg_road->single_traffic_light_size()); - for (int j = 0; j < single_valid_size; j++) { - const auto &last_msg_single_traffic_light = - last_msg_road.single_traffic_light(j); - auto current_msg_single_traffic_light = - current_msg_road->mutable_single_traffic_light(j); - if (last_msg_single_traffic_light.color() == - current_msg_single_traffic_light->color()) { - if (current_msg_single_traffic_light->color_remaining_time_s() > - last_msg_single_traffic_light.color_remaining_time_s()) { - AINFO << "correct the remaining time"; - current_msg_single_traffic_light->set_color_remaining_time_s( - last_msg_single_traffic_light.color_remaining_time_s()); - } - } - } - } - } - } - oslight_ = std::make_shared<::apollo::v2x::IntersectionTrafficLightData>(); - oslight_->CopyFrom(*tmp_os_traffic_light); - (*os_light)->CopyFrom(*tmp_os_traffic_light); - return true; -} - -bool InternalData::ProcPlanningMessage( - const ::apollo::planning::ADCTrajectory *planning_msg, - const OSLight *last_os_light, - std::shared_ptr<::apollo::perception::TrafficLightDetection> *res_light) { - if (!planning_msg || !res_light || !(*res_light)) { - return false; - } - // Keep this blank header for protect other module against coredump. - (*res_light)->mutable_header(); - if (!planning_msg->has_debug() || - !planning_msg->debug().has_planning_data()) { - return false; - } - const auto &planning_debug = planning_msg->debug().planning_data(); - if (!planning_debug.has_signal_light() || - 0 == planning_debug.signal_light().signal_size()) { - return false; - } - const std::string light_id = - planning_debug.signal_light().signal(0).light_id(); - if (!last_os_light || light_id.empty()) { - return true; // output traffic light without v2x; - } - ::apollo::common::Direction attr = ::apollo::common::Direction::EAST; - bool found = false; - for (int idx = 0; idx < last_os_light->road_traffic_light_size(); idx++) { - const auto &road_tl = last_os_light->road_traffic_light(idx); - if (0 == road_tl.single_traffic_light_size()) { - continue; - } - if (road_tl.single_traffic_light(0).id() == light_id) { - attr = road_tl.road_attribute(); - found = true; - break; - } - } - if (!found) { - AWARN << "Failed to find light_id from os_light: " << light_id - << " , Ignored"; - return true; // output traffic light without v2x; - } - (*res_light)->clear_traffic_light(); - auto res_frame_id = std::to_string(last_os_light->has_intersection_id() - ? last_os_light->intersection_id() - : -1); - (*res_light)->mutable_header()->set_frame_id(res_frame_id); - AINFO << "Selected road attr: " << ::apollo::common::Direction_Name(attr); - std::set idset; - for (int idx = 0; idx < last_os_light->road_traffic_light_size(); idx++) { - const auto &road_tl = last_os_light->road_traffic_light(idx); - if (0 == road_tl.single_traffic_light_size()) { - continue; - } - if (road_tl.road_attribute() != attr) { - continue; - } - const auto &single_tl = road_tl.single_traffic_light(0); - if (single_tl.traffic_light_type_size() < 1) { - continue; - } - auto *light1 = (*res_light)->add_traffic_light(); - // SET ID - // light1->set_id(single_tl.id()); - light1->set_id(SingleTrafficLight_Type_Name( // - single_tl.traffic_light_type(0))); - idset.emplace(single_tl.id()); - - if (single_tl.has_color()) { - switch (single_tl.color()) { - case OSLightColor::SingleTrafficLight_Color_RED: - light1->set_color( - ::apollo::perception::TrafficLight_Color::TrafficLight_Color_RED); - break; - case OSLightColor::SingleTrafficLight_Color_YELLOW: - light1->set_color(::apollo::perception::TrafficLight_Color:: - TrafficLight_Color_YELLOW); - break; - case OSLightColor::SingleTrafficLight_Color_GREEN: - case OSLightColor::SingleTrafficLight_Color_FLASH_GREEN: - light1->set_color(::apollo::perception::TrafficLight_Color:: - TrafficLight_Color_GREEN); - break; - case OSLightColor::SingleTrafficLight_Color_BLACK: - light1->set_color(::apollo::perception::TrafficLight_Color:: - TrafficLight_Color_BLACK); - break; - default: - light1->set_color(::apollo::perception::TrafficLight_Color:: - TrafficLight_Color_UNKNOWN); - break; - } - } - // REMAINING_TIME - if (single_tl.has_color_remaining_time_s()) { - light1->set_remaining_time(single_tl.color_remaining_time_s()); - } - } - return true; -} -namespace utils { -bool FindAllRoadId(const std::shared_ptr<::apollo::hdmap::HDMap> &hdmap, - const ::apollo::hdmap::LaneInfoConstPtr &start_laneinfo, - const ::apollo::hdmap::LaneInfoConstPtr &end_laneinfo, - size_t max_road_count, - std::unordered_set *result_id_set) { - if (!result_id_set) { - return false; - } - size_t road_counter = 0; - ::apollo::hdmap::Id id; - result_id_set->clear(); - result_id_set->insert(start_laneinfo->road_id().id()); - ::apollo::hdmap::LaneInfoConstPtr start_laneinfo_tmp = start_laneinfo; - while (true) { - if (0 == start_laneinfo_tmp->lane().successor_id_size()) { - AINFO << "The lane has no successor"; - return false; - } - id = start_laneinfo_tmp->lane().successor_id(0); - AINFO << "Lane id " << id.id(); - start_laneinfo_tmp = hdmap->GetLaneById(id); - if (start_laneinfo_tmp == nullptr) { - AINFO << "Get lane by id is null."; - return false; - } - result_id_set->insert(start_laneinfo_tmp->road_id().id()); - if (start_laneinfo_tmp->road_id().id() == end_laneinfo->road_id().id()) { - std::stringstream ss; - ss << "find all the road id: "; - for (const auto &item : *result_id_set) { - ss << item << " "; - } - AINFO << ss.str(); - return true; - } - road_counter++; - if (road_counter > max_road_count) { - AINFO << "not find the end road id after try " << road_counter; - return false; - } - } -} - -bool CheckCarInSet(const std::shared_ptr<::apollo::hdmap::HDMap> &hdmap, - const std::unordered_set &id_set, - const ::apollo::hdmap::LaneInfoConstPtr &car_laneinfo, - size_t max_lane_count) { - size_t lane_counter = 0; - ::apollo::hdmap::Id id; - auto car_laneinfo_tmp = car_laneinfo; - while (true) { - if (id_set.count(car_laneinfo_tmp->road_id().id()) == 1) { - AINFO << "find the car is in the speed limit region"; - return true; - } - if (car_laneinfo_tmp->lane().successor_id_size() == 0) { - AWARN << "The lane of the card no successor"; - return false; - } - id = car_laneinfo_tmp->lane().successor_id(0); - AINFO << "Lane id " << id.id(); - car_laneinfo_tmp = hdmap->GetLaneById(id); - if (car_laneinfo_tmp == nullptr) { - AWARN << "Get lane by id is null."; - return false; - } else { - if (++lane_counter > max_lane_count) { - AWARN << "not find the road in after try to " << lane_counter; - return false; - } - } - } -} - -bool GetRsuInfo(const std::shared_ptr<::apollo::hdmap::HDMap> &hdmap, - const OSLocation &os_location, - const std::set &rsu_whitelist, double distance, - double max_heading_difference, - std::shared_ptr<::apollo::v2x::CarStatus> *v2x_car_status, - std::string *out_junction_id, double *out_heading) { - if (!v2x_car_status) { - return false; - } - if (!out_junction_id) { - return false; - } - if (!out_heading) { - return false; - } - *out_junction_id = kUnknownJunctionId; - auto res = std::make_shared<::apollo::v2x::CarStatus>(); - if (nullptr == res) { - return false; - } - if (!os_location.has_header()) { - return false; - } - if (!os_location.has_pose()) { - return false; - } - res->mutable_localization()->CopyFrom(os_location); - ::apollo::common::PointENU point; - point.set_x(os_location.pose().position().x()); - point.set_y(os_location.pose().position().y()); - double heading = ::apollo::common::math::QuaternionToHeading( - os_location.pose().orientation().qw(), - os_location.pose().orientation().qx(), - os_location.pose().orientation().qy(), - os_location.pose().orientation().qz()); - *out_heading = heading; - std::vector<::apollo::hdmap::RSUInfoConstPtr> rsus; - if (0 != hdmap->GetForwardNearestRSUs(point, distance, heading, - max_heading_difference, &rsus) || - rsus.empty()) { - AINFO << "no rsu is found"; - return false; - } - AINFO << "Get " << rsus.size() << " rsu(s)"; - if (rsu_whitelist.find(rsus[0]->id().id() + "_tl") == rsu_whitelist.cend()) { - AINFO << "This rsu id '" << rsus[0]->id().id() - << "' is not in the white list"; - return false; - } - AINFO << "This RSU is in the white list"; - AINFO << "Junction id " << rsus[0]->rsu().junction_id().id(); - auto junction_info = hdmap->GetJunctionById(rsus[0]->rsu().junction_id()); - if (nullptr == junction_info) { - return false; - } - std::shared_ptr<::apollo::v2x::ObuJunction> obu_junction = nullptr; - if (!ProtoAdapter::JunctionHd2obu(junction_info, &obu_junction)) { - return false; - } - res->mutable_junction()->CopyFrom(*obu_junction); - *v2x_car_status = res; - *out_junction_id = junction_info->id().id(); - return true; -} - -OSLightColor GetNextColor(OSLightColor color) { - switch (color) { - case OSLightColor::SingleTrafficLight_Color_GREEN: - return OSLightColor::SingleTrafficLight_Color_YELLOW; - case OSLightColor::SingleTrafficLight_Color_YELLOW: - return OSLightColor::SingleTrafficLight_Color_RED; - case OSLightColor::SingleTrafficLight_Color_RED: - return OSLightColor::SingleTrafficLight_Color_GREEN; - default: - return color; - } -} - -void UniqueOslight(OSLight *os_light) { - if (nullptr == os_light) { - return; - } - auto tmp_os_light = std::make_shared(); - tmp_os_light->CopyFrom(*os_light); - os_light->clear_road_traffic_light(); - std::set idset; - for (int idx_tl = 0; idx_tl < tmp_os_light->road_traffic_light_size(); - idx_tl++) { - const auto &tmp_road_tl = tmp_os_light->road_traffic_light(idx_tl); - for (int idx_single = 0; - idx_single < tmp_road_tl.single_traffic_light_size(); idx_single++) { - const auto &single = tmp_road_tl.single_traffic_light(idx_single); - if (0 == single.traffic_light_type_size()) { - continue; - } - std::string tmpid = - single.id() + - std::to_string(static_cast(single.traffic_light_type(0))); - // Has ID - if (idset.find(tmpid) != idset.cend()) { - continue; - } - idset.insert(tmpid); - // UNIQUE ID - auto res_tl = os_light->add_road_traffic_light(); - res_tl->set_gps_x_m(tmp_road_tl.gps_x_m()); - res_tl->set_gps_y_m(tmp_road_tl.gps_y_m()); - res_tl->set_road_attribute(tmp_road_tl.road_attribute()); - auto res_single = res_tl->add_single_traffic_light(); - res_single->CopyFrom(single); - } - } -} -} // namespace utils -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/app/utils.h b/modules/v2x/v2x_proxy/app/utils.h deleted file mode 100644 index d881ac1ad7f..00000000000 --- a/modules/v2x/v2x_proxy/app/utils.h +++ /dev/null @@ -1,100 +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 utils.h - * @brief utils for v2x_proxy - */ - -#pragma once - -#include -#include -#include -#include -#include -#include - -#include "modules/common_msgs/perception_msgs/traffic_light_detection.pb.h" -#include "modules/common_msgs/planning_msgs/planning.pb.h" - -#include "cyber/cyber.h" -#include "modules/map/hdmap/hdmap.h" -#include "modules/map/hdmap/hdmap_common.h" -#include "modules/v2x/v2x_proxy/proto_adapter/proto_adapter.h" - -namespace apollo { -namespace v2x { -const char *const kUnknownJunctionId = "unknown"; - -class InternalData final { - private: - static constexpr size_t kBufferSize = 40; - std::shared_ptr oslight_ = nullptr; - std::shared_ptr obu_light_ = nullptr; - int intersection_id_ = -1; - double change_color_timestamp_ = 0.0; - int32_t *remaining_time_ = nullptr; - double *msg_timestamp_ = nullptr; - - public: - InternalData(); - - virtual ~InternalData(); - - void reset(); - - bool TrafficLightProc(const std::shared_ptr<::apollo::hdmap::HDMap> &hdmap, - double distance, ::apollo::v2x::RoadTrafficLight *msg); - - bool ProcTrafficlight(const std::shared_ptr<::apollo::hdmap::HDMap> &hdmap, - const ObuLight *x2v_traffic_light, - const std::string &junction_id, bool flag_u_turn, - double distance, double check_time, - std::shared_ptr *os_light); - - bool ProcPlanningMessage( - const ::apollo::planning::ADCTrajectory *planning_msg, - const OSLight *last_os_light, - std::shared_ptr<::apollo::perception::TrafficLightDetection> *res_light); -}; -namespace utils { - -bool FindAllRoadId(const std::shared_ptr<::apollo::hdmap::HDMap> &hdmap, - const ::apollo::hdmap::LaneInfoConstPtr &start_laneinfo, - const ::apollo::hdmap::LaneInfoConstPtr &end_laneinfo, - size_t max_road_count, - std::unordered_set *result_id_set); - -bool CheckCarInSet(const std::shared_ptr<::apollo::hdmap::HDMap> &hdmap, - const std::unordered_set &id_set, - const ::apollo::hdmap::LaneInfoConstPtr &car_laneinfo, - size_t max_lane_count); - -bool GetRsuInfo(const std::shared_ptr<::apollo::hdmap::HDMap> &hdmap, - const OSLocation &os_location, - const std::set &rsu_whitelist, double distance, - double max_heading_difference, - std::shared_ptr<::apollo::v2x::CarStatus> *v2x_car_status, - std::string *out_junction_id, double *out_heading); - -OSLightColor GetNextColor(OSLightColor color); - -void UniqueOslight(OSLight *os_light); - -} // namespace utils - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/app/utils_test.cc b/modules/v2x/v2x_proxy/app/utils_test.cc deleted file mode 100644 index f877835bb62..00000000000 --- a/modules/v2x/v2x_proxy/app/utils_test.cc +++ /dev/null @@ -1,40 +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 utils_test.cc - */ - -#include "modules/v2x/v2x_proxy/app/utils.h" - -#include "gtest/gtest.h" - -namespace apollo { -namespace v2x { - -TEST(v2x_proxy_app, v2x_proxy_UtilsGetNextColor) { - EXPECT_EQ(OSLightColor::SingleTrafficLight_Color_YELLOW, - utils::GetNextColor(OSLightColor::SingleTrafficLight_Color_GREEN)); - EXPECT_EQ(OSLightColor::SingleTrafficLight_Color_RED, - utils::GetNextColor(OSLightColor::SingleTrafficLight_Color_YELLOW)); - EXPECT_EQ(OSLightColor::SingleTrafficLight_Color_GREEN, - utils::GetNextColor(OSLightColor::SingleTrafficLight_Color_RED)); - EXPECT_EQ(OSLightColor::SingleTrafficLight_Color_BLACK, - utils::GetNextColor(OSLightColor::SingleTrafficLight_Color_BLACK)); -} - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/app/v2x_proxy.cc b/modules/v2x/v2x_proxy/app/v2x_proxy.cc deleted file mode 100644 index 2c8b103df22..00000000000 --- a/modules/v2x/v2x_proxy/app/v2x_proxy.cc +++ /dev/null @@ -1,220 +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. - *****************************************************************************/ -/** - * @file v2x_proxy.cc - * @brief define v2x proxy class - */ -#include "modules/v2x/v2x_proxy/app/v2x_proxy.h" - -#include -#include -#include -#include - -#include "modules/v2x/common/v2x_proxy_gflags.h" - -namespace apollo { -namespace v2x { -using ::apollo::canbus::ChassisDetail; -using ::apollo::v2x::CarStatus; -using ::apollo::v2x::StatusResponse; -using ::apollo::v2x::obu::ObuRsi; -using ::apollo::v2x::obu::ObuTrafficLight; - -V2xProxy::~V2xProxy() { - if (recv_thread_ != nullptr && recv_thread_->joinable()) { - recv_thread_->join(); - } - if (planning_thread_ != nullptr && planning_thread_->joinable()) { - planning_thread_->join(); - } - if (obs_thread_ != nullptr && obs_thread_->joinable()) { - obs_thread_->join(); - } -} - -V2xProxy::V2xProxy(std::shared_ptr<::apollo::hdmap::HDMap> hdmap) - : node_(::apollo::cyber::CreateNode("v2x_proxy")), exit_(false) { - if (node_ == nullptr) { - AFATAL << "Create v2x proxy node failed."; - exit(1); - } - internal_ = std::make_shared(); - hdmap_ = std::make_shared<::apollo::hdmap::HDMap>(); - const auto hdmap_file = apollo::hdmap::BaseMapFile(); - if (0 != hdmap_->LoadMapFromFile(hdmap_file)) { - AERROR << "Failed to load hadmap file: " << hdmap_file; - return; - } - ::apollo::cyber::TimerOption v2x_car_status_timer_option; - v2x_car_status_timer_option.period = - static_cast((1000 + FLAGS_v2x_car_status_timer_frequency - 1) / - FLAGS_v2x_car_status_timer_frequency); - v2x_car_status_timer_option.callback = [this]() { - this->OnV2xCarStatusTimer(); - }; - v2x_car_status_timer_option.oneshot = false; - v2x_car_status_timer_.reset( - new ::apollo::cyber::Timer(v2x_car_status_timer_option)); - os_interface_.reset(new OsInterFace()); - obu_interface_.reset(new ObuInterFaceGrpcImpl()); - recv_thread_.reset(new std::thread([this]() { - while (!exit_.load()) { - this->RecvTrafficlight(); - } - })); - CHECK(!!hdmap_ && !!v2x_car_status_timer_); - CHECK(!!os_interface_ && !!obu_interface_); - CHECK(os_interface_->InitFlag() && obu_interface_->InitFlag()); - planning_thread_.reset(new std::thread([this]() { - while (!exit_.load()) { - this->RecvOsPlanning(); - } - })); - obs_thread_.reset(new std::thread([this]() { - while (!exit_.load()) { - std::shared_ptr<::apollo::v2x::V2XObstacles> obs = nullptr; - this->obu_interface_->GetV2xObstaclesFromObu(&obs); // Blocked - this->os_interface_->SendV2xObstacles2Sys(obs); - } - })); - v2x_car_status_timer_->Start(); - GetRsuListFromFile(FLAGS_rsu_whitelist_name, &rsu_list_); - init_flag_ = true; -} - -bool V2xProxy::GetRsuListFromFile(const std::string &filename, - std::set *whitelist) { - if (nullptr == whitelist) { - return false; - } - std::ifstream input_file(filename); - if (!input_file) { - return false; - } - std::string line; - while (getline(input_file, line)) { - whitelist->insert(line); - } - return !whitelist->empty(); -} - -bool V2xProxy::InitFlag() { return init_flag_; } - -void V2xProxy::RecvOsPlanning() { - auto adc_trajectory = std::make_shared<::apollo::planning::ADCTrajectory>(); - auto res_light = - std::make_shared<::apollo::perception::TrafficLightDetection>(); - os_interface_->GetPlanningAdcFromOs(adc_trajectory); - // OK get planning message - std::shared_ptr last_os_light = nullptr; - { - std::lock_guard lock(lock_last_os_light_); - - auto now_us = ::apollo::cyber::Time::MonoTime().ToMicrosecond(); - if (last_os_light_ == nullptr || - 2000LL * 1000 * 1000 < now_us - ts_last_os_light_) { - AWARN << "V2X Traffic Light is too old!"; - last_os_light_ = nullptr; - } else { - ADEBUG << "V2X Traffic Light is on time."; - last_os_light = std::make_shared(); - last_os_light->CopyFrom(*last_os_light_); - } - } - // proc planning message - bool res_proc_planning_msg = internal_->ProcPlanningMessage( - adc_trajectory.get(), last_os_light.get(), &res_light); - if (!res_proc_planning_msg) { - return; - } - os_interface_->SendV2xTrafficLight4Hmi2Sys(res_light); -} - -void V2xProxy::RecvTrafficlight() { - // get traffic light from obu - std::shared_ptr x2v_traffic_light = nullptr; - obu_interface_->GetV2xTrafficLightFromObu(&x2v_traffic_light); - os_interface_->SendV2xObuTrafficLightToOs(x2v_traffic_light); - auto os_light = std::make_shared(); - std::string junction_id = ""; - { - std::lock_guard lg(lock_hdmap_junction_id_); - junction_id = hdmap_junction_id_; - } - bool res_success_ProcTrafficlight = internal_->ProcTrafficlight( - hdmap_, x2v_traffic_light.get(), junction_id, u_turn_, - FLAGS_traffic_light_distance, FLAGS_check_time, &os_light); - if (!res_success_ProcTrafficlight) { - return; - } - utils::UniqueOslight(os_light.get()); - os_interface_->SendV2xTrafficLightToOs(os_light); - // save for hmi - std::lock_guard lock(lock_last_os_light_); - ts_last_os_light_ = ::apollo::cyber::Time::MonoTime().ToMicrosecond(); - last_os_light_ = os_light; -} - -double cal_distance(const ::apollo::common::PointENU &p1, - const ::apollo::common::PointENU &p2) { - double x = p1.x() - p2.x(); - double y = p1.y() - p2.y(); - return std::sqrt(x * x + y * y); -} - -void V2xProxy::OnV2xCarStatusTimer() { - // get loc - auto localization = - std::make_shared<::apollo::localization::LocalizationEstimate>(); - os_interface_->GetLocalizationFromOs(localization); - if (nullptr == localization) { - return; - } - std::set rsu_whitelist; - { - std::lock_guard lg(rsu_list_mutex_); - rsu_whitelist.insert(rsu_list_.cbegin(), rsu_list_.cend()); - } - ::apollo::common::PointENU car_position; - car_position.set_x(localization->pose().position().x()); - car_position.set_y(localization->pose().position().y()); - std::shared_ptr<::apollo::v2x::CarStatus> v2x_car_status = nullptr; - double heading = 0.0; - std::string res_junction_id = ""; - bool ret_get_rsu_info = utils::GetRsuInfo( - hdmap_, *localization, rsu_whitelist, FLAGS_traffic_light_distance, - FLAGS_heading_difference, &v2x_car_status, &res_junction_id, &heading); - { - std::lock_guard lg(lock_hdmap_junction_id_); - hdmap_junction_id_ = res_junction_id; - } - if (!ret_get_rsu_info) { - return; - } - // calc heading - if (!init_heading_) { - heading_ = heading; - init_heading_ = true; - } - if (std::fabs(heading_ - heading) > 1.0) { - u_turn_ = true; - } - obu_interface_->SendCarStatusToObu(v2x_car_status); -} - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/app/v2x_proxy.h b/modules/v2x/v2x_proxy/app/v2x_proxy.h deleted file mode 100644 index c270b0d247e..00000000000 --- a/modules/v2x/v2x_proxy/app/v2x_proxy.h +++ /dev/null @@ -1,105 +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. - *****************************************************************************/ - -/** - * @file v2x_proxy.h - * @brief define v2x proxy class - */ - -#pragma once - -#include -#include -#include -#include -#include - -#include "cyber/cyber.h" -#include "modules/map/hdmap/hdmap_util.h" -#include "modules/v2x/v2x_proxy/app/utils.h" -#include "modules/v2x/v2x_proxy/obu_interface/obu_interface_grpc_impl.h" -#include "modules/v2x/v2x_proxy/os_interface/os_interface.h" -#include "modules/v2x/v2x_proxy/proto_adapter/proto_adapter.h" - -namespace apollo { -namespace v2x { -bool IsRushHour(); - -class V2xProxy { - private: - std::shared_ptr internal_ = nullptr; - std::string hdmap_junction_id_ = kUnknownJunctionId; - std::mutex lock_hdmap_junction_id_; - // for hmi traffic lights - std::shared_ptr last_os_light_ = nullptr; - uint64_t ts_last_os_light_ = 0; - std::mutex lock_last_os_light_; - - public: - explicit V2xProxy(std::shared_ptr<::apollo::hdmap::HDMap> hdmap = nullptr); - - ~V2xProxy(); - - bool InitFlag(); - - void stop() { - exit_ = true; - v2x_car_status_timer_->Stop(); - obu_status_timer_->Stop(); - rsu_whitelist_timer_->Stop(); - } - - bool GetRsuListFromFile(const std::string &filename, - std::set *whitelist); - - private: - /* function RecvTrafficlight, get traffic light msg from grpc with timeout - */ - void RecvTrafficlight(); - - void RecvOsPlanning(); - /* function obu to car traffic light timer callback - */ - // void on_x2v_traffic_light_timer(); - std::unique_ptr<::apollo::cyber::Timer> v2x_car_status_timer_; - std::unique_ptr<::apollo::cyber::Timer> obu_status_timer_; - std::unique_ptr<::apollo::cyber::Timer> rsu_whitelist_timer_; - - std::unique_ptr<::apollo::cyber::Node> node_ = nullptr; - std::unique_ptr os_interface_; - std::unique_ptr obu_interface_; - std::unique_ptr recv_thread_ = nullptr; - std::unique_ptr planning_thread_ = nullptr; - std::unique_ptr rsi_thread_ = nullptr; - std::unique_ptr obs_thread_ = nullptr; - - /* function car to obu car status timer callback - */ - void OnV2xCarStatusTimer(); - - std::shared_ptr<::apollo::hdmap::HDMap> hdmap_; - - bool init_flag_ = false; - bool init_heading_ = false; - double heading_ = 0.0001; - bool u_turn_ = false; - std::atomic exit_; - std::mutex rsu_list_mutex_; - std::set rsu_list_; -}; - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/app/v2x_proxy_test.cc b/modules/v2x/v2x_proxy/app/v2x_proxy_test.cc deleted file mode 100644 index e4e5ca4417f..00000000000 --- a/modules/v2x/v2x_proxy/app/v2x_proxy_test.cc +++ /dev/null @@ -1,37 +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/v2x/v2x_proxy/app/v2x_proxy.h" - -#include -#include - -#include - -#include "gtest/gtest.h" - -#include "modules/v2x/v2x_proxy/app/utils.h" - -TEST(V2xProxy, V2xProxy) { - ::apollo::cyber::Init("TestCase"); - auto hdmap = std::make_shared<::apollo::hdmap::HDMap>(); - hdmap->LoadMapFromFile(apollo::hdmap::BaseMapFile()); - ::apollo::v2x::V2xProxy v2x_proxy(hdmap); - EXPECT_TRUE(v2x_proxy.InitFlag()); - sleep(1); - v2x_proxy.stop(); - ::apollo::cyber::Clear(); -} diff --git a/modules/v2x/v2x_proxy/obu_interface/BUILD b/modules/v2x/v2x_proxy/obu_interface/BUILD deleted file mode 100644 index 283679d7898..00000000000 --- a/modules/v2x/v2x_proxy/obu_interface/BUILD +++ /dev/null @@ -1,31 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -cc_library( - name = "obu_interface_grpc_impl", - srcs = ["obu_interface_grpc_impl.cc"], - hdrs = [ - "obu_interface_abstract_class.h", - "obu_interface_grpc_impl.h", - ], - deps = [ - "//modules/v2x/v2x_proxy/obu_interface/grpc_interface:grpc_client", - "//modules/v2x/v2x_proxy/obu_interface/grpc_interface:grpc_server", - "@com_github_grpc_grpc//:grpc++", - ], -) - -cc_test( - name = "obu_interface_grpc_impl_test", - size = "small", - srcs = ["obu_interface_grpc_impl_test.cc"], - deps = [ - ":obu_interface_grpc_impl", - "@com_google_googletest//:gtest_main", - ], - linkstatic = True, -) - -cpplint() diff --git a/modules/v2x/v2x_proxy/obu_interface/grpc_interface/BUILD b/modules/v2x/v2x_proxy/obu_interface/grpc_interface/BUILD deleted file mode 100644 index 5f2d40459a0..00000000000 --- a/modules/v2x/v2x_proxy/obu_interface/grpc_interface/BUILD +++ /dev/null @@ -1,57 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -cc_library( - name = "grpc_client", - srcs = ["grpc_client.cc"], - hdrs = ["grpc_client.h"], - deps = [ - "//cyber", - "//modules/v2x/common:v2x_proxy_gflags", - "//modules/v2x/proto:v2x_service_car_to_obu_cc_grpc", - "//modules/v2x/proto:v2x_service_obu_to_car_cc_grpc", - "@com_github_grpc_grpc//:grpc++", - ], -) - -cc_library( - name = "grpc_server", - srcs = ["grpc_server.cc"], - hdrs = ["grpc_server.h"], - deps = [ - "//cyber", - "//modules/common_msgs/perception_msgs:perception_obstacle_cc_proto", - "//modules/common_msgs/perception_msgs:traffic_light_detection_cc_proto", - "//modules/v2x/common:v2x_proxy_gflags", - "//modules/v2x/proto:v2x_obu_rsi_cc_proto", - "//modules/v2x/proto:v2x_service_car_to_obu_cc_grpc", - "//modules/v2x/proto:v2x_service_obu_to_car_cc_grpc", - "//modules/common_msgs/v2x_msgs:v2x_traffic_light_cc_proto", - "@com_github_grpc_grpc//:grpc++", - ], -) - -cc_test( - name = "grpc_client_test", - size = "small", - srcs = ["grpc_client_test.cc"], - deps = [ - ":grpc_client", - "@com_google_googletest//:gtest_main", - ], -) - -cc_test( - name = "grpc_server_test", - size = "small", - srcs = ["grpc_server_test.cc"], - deps = [ - ":grpc_server", - "@com_google_googletest//:gtest_main", - ], - linkstatic = True, -) - -cpplint() diff --git a/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_client.cc b/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_client.cc deleted file mode 100644 index bf49c59a275..00000000000 --- a/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_client.cc +++ /dev/null @@ -1,71 +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. - *****************************************************************************/ - -/** - * @file grpc_client.cc - * @brief define v2x proxy module and onboard unit interface grpc implement - */ - -#include "modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_client.h" - -#include - -#include "cyber/common/log.h" -#include "cyber/cyber.h" - -namespace apollo { -namespace v2x { - -using ::apollo::v2x::CarStatus; -using ::apollo::v2x::UpdateStatus; -using ::apollo::v2x::obu::ObuTrafficLight; -using grpc::Channel; -using grpc::ClientContext; -using grpc::Status; - -GrpcClientImpl::GrpcClientImpl(std::shared_ptr channel) - : stub_(::apollo::v2x::CarToObu::NewStub(channel)) { - AINFO << "GrpcClientImpl initial success"; - car_status_tv_nsec_ = (1000000000 / FLAGS_v2x_car_status_timer_frequency / 2); - init_flag_ = true; -} - -void GrpcClientImpl::SendMsgToGrpc(const std::shared_ptr &msg) { - if (!msg->has_localization()) { - return; - } - // set timeout - ClientContext context; - gpr_timespec timespec; - timespec.tv_sec = 0; - timespec.tv_nsec = car_status_tv_nsec_; // 80000000; // 80ms - timespec.clock_type = GPR_TIMESPAN; - context.set_deadline(timespec); - UpdateStatus response; - - // time used statistics - auto start = std::chrono::steady_clock::now(); - Status status = stub_->PushCarStatus(&context, *msg, &response); - auto end = std::chrono::steady_clock::now(); - std::chrono::duration time_used = end - start; - - // response check: error_code 4: time out; 0: success; - AINFO << "stub PushCarStatus Time used: " << time_used.count() * 1000 - << " ms"; -} - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_client.h b/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_client.h deleted file mode 100644 index e925f1a1330..00000000000 --- a/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_client.h +++ /dev/null @@ -1,63 +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. - *****************************************************************************/ - -/** - * @file grpc_client.h - * @brief define v2x proxy module and onboard unit interface grpc implement - */ - -#pragma once - -#include -#include - -#include - -#include "modules/v2x/proto/v2x_car_status.pb.h" -#include "modules/v2x/proto/v2x_obu_traffic_light.pb.h" -#include "modules/v2x/proto/v2x_service_car_to_obu.grpc.pb.h" - -#include "cyber/cyber.h" -#include "modules/v2x/common/v2x_proxy_gflags.h" - -namespace apollo { -namespace v2x { - -class GrpcClientImpl { - public: - /* construct function - @param input car_status type msg shared ptr - */ - explicit GrpcClientImpl(std::shared_ptr channel); - - ~GrpcClientImpl() {} - - bool InitFlag() { return init_flag_; } - - /*function that send car status msg through grpc - @param input car_status type msg shared ptr - */ - void SendMsgToGrpc(const std::shared_ptr<::apollo::v2x::CarStatus> &msg); - - private: - // grpc service stub - std::unique_ptr<::apollo::v2x::CarToObu::Stub> stub_; - int car_status_tv_nsec_ = 0; - bool init_flag_ = false; -}; - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_server.cc b/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_server.cc deleted file mode 100644 index 2ca708889d0..00000000000 --- a/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_server.cc +++ /dev/null @@ -1,190 +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. - *****************************************************************************/ - -/** - * @file grpc_server.cc - * @brief define v2x proxy module and onboard unit interface grpc implement - */ - -#include "modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_server.h" - -#include - -#include "modules/v2x/common/v2x_proxy_gflags.h" - -namespace apollo { -namespace v2x { - -using ::apollo::v2x::StatusResponse; -using ::apollo::v2x::obu::ObuRsi; -using ::apollo::v2x::obu::ObuTrafficLight; -using grpc::Status; - -GrpcServerImpl::GrpcServerImpl() - : node_(::apollo::cyber::CreateNode("v2x_grpc_server")) { - CHECK(!!node_); - // _monitor = cybertron::MetricController::Instance(); - AINFO << "GrpcServerImpl initial success"; - init_flag_ = true; -} - -grpc::Status GrpcServerImpl::SendV2xRSI(grpc::ServerContext * /* context */, - const ObuRsi *request, - StatusResponse *response) { - ADEBUG << "Received SendV2xRSI request from client!"; - ADEBUG << request->DebugString(); - - if (!request->has_header()) { - response->set_status(false); - response->set_info("error no header in RSI request"); - AERROR << "SendV2xRSI request has no header"; - return Status::CANCELLED; - } - { - std::lock_guard guard(rsi_mutex_); - latest_rsi_.CopyFrom(*request); - auto obu_header = latest_rsi_.mutable_header(); - if (obu_header->has_timestamp_sec()) { - AINFO << "Obu Timestamp: " << std::setiosflags(std::ios::fixed) - << std::setprecision(11) << obu_header->timestamp_sec(); - AINFO << "SVB Timestamp: " << std::setiosflags(std::ios::fixed) - << std::setprecision(11) << ::apollo::cyber::Time::Now().ToSecond(); - obu_header->set_timestamp_sec(::apollo::cyber::Time::Now().ToSecond()); - } - rsi_refresh_ = true; - } - rsi_condition_.notify_one(); - - response->set_status(true); - AINFO << "SendV2xRSI response success."; - return Status::OK; -} -grpc::Status GrpcServerImpl::SendPerceptionObstacles( - grpc::ServerContext *, const apollo::v2x::V2XObstacles *request, - StatusResponse *response) { - ADEBUG << "Received SendPerceptionObstacles request from client!"; - { - std::lock_guard guard(obstacles_mutex_); - latest_obstacles_.CopyFrom(*request); - response->set_status(true); - obs_refresh_ = true; - ADEBUG << "SendPerceptionObstacles response success."; - } - obs_condition_.notify_one(); - return Status::OK; -} - -grpc::Status GrpcServerImpl::SendV2xTrafficLight( - grpc::ServerContext * /* context */, const ObuTrafficLight *request, - StatusResponse *response) { - ADEBUG << "Received SendV2xTrafficLight request from client!"; - ADEBUG << request->DebugString(); - - int num_current_light = request->road_traffic_light_size(); - - if (0 == num_current_light) { - response->set_status(false); - response->set_info("error v2x current lane traffic light size == 0"); - AERROR << "SendV2xTrafficLight request no current lane traffic light."; - return Status::CANCELLED; - } - if (!request->has_header()) { - response->set_status(false); - response->set_info( - "error no header in IntersectionTrafficLightData request"); - AERROR << "SendV2xTrafficLight request has no header"; - return Status::CANCELLED; - } - { - std::lock_guard guard(traffic_light_mutex_); - latest_traffic_light_.CopyFrom(*request); - auto obu_header = latest_traffic_light_.mutable_header(); - if (obu_header->has_timestamp_sec()) { - obu_header->set_timestamp_sec(::apollo::cyber::Time::Now().ToSecond()); - } - refresh_ = true; - } - traffic_light_condition_.notify_one(); - auto cur_junction_id = request->intersection_id(); - ADEBUG << "recieved the junction id " << cur_junction_id; - response->set_status(true); - return Status::OK; -} - -grpc::Status GrpcServerImpl::SendObuAlarm( - grpc::ServerContext *context, const ::apollo::v2x::ObuAlarm *request, - StatusResponse *response) { - ADEBUG << "Received SendOBUAlarm request from client!"; - if (request->error_num() != ::apollo::v2x::ErrorCode::OBUID) { - } else { - AERROR << "OBU id:" << request->error_msg(); - } - response->set_status(true); - return Status::OK; -} - -void GrpcServerImpl::GetMsgFromGrpc(std::shared_ptr *ptr) { - if (nullptr == ptr) { - return; - } - std::unique_lock guard(rsi_mutex_); - rsi_condition_.wait(guard, [this] { return rsi_refresh_; }); - rsi_refresh_ = false; - *ptr = std::make_shared(); - if (nullptr == *ptr) { - return; - } - (*ptr)->CopyFrom(latest_rsi_); -} - -void GrpcServerImpl::GetMsgFromGrpc( - std::shared_ptr<::apollo::v2x::V2XObstacles> *ptr) { - if (nullptr == ptr) { - return; - } - std::unique_lock guard(obstacles_mutex_); - obs_condition_.wait(guard, [this] { return obs_refresh_; }); - obs_refresh_ = false; - *ptr = std::make_shared<::apollo::v2x::V2XObstacles>(); - if (nullptr == *ptr) { - return; - } - (*ptr)->CopyFrom(latest_obstacles_); -} - -void GrpcServerImpl::GetMsgFromGrpc(std::shared_ptr *ptr) { - if (nullptr == ptr) { - return; - } - std::unique_lock guard(traffic_light_mutex_); - if (!traffic_light_condition_.wait_for( - guard, std::chrono::milliseconds(FLAGS_msg_timeout), - [this] { return refresh_; })) { - AERROR << "GetMsgFromGrpc IntersectionTrafficLightData is timeout"; - *ptr = nullptr; - return; - } - *ptr = std::make_shared(); - if (nullptr == *ptr) { - return; - } - (*ptr)->CopyFrom(latest_traffic_light_); - latest_traffic_light_.Clear(); - refresh_ = false; -} - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_server.h b/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_server.h deleted file mode 100644 index 4b4fac10465..00000000000 --- a/modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_server.h +++ /dev/null @@ -1,108 +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. - *****************************************************************************/ -/** - * @file grpc_server.h - * @brief define v2x proxy module and onboard unit interface grpc implement - */ - -#pragma once - -#include -#include -#include -#include - -#include - -#include "modules/common_msgs/perception_msgs/perception_obstacle.pb.h" -#include "modules/common_msgs/perception_msgs/traffic_light_detection.pb.h" -#include "modules/v2x/proto/v2x_obu_rsi.pb.h" -#include "modules/v2x/proto/v2x_service_obu_to_car.grpc.pb.h" -#include "modules/common_msgs/v2x_msgs/v2x_traffic_light.pb.h" - -#include "cyber/cyber.h" - -namespace apollo { -namespace v2x { - -class GrpcServerImpl final : public ::apollo::v2x::ObuToCar::Service { - public: - /* construct function - */ - GrpcServerImpl(); - - ~GrpcServerImpl() { - traffic_light_condition_.notify_all(); - rsi_condition_.notify_all(); - } - - bool InitFlag() { return init_flag_; } - - /* function that send v2x traffic_light through grpc - @param input v2x traffic_light grpc request - @param output grpc response - */ - grpc::Status SendV2xTrafficLight( - grpc::ServerContext *context, - const ::apollo::v2x::obu::ObuTrafficLight *request, - ::apollo::v2x::StatusResponse *response) override; - - /* function that send v2x monitor messages through grpc - @param input v2x monitor grpc request - @param output grpc response - */ - grpc::Status SendObuAlarm(grpc::ServerContext *context, - const ::apollo::v2x::ObuAlarm *request, - ::apollo::v2x::StatusResponse *response) override; - - /* function that send perception obstacles through grpc - @param input perception obstacles grpc request - @param output grpc response - */ - grpc::Status SendPerceptionObstacles(grpc::ServerContext *context, - const apollo::v2x::V2XObstacles *request, - StatusResponse *response) override; - - grpc::Status SendV2xRSI(grpc::ServerContext *context, - const ::apollo::v2x::obu::ObuRsi *request, - ::apollo::v2x::StatusResponse *response); - - void GetMsgFromGrpc( - std::shared_ptr<::apollo::v2x::obu::ObuTrafficLight> *ptr); - - void GetMsgFromGrpc(std::shared_ptr<::apollo::v2x::obu::ObuRsi> *ptr); - void GetMsgFromGrpc(std::shared_ptr<::apollo::v2x::V2XObstacles> *ptr); - - private: - std::mutex traffic_light_mutex_; - std::mutex rsi_mutex_; - std::mutex obstacles_mutex_; - std::condition_variable traffic_light_condition_; - std::condition_variable rsi_condition_; - std::condition_variable obs_condition_; - ::apollo::v2x::obu::ObuTrafficLight latest_traffic_light_; - ::apollo::v2x::obu::ObuRsi latest_rsi_; - ::apollo::v2x::V2XObstacles latest_obstacles_; - - bool init_flag_ = false; - bool refresh_ = false; - bool rsi_refresh_ = false; - bool obs_refresh_ = false; - std::unique_ptr<::apollo::cyber::Node> node_ = nullptr; -}; - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/obu_interface/obu_interface_abstract_class.h b/modules/v2x/v2x_proxy/obu_interface/obu_interface_abstract_class.h deleted file mode 100644 index 7df16a3ebe9..00000000000 --- a/modules/v2x/v2x_proxy/obu_interface/obu_interface_abstract_class.h +++ /dev/null @@ -1,62 +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. - *****************************************************************************/ - -/** - * @file obu_interface_abstract_class.h - * @brief define v2x proxy module and onboard unit interface base class - */ - -#pragma once - -#include -#include - -#include "modules/common_msgs/perception_msgs/traffic_light_detection.pb.h" -#include "modules/v2x/proto/v2x_car_status.pb.h" -#include "modules/v2x/proto/v2x_obstacles.pb.h" -#include "modules/v2x/proto/v2x_obu_rsi.pb.h" -#include "modules/common_msgs/v2x_msgs/v2x_traffic_light.pb.h" - -#include "cyber/cyber.h" - -namespace apollo { -namespace v2x { - -class ObuInterFaceBase { - public: - ObuInterFaceBase() {} - - virtual ~ObuInterFaceBase() {} - - public: - virtual bool InitialServer() = 0; - - virtual bool InitialClient() = 0; - - virtual void GetV2xTrafficLightFromObu( - std::shared_ptr<::apollo::v2x::obu::ObuTrafficLight> *msg) {} - - virtual void SendCarStatusToObu( - const std::shared_ptr<::apollo::v2x::CarStatus> &msg) {} - - virtual void GetV2xRsiFromObu( - std::shared_ptr<::apollo::v2x::obu::ObuRsi> *msg) {} - virtual void GetV2xObstaclesFromObu( - std::shared_ptr<::apollo::v2x::V2XObstacles> *msg) {} -}; - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/obu_interface/obu_interface_grpc_impl.cc b/modules/v2x/v2x_proxy/obu_interface/obu_interface_grpc_impl.cc deleted file mode 100644 index f26641481ec..00000000000 --- a/modules/v2x/v2x_proxy/obu_interface/obu_interface_grpc_impl.cc +++ /dev/null @@ -1,113 +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. - *****************************************************************************/ -/** - * @file obu_interface_grpc_impl.cc - * @brief define v2x proxy module and onboard unit interface grpc impl class - */ -#include "modules/v2x/v2x_proxy/obu_interface/obu_interface_grpc_impl.h" - -#include -#include -#include - -#include "modules/v2x/common/v2x_proxy_gflags.h" - -namespace apollo { -namespace v2x { - -using ::apollo::v2x::CarStatus; -using ::apollo::v2x::obu::ObuRsi; -using ::apollo::v2x::obu::ObuTrafficLight; -using grpc::Server; -using grpc::ServerBuilder; -using grpc::ServerContext; - -ObuInterFaceGrpcImpl::ObuInterFaceGrpcImpl() - : grpc_client_(new GrpcClientImpl(grpc::CreateChannel( - FLAGS_grpc_client_host + ":" + FLAGS_grpc_client_port, - grpc::InsecureChannelCredentials()))) { - AINFO << "ObuInterFaceGrpcImpl Start Construct."; - cli_init_ = grpc_client_->InitFlag(); - grpc_server_.reset(new GrpcServerImpl()); - srv_init_ = grpc_server_->InitFlag(); - CHECK(InitialClient()); - CHECK(InitialServer()); - init_succ_ = true; -} - -ObuInterFaceGrpcImpl::~ObuInterFaceGrpcImpl() { - { - std::unique_lock lck(mutex_); - exit_flag_ = true; - } - condition_.notify_all(); - if (!!thread_grpc_ && thread_grpc_->joinable()) { - thread_grpc_->join(); - } - AINFO << "close obu interface success"; -} - -bool ObuInterFaceGrpcImpl::InitialClient() { return cli_init_; } - -bool ObuInterFaceGrpcImpl::InitialServer() { - if (!srv_init_) { - return false; - } - thread_grpc_.reset(new std::thread([this]() { this->ThreadRunServer(); })); - return thread_grpc_ != nullptr; -} - -void ObuInterFaceGrpcImpl::ThreadRunServer() { - std::unique_lock lck(mutex_); - auto start = std::chrono::steady_clock::now(); - std::string server_address(FLAGS_grpc_server_host + ":" + - FLAGS_grpc_server_port); - ServerBuilder builder; - // Listen on the given address without any authentication mechanism. - builder.AddListeningPort(server_address, grpc::InsecureServerCredentials()); - // Register "service" as the instance through which we'll communicate with - // clients. In this case it corresponds to an *synchronous* service. - builder.RegisterService(grpc_server_.get()); - // Finally assemble the server. - auto tmp = builder.BuildAndStart(); - server_ = std::move(tmp); - auto end = std::chrono::steady_clock::now(); - std::chrono::duration time_used = end - start; - AINFO << "ObuInterFaceGrpcImpl grpc server has listening on : " - << server_address << " time used : " << time_used.count(); - condition_.wait(lck, [&]() { return exit_flag_; }); -} - -void ObuInterFaceGrpcImpl::GetV2xTrafficLightFromObu( - std::shared_ptr *msg) { - grpc_server_->GetMsgFromGrpc(msg); -} - -void ObuInterFaceGrpcImpl::GetV2xObstaclesFromObu( - std::shared_ptr<::apollo::v2x::V2XObstacles> *msg) { - grpc_server_->GetMsgFromGrpc(msg); -} - -void ObuInterFaceGrpcImpl::GetV2xRsiFromObu(std::shared_ptr *msg) { - grpc_server_->GetMsgFromGrpc(msg); -} - -void ObuInterFaceGrpcImpl::SendCarStatusToObu( - const std::shared_ptr &msg) { - grpc_client_->SendMsgToGrpc(msg); -} -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/obu_interface/obu_interface_grpc_impl.h b/modules/v2x/v2x_proxy/obu_interface/obu_interface_grpc_impl.h deleted file mode 100644 index 54555e0cf6e..00000000000 --- a/modules/v2x/v2x_proxy/obu_interface/obu_interface_grpc_impl.h +++ /dev/null @@ -1,93 +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. - *****************************************************************************/ - -/** - * @file obu_interface_grpc_impl.h - * @brief define v2x proxy module and onboard unit interface grpc impl class - */ - -#pragma once - -#include -#include -#include -#include - -#include - -#include "modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_client.h" -#include "modules/v2x/v2x_proxy/obu_interface/grpc_interface/grpc_server.h" -#include "modules/v2x/v2x_proxy/obu_interface/obu_interface_abstract_class.h" - -namespace apollo { -namespace v2x { - -class ObuInterFaceGrpcImpl : public ObuInterFaceBase { - public: - ObuInterFaceGrpcImpl(); - ~ObuInterFaceGrpcImpl(); - - /* function that init grpc server - */ - bool InitialServer() override; - - /* function that init grpc client - */ - bool InitialClient() override; - - /* function that get v2x traffic light through grpc - @param output return latest v2x traffic light - */ - void GetV2xTrafficLightFromObu( - std::shared_ptr<::apollo::v2x::obu::ObuTrafficLight> *msg) override; - - void GetV2xObstaclesFromObu( - std::shared_ptr<::apollo::v2x::V2XObstacles> *msg) override; - - void GetV2xRsiFromObu( - std::shared_ptr<::apollo::v2x::obu::ObuRsi> *msg) override; - - /* function that send car status through grpc - @param input send car status msg to grpc - */ - void SendCarStatusToObu( - const std::shared_ptr<::apollo::v2x::CarStatus> &msg) override; - - /* function that return init flag - */ - bool InitFlag() { return init_succ_; } - - private: - /* thread function that run server - */ - void ThreadRunServer(); - - std::shared_ptr grpc_client_; - std::unique_ptr grpc_server_; - std::unique_ptr server_; - - bool cli_init_ = false; - bool srv_init_ = false; - - bool init_succ_ = false; - bool exit_flag_ = false; - std::unique_ptr thread_grpc_; - std::mutex mutex_; - std::condition_variable condition_; -}; - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/obu_interface/obu_interface_grpc_impl_test.cc b/modules/v2x/v2x_proxy/obu_interface/obu_interface_grpc_impl_test.cc deleted file mode 100644 index 1c5f83fd1fb..00000000000 --- a/modules/v2x/v2x_proxy/obu_interface/obu_interface_grpc_impl_test.cc +++ /dev/null @@ -1,35 +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. - *****************************************************************************/ - -/** - * @file obu_interface_grpc_impl_test.cc - * @brief test v2x proxy module and onboard unit interface grpc impl class - */ - -#include "modules/v2x/v2x_proxy/obu_interface/obu_interface_grpc_impl.h" - -#include "gtest/gtest.h" - -namespace apollo { -namespace v2x { - -TEST(ObuInterFaceGrpcImplTest, Construct) { - apollo::cyber::Init("obu_interface_grpc_impl_test"); - ObuInterFaceGrpcImpl obuinteface; - EXPECT_TRUE(obuinteface.InitFlag()); -} -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/os_interface/BUILD b/modules/v2x/v2x_proxy/os_interface/BUILD deleted file mode 100644 index d5ab1bc163e..00000000000 --- a/modules/v2x/v2x_proxy/os_interface/BUILD +++ /dev/null @@ -1,36 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -cc_library( - name = "os_interface", - srcs = ["os_interface.cc"], - hdrs = ["os_interface.h"], - deps = [ - "//cyber", - "//modules/common/adapters:adapter_gflags", - "//modules/common_msgs/localization_msgs:localization_cc_proto", - "//modules/common_msgs/perception_msgs:perception_obstacle_cc_proto", - "//modules/common_msgs/planning_msgs:planning_cc_proto", - "//modules/v2x/common:v2x_proxy_gflags", - "//modules/v2x/proto:v2x_obstacles_cc_proto", - "//modules/v2x/proto:v2x_obu_rsi_cc_proto", - "//modules/v2x/proto:v2x_obu_traffic_light_cc_proto", - "//modules/common_msgs/v2x_msgs:v2x_traffic_light_cc_proto", - ], -) - -cc_test( - name = "os_interface_test", - size = "small", - timeout = "short", - srcs = ["os_interface_test.cc"], - deps = [ - ":os_interface", - "@com_google_googletest//:gtest_main", - ], - linkstatic = True, -) - -cpplint() diff --git a/modules/v2x/v2x_proxy/os_interface/os_interface.cc b/modules/v2x/v2x_proxy/os_interface/os_interface.cc deleted file mode 100644 index dc270198415..00000000000 --- a/modules/v2x/v2x_proxy/os_interface/os_interface.cc +++ /dev/null @@ -1,140 +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. - *****************************************************************************/ - -/** - * @file os_interface.cc - * @brief define v2x proxy module and apollo os interface - */ - -#include "modules/v2x/v2x_proxy/os_interface/os_interface.h" - -#include "modules/common/adapters/adapter_gflags.h" - -namespace apollo { -namespace v2x { - -using ::apollo::localization::LocalizationEstimate; -using ::apollo::perception::PerceptionObstacles; -using ::apollo::planning::ADCTrajectory; -using ::apollo::v2x::IntersectionTrafficLightData; - -OsInterFace::OsInterFace() - : node_(::apollo::cyber::CreateNode("v2x_os_interface")), - init_flag_(false) { - init_flag_ = !!node_ && InitReaders() && InitWriters(); -} - -OsInterFace::~OsInterFace() {} - -bool OsInterFace::InitReaders() { - localization_reader_ = node_->CreateReader( - FLAGS_localization_topic, - [this](const std::shared_ptr &msg) { - std::lock_guard lg(mutex_localization_); - current_localization_.Clear(); - current_localization_.CopyFrom(*msg); - }); - planning_reader_ = node_->CreateReader( - FLAGS_planning_trajectory_topic, - [this](const std::shared_ptr &msg) { - { - std::lock_guard lg(mutex_planning_); - adc_trajectory_msg_.Clear(); - adc_trajectory_msg_.CopyFrom(*msg); - flag_planning_new_ = true; - } - cond_planning_.notify_one(); - }); - return nullptr != localization_reader_ && nullptr != planning_reader_; -} - -bool OsInterFace::InitWriters() { - v2x_obu_traffic_light_writer_ = - node_->CreateWriter<::apollo::v2x::obu::ObuTrafficLight>( - FLAGS_v2x_obu_traffic_light_topic); - v2x_traffic_light_writer_ = - node_->CreateWriter<::apollo::v2x::IntersectionTrafficLightData>( - FLAGS_v2x_traffic_light_topic); - v2x_traffic_light_hmi_writer_ = - node_->CreateWriter<::apollo::perception::TrafficLightDetection>( - FLAGS_v2x_traffic_light_for_hmi_topic); - v2x_obstacles_internal_writer_ = - node_->CreateWriter( - FLAGS_v2x_internal_obstacle_topic); - return nullptr != v2x_obu_traffic_light_writer_ && - nullptr != v2x_traffic_light_hmi_writer_ && - nullptr != v2x_obstacles_internal_writer_ && - nullptr != v2x_traffic_light_writer_; -} - -void OsInterFace::GetLocalizationFromOs( - const std::shared_ptr &msg) { - AINFO << "get localization result from os"; - std::lock_guard lg(mutex_localization_); - msg->CopyFrom(current_localization_); -} - -void OsInterFace::GetPlanningAdcFromOs( - const std::shared_ptr<::apollo::planning::ADCTrajectory> &msg) { - AINFO << "get planning adc from os"; - std::unique_lock lg(mutex_planning_); - cond_planning_.wait(lg, [this]() { return flag_planning_new_; }); - flag_planning_new_ = false; - msg->CopyFrom(adc_trajectory_msg_); -} - -void OsInterFace::SendV2xObuTrafficLightToOs( - const std::shared_ptr<::apollo::v2x::obu::ObuTrafficLight> &msg) { - if (nullptr == msg) { - return; - } - AINFO << "send v2x obu traffic_light to os"; - SendMsgToOs(v2x_obu_traffic_light_writer_.get(), msg); - AINFO << "v2x obu traffic_light result: " << msg->DebugString(); -} - -void OsInterFace::SendV2xObstacles2Sys( - const std::shared_ptr &msg) { - if (nullptr == msg) { - return; - } - AINFO << "send v2x obu traffic_light to os"; - SendMsgToOs(v2x_obstacles_internal_writer_.get(), msg); - AINFO << "v2x obu traffic_light result: " << msg->DebugString(); -} - -void OsInterFace::SendV2xTrafficLightToOs( - const std::shared_ptr &msg) { - if (nullptr == msg) { - return; - } - AINFO << "send v2x traffic_light to os"; - SendMsgToOs(v2x_traffic_light_writer_.get(), msg); - AINFO << "v2x traffic_light result: " << msg->DebugString(); -} - -void OsInterFace::SendV2xTrafficLight4Hmi2Sys( - const std::shared_ptr<::apollo::perception::TrafficLightDetection> &msg) { - if (nullptr == msg) { - return; - } - AINFO << "send v2x tl4hmi to os"; - SendMsgToOs(v2x_traffic_light_hmi_writer_.get(), msg); - AINFO << "v2x tl4hmi result: " << msg->DebugString(); -} - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/os_interface/os_interface.h b/modules/v2x/v2x_proxy/os_interface/os_interface.h deleted file mode 100644 index cf577289c32..00000000000 --- a/modules/v2x/v2x_proxy/os_interface/os_interface.h +++ /dev/null @@ -1,111 +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. - *****************************************************************************/ - -/** - * @file os_interface.h - * @brief define v2x proxy module and apollo os interface - */ - -#pragma once - -#include -#include -#include -#include -#include -#include - -#include "modules/common_msgs/localization_msgs/localization.pb.h" -#include "modules/common_msgs/perception_msgs/perception_obstacle.pb.h" -#include "modules/common_msgs/planning_msgs/planning.pb.h" -#include "modules/v2x/proto/v2x_obstacles.pb.h" -#include "modules/v2x/proto/v2x_obu_rsi.pb.h" -#include "modules/v2x/proto/v2x_obu_traffic_light.pb.h" -#include "modules/common_msgs/v2x_msgs/v2x_traffic_light.pb.h" - -#include "cyber/cyber.h" -#include "modules/v2x/common/v2x_proxy_gflags.h" - -namespace apollo { -namespace v2x { -class OsInterFace { - public: - OsInterFace(); - - ~OsInterFace(); - - bool InitFlag() { return init_flag_; } - - void GetLocalizationFromOs( - const std::shared_ptr<::apollo::localization::LocalizationEstimate> &msg); - - void GetPlanningAdcFromOs( - const std::shared_ptr<::apollo::planning::ADCTrajectory> &msg); - - void SendV2xObuTrafficLightToOs( - const std::shared_ptr<::apollo::v2x::obu::ObuTrafficLight> &msg); - - void SendV2xTrafficLightToOs( - const std::shared_ptr<::apollo::v2x::IntersectionTrafficLightData> &msg); - - void SendV2xObstacles2Sys( - const std::shared_ptr &msg); - - void SendV2xTrafficLight4Hmi2Sys( - const std::shared_ptr<::apollo::perception::TrafficLightDetection> &msg); - - private: - template - void SendMsgToOs(::apollo::cyber::Writer *writer, - const std::shared_ptr &msg) { - if (nullptr == writer) { - return; - } - writer->Write(msg); - } - - bool InitReaders(); - - bool InitWriters(); - - std::unique_ptr<::apollo::cyber::Node> node_ = nullptr; - std::shared_ptr< - ::apollo::cyber::Reader<::apollo::localization::LocalizationEstimate>> - localization_reader_ = nullptr; - std::shared_ptr<::apollo::cyber::Reader<::apollo::planning::ADCTrajectory>> - planning_reader_ = nullptr; - std::shared_ptr<::apollo::cyber::Writer<::apollo::v2x::obu::ObuTrafficLight>> - v2x_obu_traffic_light_writer_ = nullptr; - std::shared_ptr< - ::apollo::cyber::Writer<::apollo::v2x::IntersectionTrafficLightData>> - v2x_traffic_light_writer_ = nullptr; - std::shared_ptr< - ::apollo::cyber::Writer<::apollo::perception::TrafficLightDetection>> - v2x_traffic_light_hmi_writer_ = nullptr; - std::shared_ptr<::apollo::cyber::Writer<::apollo::v2x::V2XObstacles>> - v2x_obstacles_internal_writer_ = nullptr; - ::apollo::localization::LocalizationEstimate current_localization_; - ::apollo::planning::ADCTrajectory adc_trajectory_msg_; - bool flag_planning_new_ = false; - - mutable std::mutex mutex_localization_; - mutable std::mutex mutex_planning_; - mutable std::condition_variable cond_planning_; - - bool init_flag_ = false; -}; -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/os_interface/os_interface_test.cc b/modules/v2x/v2x_proxy/os_interface/os_interface_test.cc deleted file mode 100644 index 55c113b19c0..00000000000 --- a/modules/v2x/v2x_proxy/os_interface/os_interface_test.cc +++ /dev/null @@ -1,35 +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. - *****************************************************************************/ - -/** - * @file os_interface_test.cc - * @brief test v2x proxy module and apollo os interface - */ - -#include "modules/v2x/v2x_proxy/os_interface/os_interface.h" - -#include "gtest/gtest.h" - -namespace apollo { -namespace v2x { - -TEST(OsInterFaceTest, Construct) { - apollo::cyber::Init("os_inteface_test"); - OsInterFace os_interface; - EXPECT_TRUE(os_interface.InitFlag()); -} -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/proto_adapter/BUILD b/modules/v2x/v2x_proxy/proto_adapter/BUILD deleted file mode 100644 index 2be9c61ac5e..00000000000 --- a/modules/v2x/v2x_proxy/proto_adapter/BUILD +++ /dev/null @@ -1,35 +0,0 @@ -load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test") -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -cc_library( - name = "proto_adapter", - srcs = ["proto_adapter.cc"], - hdrs = ["proto_adapter.h"], - deps = [ - "//cyber", - "//modules/map/hdmap", - "//modules/v2x/common:v2x_proxy_gflags", - "//modules/v2x/proto:v2x_car_status_cc_proto", - "//modules/v2x/proto:v2x_junction_cc_proto", - "//modules/v2x/proto:v2x_obu_rsi_cc_proto", - "//modules/v2x/proto:v2x_obu_traffic_light_cc_proto", - "//modules/v2x/proto:v2x_rsi_cc_proto", - "//modules/common_msgs/v2x_msgs:v2x_traffic_light_cc_proto", - "@eigen", - ], -) - -cc_test( - name = "proto_adapter_test", - size = "small", - timeout = "short", - srcs = ["proto_adapter_test.cc"], - deps = [ - ":proto_adapter", - "@com_google_googletest//:gtest_main", - ], -) - -cpplint() diff --git a/modules/v2x/v2x_proxy/proto_adapter/proto_adapter.cc b/modules/v2x/v2x_proxy/proto_adapter/proto_adapter.cc deleted file mode 100644 index 73ec55c0097..00000000000 --- a/modules/v2x/v2x_proxy/proto_adapter/proto_adapter.cc +++ /dev/null @@ -1,230 +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/v2x/v2x_proxy/proto_adapter/proto_adapter.h" - -#include -#include - -#include "cyber/cyber.h" - -namespace apollo { -namespace v2x { - -OSLightype ProtoAdapter::LightTypeObu2Sys(int32_t type) { - switch (type) { - case 2: - return OSLightype::SingleTrafficLight_Type_LEFT; - case 3: - return OSLightype::SingleTrafficLight_Type_RIGHT; - case 4: - return OSLightype::SingleTrafficLight_Type_U_TURN; - case 1: - default: - return OSLightype::SingleTrafficLight_Type_STRAIGHT; - } -} - -bool ProtoAdapter::LightObu2Sys(const ObuLight &obu_light, - std::shared_ptr *os_light) { - if (nullptr == os_light) { - return false; - } - auto res = std::make_shared(); - if (nullptr == res) { - return false; - } - if (!obu_light.has_header()) { - return false; - } - if (obu_light.header().has_timestamp_sec()) { - res->mutable_header()->set_timestamp_sec( - obu_light.header().timestamp_sec()); - } - if (obu_light.header().has_module_name()) { - res->mutable_header()->set_module_name(obu_light.header().module_name()); - } - if (0 == obu_light.road_traffic_light_size()) { - return false; - } - bool flag_has_data = false; - for (int idx_road = 0; idx_road < obu_light.road_traffic_light_size(); - idx_road++) { - const auto &obu_road_light1 = obu_light.road_traffic_light(idx_road); - // Set the road index for lane - apollo::common::Direction tl_attr = apollo::common::Direction::EAST; - switch (obu_road_light1.road_direction()) { - case 1: - tl_attr = apollo::common::Direction::EAST; - break; - case 2: - tl_attr = apollo::common::Direction::WEST; - break; - case 3: - tl_attr = apollo::common::Direction::SOUTH; - break; - case 4: - tl_attr = apollo::common::Direction::NORTH; - break; - default: - AINFO << "Road direction=" << obu_road_light1.road_direction() - << " is invalid."; - } - // FOR-EACH LANE - for (int idx_lane = 0; idx_lane < obu_road_light1.lane_traffic_light_size(); - idx_lane++) { - const auto &obu_lane_light1 = - obu_road_light1.lane_traffic_light(idx_lane); - if (!obu_lane_light1.has_gps_x_m() || !obu_lane_light1.has_gps_y_m()) { - AWARN << "Invalid lane_traffic_light: [" << idx_road << "][" << idx_lane - << "]: no gps info here."; - continue; - } - flag_has_data = true; - auto *res_light1 = res->add_road_traffic_light(); - res_light1->set_gps_x_m(obu_lane_light1.gps_x_m()); - res_light1->set_gps_y_m(obu_lane_light1.gps_y_m()); - res_light1->set_road_attribute(tl_attr); - // single traffic light - for (int j = 0; j < obu_lane_light1.single_traffic_light_size(); j++) { - auto *res_single1 = res_light1->add_single_traffic_light(); - const auto &obu_single1 = obu_lane_light1.single_traffic_light(j); - if (obu_single1.has_id()) { - res_single1->set_id(obu_single1.id()); - } - if (obu_single1.has_color_remaining_time_s()) { - res_single1->set_color_remaining_time_s( - obu_single1.color_remaining_time_s()); - } - if (obu_single1.has_next_remaining_time()) { - res_single1->set_next_remaining_time_s( - obu_single1.next_remaining_time()); - } - if (obu_single1.has_right_turn_light()) { - res_single1->set_right_turn_light(obu_single1.right_turn_light()); - } - if (obu_single1.has_color()) { - res_single1->set_color(obu_single1.color()); - } - if (obu_single1.has_next_color()) { - res_single1->set_next_color(obu_single1.next_color()); - } - if (obu_single1.has_traffic_light_type()) { - res_single1->add_traffic_light_type( - LightTypeObu2Sys(obu_single1.traffic_light_type())); - } - } - } - } - *os_light = res; - return flag_has_data; -} - -bool ProtoAdapter::RsiObu2Sys(const ObuRsi *obu_rsi, - std::shared_ptr *os_rsi) { - if (nullptr == obu_rsi) { - return false; - } - if (nullptr == os_rsi) { - return false; - } - auto res = std::make_shared(); - if (nullptr == res) { - return false; - } - if (!obu_rsi->has_alter_type()) { - return false; - } - res->set_radius(obu_rsi->radius()); - res->set_rsi_type(obu_rsi->alter_type()); - if (obu_rsi->has_header()) { - auto header = res->mutable_header(); - header->set_sequence_num(obu_rsi->header().sequence_num()); - header->set_timestamp_sec(obu_rsi->header().timestamp_sec()); - header->set_module_name("v2x"); - } - switch (obu_rsi->alter_type()) { - case RsiAlterType::SPEED_LIMIT: - case RsiAlterType::SPEED_LIMIT_BRIDGE: - case RsiAlterType::SPEED_LIMIT_TUNNEL: - for (int index = 0; index < obu_rsi->points_size(); index++) { - auto point = res->add_points(); - point->set_x(obu_rsi->points(index).x()); - point->set_y(obu_rsi->points(index).y()); - res->set_speed(std::atof(obu_rsi->description().c_str())); - } - break; - case RsiAlterType::CONSTRUCTION_AHEAD: // Construction Ahead - case RsiAlterType::BUS_LANE: // Bus Lane - case RsiAlterType::TIDAL_LANE: // tidal Lane - case RsiAlterType::TRAFFIC_JAM: // traffic jam - case RsiAlterType::TRAFFIC_ACCIDENT: // traffic accident - for (int index = 0; index < obu_rsi->points_size(); index++) { - auto point = res->add_points(); - point->set_x(obu_rsi->points(index).x()); - point->set_y(obu_rsi->points(index).y()); - } - break; - case RsiAlterType::NO_HONKING: // No Honking - case RsiAlterType::SLOW_DOWN_SECTION: // slow down section - case RsiAlterType::ACCIDENT_PRONE: // Accident Prone - case RsiAlterType::OVERSPEED_VEHICLE: // overspeed vehicle - case RsiAlterType::EMERGENCY_BRAKING: // emergency braking - case RsiAlterType::ANTIDROMIC_VEHICLE: // antidromic vehicle - case RsiAlterType::ZOMBIES_VEHICLE: { // zombies vehicle - auto point = res->add_points(); - point->set_x(obu_rsi->points(0).x()); - point->set_y(obu_rsi->points(0).y()); - break; - } - case RsiAlterType::CONTROLLOSS_VEHICLE: // controlloss vehicle - case RsiAlterType::SPECIAL_VEHICLE: { // special vehicle - auto point = res->add_points(); - point->set_x(obu_rsi->points(0).x()); - point->set_y(obu_rsi->points(0).y()); - res->set_speed(std::atof(obu_rsi->description().c_str())); - break; - } - default: - AINFO << "RSI type:" << obu_rsi->alter_type(); - break; - } - *os_rsi = res; - return true; -} - -bool ProtoAdapter::JunctionHd2obu(const HDJunction &hd_junction, - std::shared_ptr *obu_junction) { - if (nullptr == obu_junction) { - return false; - } - auto res = std::make_shared(); - if (nullptr == res) { - return false; - } - res->mutable_id()->set_id(hd_junction->id().id()); - for (const auto &point : hd_junction->polygon().points()) { - auto res_point = res->mutable_polygon()->add_point(); - res_point->set_x(point.x()); - res_point->set_y(point.y()); - res_point->set_z(0); - } - *obu_junction = res; - return true; -} - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/proto_adapter/proto_adapter.h b/modules/v2x/v2x_proxy/proto_adapter/proto_adapter.h deleted file mode 100644 index 05e0a6e3d60..00000000000 --- a/modules/v2x/v2x_proxy/proto_adapter/proto_adapter.h +++ /dev/null @@ -1,74 +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/v2x/proto/v2x_car_status.pb.h" -#include "modules/v2x/proto/v2x_junction.pb.h" -#include "modules/v2x/proto/v2x_obu_rsi.pb.h" -#include "modules/v2x/proto/v2x_obu_traffic_light.pb.h" -#include "modules/v2x/proto/v2x_rsi.pb.h" -#include "modules/common_msgs/v2x_msgs/v2x_traffic_light.pb.h" - -#include "modules/map/hdmap/hdmap.h" -#include "modules/map/hdmap/hdmap_common.h" - -namespace apollo { -namespace v2x { -enum RsiAlterType { - SPEED_LIMIT = 85, - SPEED_LIMIT_BRIDGE = 8, - SPEED_LIMIT_TUNNEL = 21, - CONSTRUCTION_AHEAD = 38, - BUS_LANE = 123, - TIDAL_LANE = 41, - TRAFFIC_JAM = 47, - TRAFFIC_ACCIDENT = 244, - NO_HONKING = 80, - SLOW_DOWN_SECTION = 35, - ACCIDENT_PRONE = 34, - OVERSPEED_VEHICLE = 801, - EMERGENCY_BRAKING = 802, - ANTIDROMIC_VEHICLE = 803, - ZOMBIES_VEHICLE = 804, - CONTROLLOSS_VEHICLE = 1000, - SPECIAL_VEHICLE = 2000, -}; - -using OSLightColor = ::apollo::v2x::SingleTrafficLight_Color; -using OSLightype = ::apollo::v2x::SingleTrafficLight_Type; -using ObuLightype = ::apollo::v2x::obu::SingleTrafficLight_Type; -using OSLight = ::apollo::v2x::IntersectionTrafficLightData; -using ObuLight = ::apollo::v2x::obu::ObuTrafficLight; -using OSLocation = ::apollo::localization::LocalizationEstimate; -using OSRsi = ::apollo::v2x::RsiMsg; -using ObuRsi = ::apollo::v2x::obu::ObuRsi; -using HDJunction = ::apollo::hdmap::JunctionInfoConstPtr; -using ObuJunction = ::apollo::v2x::Junction; -class ProtoAdapter final { - public: - static OSLightype LightTypeObu2Sys(int32_t type); - static bool LightObu2Sys(const ObuLight &obu_light, - std::shared_ptr *os_light); - static bool RsiObu2Sys(const ObuRsi *obu_rsi, std::shared_ptr *os_rsi); - static bool JunctionHd2obu(const HDJunction &hd_junction, - std::shared_ptr *obu_junction); -}; - -} // namespace v2x -} // namespace apollo diff --git a/modules/v2x/v2x_proxy/proto_adapter/proto_adapter_test.cc b/modules/v2x/v2x_proxy/proto_adapter/proto_adapter_test.cc deleted file mode 100644 index 7875fb71ae8..00000000000 --- a/modules/v2x/v2x_proxy/proto_adapter/proto_adapter_test.cc +++ /dev/null @@ -1,40 +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 proto_adapter_test.cc - */ - -#include "modules/v2x/v2x_proxy/proto_adapter/proto_adapter.h" - -#include "gtest/gtest.h" - -namespace apollo { -namespace v2x { - -TEST(v2x_proxy_app, v2x_proxy_adapter_convert_enum) { - EXPECT_EQ(OSLightype::SingleTrafficLight_Type_LEFT, - ProtoAdapter::LightTypeObu2Sys(2)); - EXPECT_EQ(OSLightype::SingleTrafficLight_Type_RIGHT, - ProtoAdapter::LightTypeObu2Sys(3)); - EXPECT_EQ(OSLightype::SingleTrafficLight_Type_U_TURN, - ProtoAdapter::LightTypeObu2Sys(4)); - EXPECT_EQ(OSLightype::SingleTrafficLight_Type_STRAIGHT, - ProtoAdapter::LightTypeObu2Sys(1)); -} - -} // namespace v2x -} // namespace apollo diff --git a/scripts/apollo_build.sh b/scripts/apollo_build.sh index abf1fe2d110..051579b3af9 100755 --- a/scripts/apollo_build.sh +++ b/scripts/apollo_build.sh @@ -247,7 +247,12 @@ function run_bazel_build() { info "${TAB}Build Targets: ${GREEN}${build_targets}${NO_COLOR}" info "${TAB}Disabled: ${YELLOW}${disabled_targets}${NO_COLOR}" - local job_args="--copt=-mavx2 --host_copt=-mavx2 --jobs=$(nproc) --local_ram_resources=HOST_RAM*0.7" + if [[ "$(uname -m)" == "aarch64" ]]; then + local job_args="--copt=-march=native --host_copt=-march=native --jobs=$(nproc) --local_ram_resources=HOST_RAM*0.7" + else + # x64 + local job_args="--copt=-mavx2 --host_copt=-mavx2 --jobs=$(nproc) --local_ram_resources=HOST_RAM*0.7" + fi bazel build ${CMDLINE_OPTIONS} ${job_args} -- ${formatted_targets} } diff --git a/scripts/cyberfile.xml b/scripts/cyberfile.xml deleted file mode 100644 index 2cdc75924e4..00000000000 --- a/scripts/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - origin-scripts - local - - Some apollo origin scripts. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module-wrapper - //dev/scripts - - diff --git a/third_party/absl/cyberfile.xml b/third_party/absl/cyberfile.xml deleted file mode 100644 index 9eb5419a51a..00000000000 --- a/third_party/absl/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-absl - local - - Apollo packaged absl Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/absl - - \ No newline at end of file diff --git a/third_party/ad_rss_lib/cyberfile.xml b/third_party/ad_rss_lib/cyberfile.xml deleted file mode 100644 index dcee78a964f..00000000000 --- a/third_party/ad_rss_lib/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-ad-rss-lib - local - - Apollo packaged 3rd-ad-rss-lib Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/ad_rss_lib - - \ No newline at end of file diff --git a/third_party/adolc/cyberfile.xml b/third_party/adolc/cyberfile.xml deleted file mode 100644 index 0a1c0651652..00000000000 --- a/third_party/adolc/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-adolc - local - - Apollo packaged adolc Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/adolc - - \ No newline at end of file diff --git a/third_party/adv_plat/cyberfile.xml b/third_party/adv_plat/cyberfile.xml deleted file mode 100644 index 888151f41ee..00000000000 --- a/third_party/adv_plat/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-adv-plat - local - - Apollo packaged 3rd-adv-plat Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/adv_plat - - \ No newline at end of file diff --git a/third_party/atlas/cyberfile.xml b/third_party/atlas/cyberfile.xml deleted file mode 100644 index 0f48a0105ce..00000000000 --- a/third_party/atlas/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-atlas - local - - Apollo packaged atlas Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/atlas - - \ No newline at end of file diff --git a/third_party/benchmark/cyberfile.xml b/third_party/benchmark/cyberfile.xml deleted file mode 100644 index 96a160683f0..00000000000 --- a/third_party/benchmark/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-benchmark - local - - Apollo packaged benchmark Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/benchmark - - \ No newline at end of file diff --git a/third_party/boost/cyberfile.xml b/third_party/boost/cyberfile.xml deleted file mode 100644 index cea536360e6..00000000000 --- a/third_party/boost/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-boost - local - - Apollo packaged boost Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/boost - - \ No newline at end of file diff --git a/third_party/caddn_infer_op/cyberfile.xml b/third_party/caddn_infer_op/cyberfile.xml deleted file mode 100644 index 59b639e1dcd..00000000000 --- a/third_party/caddn_infer_op/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-caddn-infer-op - local - - Apollo packaged civetweb Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/caddn_infer_op - - \ No newline at end of file diff --git a/third_party/caddn_infer_op/workspace.bzl b/third_party/caddn_infer_op/workspace.bzl index 7f733d73ce6..34c38afe63a 100644 --- a/third_party/caddn_infer_op/workspace.bzl +++ b/third_party/caddn_infer_op/workspace.bzl @@ -9,10 +9,15 @@ def clean_dep(dep): def repo(): http_archive( - name = "caddn_infer_op", + name = "caddn_infer_op-x86_64", sha256 = "8cf2f7444de837b80a5a23783dc58f8e372a5eb61f76cbbc543f0c036ecc73ce", strip_prefix = "caddn_infer_op", - urls = [ - "https://apollo-system.bj.bcebos.com/archive/v8.0_bev/caddn_infer_op.tar.gz", - ], + urls = ["https://apollo-system.bj.bcebos.com/archive/v8.0_bev/caddn_infer_op.tar.gz"], + ) + + http_archive( + name = "caddn_infer_op-aarch64", + sha256 = "27ce8bf6cb071b79e33676bd8ae237bbb640c7b99bf9e7a8944df40247723099", + strip_prefix = "caddn_infer_op", + urls = ["https://apollo-pkg-beta.bj.bcebos.com/archive/caddn_infer_op-linux-aarch64-1.0.0.tar.gz"], ) diff --git a/third_party/camera_library/cyberfile.xml b/third_party/camera_library/cyberfile.xml deleted file mode 100644 index c7ba707e7ad..00000000000 --- a/third_party/camera_library/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-camera-library - local - - Apollo packaged camera library. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //third_party/camera_library - - \ No newline at end of file diff --git a/third_party/can_card_library/cyberfile.xml b/third_party/can_card_library/cyberfile.xml deleted file mode 100644 index 1c15996592c..00000000000 --- a/third_party/can_card_library/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-can-card-library - local - - Apollo packaged cancard Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //third_party/can_card_library - - \ No newline at end of file diff --git a/third_party/centerpoint_infer_op/cyberfile.xml b/third_party/centerpoint_infer_op/cyberfile.xml deleted file mode 100644 index c198eae25fa..00000000000 --- a/third_party/centerpoint_infer_op/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-centerpoint-infer-op - local - - Apollo packaged civetweb Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/centerpoint_infer_op - - \ No newline at end of file diff --git a/third_party/centerpoint_infer_op/workspace.bzl b/third_party/centerpoint_infer_op/workspace.bzl index 99b5fd51685..f85117169e0 100644 --- a/third_party/centerpoint_infer_op/workspace.bzl +++ b/third_party/centerpoint_infer_op/workspace.bzl @@ -9,10 +9,16 @@ def clean_dep(dep): def repo(): http_archive( - name = "centerpoint_infer_op", - sha256 = "b39430eafad6b8b9b7e216840845b01c24b66406fb94ce06df721c6a3d738054", + name = "centerpoint_infer_op-x86_64", + sha256 = "9a8e95e0e71d4fbf6369c21541bbcaaf96581b8df1b1623e7fbf6049fda69306", strip_prefix = "centerpoint_infer_op", - urls = [ - "https://apollo-system.bj.bcebos.com/archive/v8.0_bev/centerpoint_infer_op.tar.gz", - ], + urls = ["https://apollo-pkg-beta.cdn.bcebos.com/archive/centerpoint_infer_op_cu111.tar.gz"], ) + + http_archive( + name = "centerpoint_infer_op-aarch64", + sha256 = "5d761076e139ef9e973541d7c0d2196cf789e55e14d9b9df0574bbea7caf184c", + strip_prefix = "centerpoint_infer_op", + urls = ["https://apollo-pkg-beta.bj.bcebos.com/archive/centerpoint_infer_op-linux-aarch64-2.0.0.tar.gz"], + ) + diff --git a/third_party/civetweb/cyberfile.xml b/third_party/civetweb/cyberfile.xml deleted file mode 100644 index a4a1efb7221..00000000000 --- a/third_party/civetweb/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-civetweb - local - - Apollo packaged civetweb Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/civetweb - - \ No newline at end of file diff --git a/third_party/cpplint/cyberfile.xml b/third_party/cpplint/cyberfile.xml deleted file mode 100644 index be772706b55..00000000000 --- a/third_party/cpplint/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-cpplint - local - - Apollo packaged cpplint Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/cpplint - - \ No newline at end of file diff --git a/third_party/eigen3/cyberfile.xml b/third_party/eigen3/cyberfile.xml deleted file mode 100644 index 4d80be96592..00000000000 --- a/third_party/eigen3/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-eigen3 - local - - Apollo packaged eigen3 Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/eigen3 - - \ No newline at end of file diff --git a/third_party/fastrtps/cyberfile.xml b/third_party/fastrtps/cyberfile.xml deleted file mode 100644 index d2e4bd06bbb..00000000000 --- a/third_party/fastrtps/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-fastrtps - local - - Apollo packaged 3rd-fastrtps Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/fastrtps - - \ No newline at end of file diff --git a/third_party/ffmpeg/cyberfile.xml b/third_party/ffmpeg/cyberfile.xml deleted file mode 100644 index 32c60fa66b0..00000000000 --- a/third_party/ffmpeg/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-ffmpeg - local - - Apollo packaged 3rd-ffmpeg Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/ffmpeg - - \ No newline at end of file diff --git a/third_party/fftw3/cyberfile.xml b/third_party/fftw3/cyberfile.xml deleted file mode 100644 index 83215e50b1e..00000000000 --- a/third_party/fftw3/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-fftw3 - local - - Apollo packaged fftw3 Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/fftw3 - - \ No newline at end of file diff --git a/third_party/gflags/cyberfile.xml b/third_party/gflags/cyberfile.xml deleted file mode 100644 index ce9f5cd8af0..00000000000 --- a/third_party/gflags/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-gflags - local - - Apollo packaged gflags Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/gflags - - \ No newline at end of file diff --git a/third_party/glew/cyberfile.xml b/third_party/glew/cyberfile.xml deleted file mode 100644 index a48e1d0326a..00000000000 --- a/third_party/glew/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-glew - local - - Apollo packaged glew Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/glew - - \ No newline at end of file diff --git a/third_party/glog/cyberfile.xml b/third_party/glog/cyberfile.xml deleted file mode 100644 index 493c74afc96..00000000000 --- a/third_party/glog/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-glog - local - - Apollo packaged 3rd-glog Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/glog - - \ No newline at end of file diff --git a/third_party/gpus/cyberfile.xml b/third_party/gpus/cyberfile.xml deleted file mode 100644 index 1134892c138..00000000000 --- a/third_party/gpus/cyberfile.xml +++ /dev/null @@ -1,19 +0,0 @@ - - 3rd-gpus - local - - Apollo packaged 3rd-gpu Libs. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - 3rd-bazel-skylib-dev - - third-wrapper - //third_party/gpus - - \ No newline at end of file diff --git a/third_party/gtest/cyberfile.xml b/third_party/gtest/cyberfile.xml deleted file mode 100644 index 05ae9cbacba..00000000000 --- a/third_party/gtest/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-gtest - local - - Apollo packaged gtest Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/gtest - - \ No newline at end of file diff --git a/third_party/ipopt/cyberfile.xml b/third_party/ipopt/cyberfile.xml deleted file mode 100644 index c76f00d5439..00000000000 --- a/third_party/ipopt/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-ipopt - local - - Apollo packaged ipopt Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/ipopt - - \ No newline at end of file diff --git a/third_party/localization_msf/BUILD b/third_party/localization_msf/BUILD index 9108755d02d..22c0e98386a 100644 --- a/third_party/localization_msf/BUILD +++ b/third_party/localization_msf/BUILD @@ -6,27 +6,6 @@ package(default_visibility = ["//visibility:public"]) licenses(["notice"]) -cc_library( - name = "localization_msf", - srcs = if_x86_64([ - "x86_64/lib/liblocalization_msf.so", - ]) + if_aarch64([ - "aarch64/lib/liblocalization_msf.so", - ]), - hdrs = if_x86_64(glob([ - "x86_64/include/*.h", - ])) + if_aarch64(glob([ - "aarch64/include/*.h", - ])), - include_prefix = "localization_msf", - linkopts = [ - "-lm", - ], - strip_include_prefix = select({ - "@platforms//cpu:x86_64": "x86_64/include", - "@platforms//cpu:aarch64": "aarch64/include", - }), -) install( diff --git a/third_party/localization_msf/cyberfile.xml b/third_party/localization_msf/cyberfile.xml deleted file mode 100644 index b2102e14c86..00000000000 --- a/third_party/localization_msf/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-localization-msf - local - - Apollo packaged localization-msf Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/localization_msf - - diff --git a/third_party/localization_msf/init.bzl b/third_party/localization_msf/init.bzl index 6a5dbf1616c..7da49927da6 100644 --- a/third_party/localization_msf/init.bzl +++ b/third_party/localization_msf/init.bzl @@ -1,5 +1,5 @@ - +"""Loads the caddn_infer_op library""" +load("//third_party/localization_msf:workspace.bzl", "repo") def init(): - pass - \ No newline at end of file + repo() diff --git a/third_party/localization_msf/workspace.bzl b/third_party/localization_msf/workspace.bzl new file mode 100644 index 00000000000..61769494ee0 --- /dev/null +++ b/third_party/localization_msf/workspace.bzl @@ -0,0 +1,16 @@ +"""Loads the paddlelite library""" + +# Sanitize a dependency so that it works correctly from code that includes +# Apollo as a submodule. +load("@bazel_tools//tools/build_defs/repo:http.bzl", "http_archive") + +def clean_dep(dep): + return str(Label(dep)) + +def repo(): + http_archive( + name = "localization_msf", + sha256 = "58e11d580060ad9b75d62254eb4f943c510acf5e1eb88868797aa7d77d32299b", + strip_prefix = "localization_msf", + urls = ["https://apollo-pkg-beta.bj.bcebos.com/archive/localization_msf-linux-any-1.0.0.tar.gz"], + ) \ No newline at end of file diff --git a/third_party/ncurses5/cyberfile.xml b/third_party/ncurses5/cyberfile.xml deleted file mode 100644 index 5c7d7ea810a..00000000000 --- a/third_party/ncurses5/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-ncurses5 - local - - Apollo packaged ncurses5 Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/ncurses5 - - \ No newline at end of file diff --git a/third_party/nlohmann_json/cyberfile.xml b/third_party/nlohmann_json/cyberfile.xml deleted file mode 100644 index 5db91536f9d..00000000000 --- a/third_party/nlohmann_json/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-nlohmann-json - local - - Apollo packaged nlohmann-json Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/nlohmann_json - - \ No newline at end of file diff --git a/third_party/npp/cyberfile.xml b/third_party/npp/cyberfile.xml deleted file mode 100644 index 1881638b748..00000000000 --- a/third_party/npp/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-npp - local - - Apollo packaged npp Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/npp - - \ No newline at end of file diff --git a/third_party/opencv/cyberfile.xml b/third_party/opencv/cyberfile.xml deleted file mode 100644 index 9ca20abe900..00000000000 --- a/third_party/opencv/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-opencv - local - - Apollo packaged 3rd-opencv Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/opencv - - \ No newline at end of file diff --git a/third_party/opengl/cyberfile.xml b/third_party/opengl/cyberfile.xml deleted file mode 100644 index 2b13bbff8b9..00000000000 --- a/third_party/opengl/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-opengl - local - - Apollo packaged opengl Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/opengl - - \ No newline at end of file diff --git a/third_party/openh264/cyberfile.xml b/third_party/openh264/cyberfile.xml deleted file mode 100644 index 7ad9f58a0cc..00000000000 --- a/third_party/openh264/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-openh264 - local - - Apollo packaged openh264 Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/openh264 - - \ No newline at end of file diff --git a/third_party/osqp/cyberfile.xml b/third_party/osqp/cyberfile.xml deleted file mode 100644 index 5d4f23b60d2..00000000000 --- a/third_party/osqp/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-osqp - local - - Apollo packaged osqp Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/osqp - - \ No newline at end of file diff --git a/third_party/paddleinference/cyberfile.xml b/third_party/paddleinference/cyberfile.xml deleted file mode 100644 index bce7b5bdc00..00000000000 --- a/third_party/paddleinference/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-paddleinference - local - - Apollo packaged paddleinference. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/paddleinference - - \ No newline at end of file diff --git a/third_party/paddleinference/workspace.bzl b/third_party/paddleinference/workspace.bzl index ceef0724952..f5374fc60d3 100644 --- a/third_party/paddleinference/workspace.bzl +++ b/third_party/paddleinference/workspace.bzl @@ -9,10 +9,15 @@ def clean_dep(dep): def repo(): http_archive( - name = "paddleinference", - sha256 = "d79ae353d0181035eb6c750d1e9e8cf50148e3c8648dd1fa084e50af64380b1c", + name = "paddleinference-x86_64", + sha256 = "ed4f9b5757a81351e869d31e8371393340fdfd183b83a8e532a6b2951dfae8c4", strip_prefix = "paddleinference", - urls = [ - "https://apollo-system.bj.bcebos.com/archive/v8.0_bev/paddleinferencev-1.0.0.tar.gz", - ], + urls = ["https://apollo-pkg-beta.cdn.bcebos.com/archive/paddleinference-cu111-x86.tar.gz"], ) + + http_archive( + name = "paddleinference-aarch64", + sha256 = "ac5f124650e61d8d4b3552cf070258bc2464293bc31d7416ee99e9ba9693e3ee", + strip_prefix = "paddleinference", + urls = ["https://apollo-pkg-beta.bj.bcebos.com/archive/paddleinference-linux-aarch64-2.0.0.tar.gz"], + ) \ No newline at end of file diff --git a/third_party/pcl/cyberfile.xml b/third_party/pcl/cyberfile.xml deleted file mode 100644 index 4e75bb031a1..00000000000 --- a/third_party/pcl/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-pcl - local - - Apollo packaged 3rd-pcl Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/pcl - - \ No newline at end of file diff --git a/third_party/portaudio/cyberfile.xml b/third_party/portaudio/cyberfile.xml deleted file mode 100644 index f2048b73638..00000000000 --- a/third_party/portaudio/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-portaudio - local - - Apollo packaged portaudio Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/portaudio - - \ No newline at end of file diff --git a/third_party/proj/cyberfile.xml b/third_party/proj/cyberfile.xml deleted file mode 100644 index a390f4f80ad..00000000000 --- a/third_party/proj/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-proj - local - - Apollo packaged proj Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/proj - - \ No newline at end of file diff --git a/third_party/protobuf/cyberfile.xml b/third_party/protobuf/cyberfile.xml deleted file mode 100644 index 38b73af8ef9..00000000000 --- a/third_party/protobuf/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-protobuf - local - - Apollo packaged protobuf Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/protobuf - - \ No newline at end of file diff --git a/third_party/py/cyberfile.xml b/third_party/py/cyberfile.xml deleted file mode 100644 index a942d537ecf..00000000000 --- a/third_party/py/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-py - local - - Apollo packaged py Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/py - - \ No newline at end of file diff --git a/third_party/qt5/cyberfile.xml b/third_party/qt5/cyberfile.xml deleted file mode 100644 index d557777bb37..00000000000 --- a/third_party/qt5/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-qt5 - local - - Apollo packaged qt5 Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/qt5 - - \ No newline at end of file diff --git a/third_party/rtklib/cyberfile.xml b/third_party/rtklib/cyberfile.xml deleted file mode 100644 index 2937805fc5e..00000000000 --- a/third_party/rtklib/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-rtklib - local - - Apollo packaged cancard Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module - //third_party/rtklib - - \ No newline at end of file diff --git a/third_party/sqlite3/cyberfile.xml b/third_party/sqlite3/cyberfile.xml deleted file mode 100644 index 3a6ef120a53..00000000000 --- a/third_party/sqlite3/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-sqlite3 - local - - Apollo packaged sqlite3 Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/sqlite3 - - \ No newline at end of file diff --git a/third_party/sse2neon/workspace.bzl b/third_party/sse2neon/workspace.bzl index 35c7af35198..cb136758a51 100644 --- a/third_party/sse2neon/workspace.bzl +++ b/third_party/sse2neon/workspace.bzl @@ -1,5 +1,7 @@ """Loads the sse2neon library""" +load("@bazel_tools//tools/build_defs/repo:http.bzl", "http_archive") + # Sanitize a dependency so that it works correctly from code that includes # Apollo as a submodule. def clean_dep(dep): @@ -7,9 +9,9 @@ def clean_dep(dep): def repo(): # sse2neon - native.new_local_repository( + http_archive( name = "sse2neon", - build_file = clean_dep("//third_party/sse2neon/sse2neon.BUILD"), + build_file = clean_dep("//third_party/sse2neon:sse2neon.BUILD"), strip_prefix = "sse2neon-1.6.0", urls = [ "https://github.com/DLTcollab/sse2neon/archive/refs/tags/v1.6.0.tar.gz", diff --git a/third_party/tensorrt/cyberfile.xml b/third_party/tensorrt/cyberfile.xml deleted file mode 100644 index 581a9c98cca..00000000000 --- a/third_party/tensorrt/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-tensorrt - local - - Apollo packaged tensorrt Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/tensorrt - - \ No newline at end of file diff --git a/third_party/tf2/cyberfile.xml b/third_party/tf2/cyberfile.xml deleted file mode 100644 index 2aaff8c0c51..00000000000 --- a/third_party/tf2/cyberfile.xml +++ /dev/null @@ -1,18 +0,0 @@ - - 3rd-tf2 - local - - Apollo packaged tf2 Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - 3rd-boost-dev - - module - //third_party/tf2 - - \ No newline at end of file diff --git a/third_party/tinyxml2/cyberfile.xml b/third_party/tinyxml2/cyberfile.xml deleted file mode 100644 index 1e3aa473cc7..00000000000 --- a/third_party/tinyxml2/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-tinyxml2 - local - - Apollo packaged tinyxml2 Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/tinyxml2 - - \ No newline at end of file diff --git a/third_party/uuid/cyberfile.xml b/third_party/uuid/cyberfile.xml deleted file mode 100644 index 92e246455cf..00000000000 --- a/third_party/uuid/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-uuid - local - - Apollo packaged uuid Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-binary - //third_party/uuid - - \ No newline at end of file diff --git a/third_party/vtk/cyberfile.xml b/third_party/vtk/cyberfile.xml deleted file mode 100644 index 7a06ed7b544..00000000000 --- a/third_party/vtk/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-vtk - local - - Apollo packaged 3rd-vtk Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/vtk - - \ No newline at end of file diff --git a/third_party/yaml_cpp/cyberfile.xml b/third_party/yaml_cpp/cyberfile.xml deleted file mode 100644 index ba144a85e1c..00000000000 --- a/third_party/yaml_cpp/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - 3rd-yaml-cpp - local - - Apollo packaged yaml-cpp Lib. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - third-wrapper - //third_party/yaml_cpp - - \ No newline at end of file diff --git a/tools/cyberfile.xml b/tools/cyberfile.xml deleted file mode 100644 index 4ac9aeba26f..00000000000 --- a/tools/cyberfile.xml +++ /dev/null @@ -1,17 +0,0 @@ - - bazel-extend-tools - local - - Some extend rules of bazel and scripts. - - - Apollo - Apache License 2.0 - https://www.apollo.auto/ - https://github.com/ApolloAuto/apollo - https://github.com/ApolloAuto/apollo/issues - - module-wrapper - //tools - - \ No newline at end of file diff --git a/tools/workspace.bzl b/tools/workspace.bzl index dc506bdd029..529bf52b334 100644 --- a/tools/workspace.bzl +++ b/tools/workspace.bzl @@ -35,7 +35,8 @@ load("//third_party/sqlite3:workspace.bzl", sqlite3 = "repo") load("//third_party/tinyxml2:workspace.bzl", tinyxml2 = "repo") load("//third_party/uuid:workspace.bzl", uuid = "repo") load("//third_party/yaml_cpp:workspace.bzl", yaml_cpp = "repo") - +load("//third_party/sse2neon:workspace.bzl", sse2neon = "repo") +load("//third_party/localization_msf:workspace.bzl", localization_msf = "repo") # load("//third_party/glew:workspace.bzl", glew = "repo") load("//third_party/gpus:cuda_configure.bzl", "cuda_configure") @@ -70,6 +71,7 @@ def initialize_third_party(): libtorch_gpu() ncurses5() nlohmann_json() + localization_msf() npp() opencv() opengl() @@ -84,6 +86,7 @@ def initialize_third_party(): tinyxml2() uuid() yaml_cpp() + sse2neon() # Define all external repositories required by def apollo_repositories():