• Apollo 应用与源码分析:CyberRT-组件(component)


    目录

    概念

    二进制与组件

    基本的使用方法

    使用组件的优势

    Dag文件

    样例

    参数含义

    样例

    Common_component_example

    Timer_component_example

    构建与运行

    注意

    Apollo Guardian 样例分析

    guardian_component.h

    guardian_component.cc

    dag

    build

    launch


    概念

    组件是cyberrt提供的用于构建应用程序模块的基类。

    每个特定的应用程序模块都可以继承Component类,并定义自己的Init和Proc函数,以便将其加载到Cyber框架中。

    二进制与组件

    将Cyber RT框架用于应用程序有两个选项:

    • 基于二进制文件:应用程序单独编译成二进制文件,通过创建自己的Reader和Writer与其他网络模块通信。
    • 基于组件:应用程序被编译成共享库。通过继承component类并编写相应的dag描述文件,Cyber RT框架将动态加载和运行应用程序。

    基本的使用方法

    主要是需要继承component类,然后重写两个函数: init和proc

    • 组件的Init()函数类似于对算法进行一些初始化的主要函数。
    • 组件的Proc()函数的工作原理类似于框架在消息到达时调用的Reader回调函数。


    使用组件的优势

    • 组件可以通过启动文件加载到不同的进程中,并且部署是灵活的。
    • 组件可以通过修改dag文件而不重新编译来更改收到的通道名称。
    • 组件支持接收多种类型的数据。
    • 组件支持提供多种融合策略。

    Dag文件

    样例

    # Define all coms in DAG streaming.
    module_config {
        module_library : "lib/libperception_component.so"
        components {
            class_name : "PerceptionComponent"
            config {
                name : "perception"
                readers {
                    channel: "perception/channel_name"
                }
            }
        }
        timer_components {
            class_name : "DriverComponent"
            config {
                name : "driver"
                interval : 100
            }
        }
    }

    参数含义

    • module_library:如果您想加载.so库,根目录是网络的工作目录(setup.bash的同一目录)
    • components & timer_component:选择需要加载的基本组件类类型。
    • class_name:要加载的组件类的名称
    • name:加载的class_name作为加载示例的标识符
    • readers:当前组件收到的数据,支持1-3个数据通道。

    样例

    Common_component_example

    #include 
    
    #include "cyber/class_loader/class_loader.h"
    #include "cyber/component/component.h"
    #include "cyber/examples/proto/examples.pb.h"
    
    using apollo::cyber::examples::proto::Driver;
    using apollo::cyber::Component;
    using apollo::cyber::ComponentBase;
    
    class Commontestcomponent : public Component {
     public:
      bool Init() override;
      bool Proc(const std::shared_ptr& msg0,
                const std::shared_ptr& msg1) override;
    };
    CYBER_REGISTER_COMPONENT(Commontestcomponent)  // 注册到反射框架中
    #include "cyber/examples/common_component_smaple/common_component_example.h"
    
    #include "cyber/class_loader/class_loader.h"
    #include "cyber/component/component.h"
    
    bool Commontestcomponent::Init() {
      AINFO << "Commontest component init";
      return true;
    }
    
    bool Commontestcomponent::Proc(const std::shared_ptr& msg0,
                                   const std::shared_ptr& msg1) {
      AINFO << "Start commontest component Proc [" << msg0->msg_id() << "] ["
            << msg1->msg_id() << "]";
      return true;
    } 

    Timer_component_example

    #include 
    
    #include "cyber/class_loader/class_loader.h"
    #include "cyber/component/component.h"
    #include "cyber/component/timer_component.h"
    #include "cyber/examples/proto/examples.pb.h"
    
    using apollo::cyber::examples::proto::Driver;
    using apollo::cyber::Component;
    using apollo::cyber::ComponentBase;
    using apollo::cyber::TimerComponent;
    using apollo::cyber::Writer;
    
    class TimertestComponent : public TimerComponent {
     public:
      bool Init() override;
      bool Proc() override;
    
     private:
      std::shared_ptr> driver_writer_ = nullptr;
    };
    CYBER_REGISTER_COMPONENT(TimertestComponent)
    #include "cyber/examples/timer_component_example/timer_component_example.h"
    
    #include "cyber/class_loader/class_loader.h"
    #include "cyber/component/component.h"
    #include "cyber/examples/proto/examples.pb.h"
    
    bool TimertestComponent::Init() {
      driver_writer_ = node_->CreateWriter("/carstatus/channel");
      return true;
    }
    
    bool TimertestComponent::Proc() {
      static int i = 0;
      auto out_msg = std::make_shared();
      out_msg->set_msg_id(i++);
      driver_writer_->Write(out_msg);
      AINFO << "timertestcomponent: Write drivermsg->"
            << out_msg->ShortDebugString();
      return true;
    }

    构建与运行

    • Build: bazel build cyber/examples/timer_component_smaple/…
    • Run: mainboard -d cyber/examples/timer_component_smaple/timer.dag

    注意

    • 需要注册组件才能通过SharedLibrary加载类。注册界面如下所示:
    CYBER_REGISTER_COMPONENT(DriverComponent) 

    如果您在注册时使用命名空间,则在dag文件中定义命名空间时,您还需要添加命名空间。

    • Component和TimerComponent的配置不同,请注意不要将两者混淆。

    Apollo Guardian 样例分析

    guardian 相对比较简单,可以用于分析component的使用

    guardian_component.h

    /******************************************************************************
     * 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
     */
    
    #pragma once
    
    #include 
    
    #include "cyber/common/macros.h"
    #include "cyber/component/timer_component.h"
    #include "cyber/cyber.h"
    
    #include "modules/canbus/proto/chassis.pb.h"
    #include "modules/control/proto/control_cmd.pb.h"
    #include "modules/guardian/proto/guardian.pb.h"
    #include "modules/guardian/proto/guardian_conf.pb.h"
    #include "modules/monitor/proto/system_status.pb.h"
    
    /**
     * @namespace apollo::guardian
     * @brief apollo::guardian
     */
    namespace apollo {
    namespace guardian {
    
    class GuardianComponent : public apollo::cyber::TimerComponent {
     public:
      bool Init() override;
      bool Proc() override;
    
     private:
      void PassThroughControlCommand();
      void TriggerSafetyMode();
    
      apollo::guardian::GuardianConf guardian_conf_;
      apollo::canbus::Chassis chassis_;
      apollo::monitor::SystemStatus system_status_;
      apollo::control::ControlCommand control_cmd_;
      apollo::guardian::GuardianCommand guardian_cmd_;
    
      double last_status_received_s_{};
    
      std::shared_ptr>
          chassis_reader_;
      std::shared_ptr>
          control_cmd_reader_;
      std::shared_ptr>
          system_status_reader_;
      std::shared_ptr>
          guardian_writer_;
    
      std::mutex mutex_;
    };
    
    CYBER_REGISTER_COMPONENT(GuardianComponent)
    
    }  // namespace guardian
    }  // namespace apollo
    

    guardian_component.cc

    /******************************************************************************
     * 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/guardian/guardian_component.h"
    
    #include "cyber/common/log.h"
    #include "modules/common/adapters/adapter_gflags.h"
    #include "modules/common/util/message_util.h"
    
    using Time = ::apollo::cyber::Time;
    
    namespace apollo {
    namespace guardian {
    
    using apollo::canbus::Chassis;
    using apollo::control::ControlCommand;
    using apollo::monitor::SystemStatus;
    
    bool GuardianComponent::Init() {
      if (!GetProtoConfig(&guardian_conf_)) {
        AERROR << "Unable to load canbus conf file: " << ConfigFilePath();
        return false;
      }
    
      chassis_reader_ = node_->CreateReader(
          FLAGS_chassis_topic, [this](const std::shared_ptr& chassis) {
            ADEBUG << "Received chassis data: run chassis callback.";
            std::lock_guard lock(mutex_);
            chassis_.CopyFrom(*chassis);
          });
    
      control_cmd_reader_ = node_->CreateReader(
          FLAGS_control_command_topic,
          [this](const std::shared_ptr& cmd) {
            ADEBUG << "Received control data: run control callback.";
            std::lock_guard lock(mutex_);
            control_cmd_.CopyFrom(*cmd);
          });
    
      system_status_reader_ = node_->CreateReader(
          FLAGS_system_status_topic,
          [this](const std::shared_ptr& status) {
            ADEBUG << "Received system status data: run system status callback.";
            std::lock_guard lock(mutex_);
            last_status_received_s_ = Time::Now().ToSecond();
            system_status_.CopyFrom(*status);
          });
    
      guardian_writer_ = node_->CreateWriter(FLAGS_guardian_topic);
    
      return true;
    }
    
    bool GuardianComponent::Proc() {
      constexpr double kSecondsTillTimeout(2.5);
    
      bool safety_mode_triggered = false;
      if (guardian_conf_.guardian_enable()) {
        std::lock_guard lock(mutex_);
        if (Time::Now().ToSecond() - last_status_received_s_ >
            kSecondsTillTimeout) {
          safety_mode_triggered = true;
        }
        safety_mode_triggered =
            safety_mode_triggered || system_status_.has_safety_mode_trigger_time();
      }
    
      if (safety_mode_triggered) {
        ADEBUG << "Safety mode triggered, enable safety mode";
        TriggerSafetyMode();
      } else {
        ADEBUG << "Safety mode not triggered, bypass control command";
        PassThroughControlCommand();
      }
    
      common::util::FillHeader(node_->Name(), &guardian_cmd_);
      guardian_writer_->Write(guardian_cmd_);
      return true;
    }
    
    void GuardianComponent::PassThroughControlCommand() {
      std::lock_guard lock(mutex_);
      guardian_cmd_.mutable_control_command()->CopyFrom(control_cmd_);
    }
    
    void GuardianComponent::TriggerSafetyMode() {
      AINFO << "Safety state triggered, with system safety mode trigger time : "
            << system_status_.safety_mode_trigger_time();
      std::lock_guard lock(mutex_);
      bool sensor_malfunction = false, obstacle_detected = false;
      if (!chassis_.surround().sonar_enabled() ||
          chassis_.surround().sonar_fault()) {
        AINFO << "Ultrasonic sensor not enabled for faulted, will do emergency "
                 "stop!";
        sensor_malfunction = true;
      } else {
        // TODO(QiL) : Load for config
        for (int i = 0; i < chassis_.surround().sonar_range_size(); ++i) {
          if ((chassis_.surround().sonar_range(i) > 0.0 &&
               chassis_.surround().sonar_range(i) < 2.5) ||
              chassis_.surround().sonar_range(i) > 30) {
            AINFO << "Object detected or ultrasonic sensor fault output, will do "
                     "emergency stop!";
            obstacle_detected = true;
          }
        }
      }
    
      guardian_cmd_.mutable_control_command()->set_throttle(0.0);
      guardian_cmd_.mutable_control_command()->set_steering_target(0.0);
      guardian_cmd_.mutable_control_command()->set_steering_rate(25.0);
      guardian_cmd_.mutable_control_command()->set_is_in_safe_mode(true);
    
      // TODO(QiL) : Remove this one once hardware re-alignment is done.
      sensor_malfunction = false;
      obstacle_detected = false;
      AINFO << "Temporarily ignore the ultrasonic sensor output during hardware "
               "re-alignment!";
    
      if (system_status_.require_emergency_stop() || sensor_malfunction ||
          obstacle_detected) {
        AINFO << "Emergency stop triggered! with system status from monitor as : "
              << system_status_.require_emergency_stop();
        guardian_cmd_.mutable_control_command()->set_brake(
            guardian_conf_.guardian_cmd_emergency_stop_percentage());
      } else {
        AINFO << "Soft stop triggered! with system status from monitor as : "
              << system_status_.require_emergency_stop();
        guardian_cmd_.mutable_control_command()->set_brake(
            guardian_conf_.guardian_cmd_soft_stop_percentage());
      }
    }
    
    }  // namespace guardian
    }  // namespace apollo
    

    dag

    module_config {
        module_library : "/apollo/bazel-bin/modules/guardian/libguardian_component.so",
        timer_components {
            class_name : "GuardianComponent"
            config {
                name: "guardian"
                config_file_path: "/apollo/modules/guardian/conf/guardian_conf.pb.txt"
                interval: 10
            }
        }
    }
    

    build

    load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library")
    load("//tools/install:install.bzl", "install")
    load("//tools:cpplint.bzl", "cpplint")
    
    package(default_visibility = ["//visibility:public"])
    
    GUARDIAN_COPTS = ['-DMODULE_NAME=\\"guardian\\"']
    
    cc_library(
        name = "guardian_component_lib",
        srcs = ["guardian_component.cc"],
        hdrs = ["guardian_component.h"],
        copts = GUARDIAN_COPTS,
        deps = [
            "//cyber",
            "//modules/canbus/proto:chassis_cc_proto",
            "//modules/common/adapters:adapter_gflags",
            "//modules/common/util:message_util",
            "//modules/control/proto:control_cmd_cc_proto",
            "//modules/guardian/proto:guardian_cc_proto",
            "//modules/guardian/proto:guardian_conf_cc_proto",
            "//modules/monitor/proto:system_status_cc_proto",
        ],
    )
    
    cc_binary(
        name = "libguardian_component.so",
        linkshared = True,
        linkstatic = False,
        deps = [
            ":guardian_component_lib",
        ],
    )
    
    install(
        name = "install",
        data = [
            ":runtime_data",
        ],
        targets = [
            ":libguardian_component.so",
        ],
        deps = [
            "//cyber:install",
        ],
    )
    
    filegroup(
        name = "runtime_data",
        srcs = glob([
            "conf/*.txt",
            "dag/*.dag",
            "launch/*.launch",
        ]),
    )
    
    cpplint()
    

    launch

    
        
            guardian
            /apollo/modules/guardian/dag/guardian.dag
            guardian
        
    
    
  • 相关阅读:
    Redis——》内存最大限制
    Java进阶之路-目录
    【算法刷题日记之本手篇】求正数数组的最小不可组成和与有假币
    php fpdf使用记录
    74. 搜索二维矩阵
    python篇-自动化-poco
    【C语言】刷题训练营 —— 每日一练
    二十六、设置时序电路初始状态的方法(初始值设置)(时序电路置数)2
    互融云商业保理系统开发|产品成熟,已服务上千家保理企业
    LaTeX学习笔记
  • 原文地址:https://blog.csdn.net/qq_32378713/article/details/127994910