一,背景
ROS 應用於自動駕駛領域的不足:
- 調度的不確定性:各節點以獨立進程運行,節點運行順序無法確定,因而業務邏輯的調度順序無法保證;
- 運行效率:ROS 爲分佈式系統,存在通信開銷
二,Cyber RT 框架
從下到上依次爲:
基礎庫:高性能,無鎖隊列;
通信層:Publish/Subscribe機制,Service/Client機制,服務自發現,自適應的通信機制(共享內存、Socket、進程內);
數據層:數據緩存與融合。多路傳感器之間數據需要融合,而且算法可能需要緩存一定的數據。比如典型的仿真應用,不同算法模塊之間需要有一個數據橋樑,數據層起到了這個模塊間通信的橋樑的作用;
計算層:計算模型,任務以及任務調度;
三,運行流程
算法模塊通過有向無環圖(DAG),配置任務間的邏輯關係。對於每個算法可以進行優先級、運行時間、使用資源等方面的配置。
系統啓動時,結合DAG、調度配置等,創建相應的任務,從框架內部來講,就是協程(coroutine)
調度器把任務放到各個 Processor 的隊列中。
然後,由 Sensor 輸入的數據,驅動整個系統運轉。
四,基本概念以及與 ROS 對照
五,特色
高性能:無鎖對象,協程(coroutine),自適應通信機制;
確定性:可配置的任務以及任務調度,通過協程將調度從內核空間轉移到用戶空間;
模塊化:在框架內實現組件以及節點,即可完成系統任務;
便利性:創建和使用任務
六,示例
Writer/Reader
Message:
syntax = "proto2";
package apollo.cyber.examples.proto;
message Chatter {
optional uint64 timestamp = 1;
optional uint64 lidar_timestamp = 2;
optional uint64 seq = 3;
optional bytes content = 4;
};
Writer:
#include "cyber/cyber.h"
#include "cyber/examples/proto/examples.pb.h"
#include "cyber/time/rate.h"
#include "cyber/time/time.h"
using apollo::cyber::Rate;
using apollo::cyber::Time;
using apollo::cyber::examples::proto::Chatter;
int main(int argc, char *argv[]) {
// init cyber framework
apollo::cyber::Init(argv[0]);
// create talker node
auto talker_node = apollo::cyber::CreateNode("talker");
// create talker
auto talker = talker_node->CreateWriter<Chatter>("channel/chatter");
Rate rate(1.0);
while (apollo::cyber::OK()) {
static uint64_t seq = 0;
auto msg = std::make_shared<Chatter>();
msg->set_timestamp(Time::Now().ToNanosecond());
msg->set_lidar_timestamp(Time::Now().ToNanosecond());
msg->set_seq(seq++);
msg->set_content("Hello, apollo!");
talker->Write(msg);
AINFO << "talker sent a message!";
rate.Sleep();
}
return 0;
}
Reader:
#include "cyber/cyber.h"
#include "cyber/examples/proto/examples.pb.h"
void MessageCallback(
const std::shared_ptr<apollo::cyber::examples::proto::Chatter>& msg) {
AINFO << "Received message seq-> " << msg->seq();
AINFO << "msgcontent->" << msg->content();
}
int main(int argc, char* argv[]) {
// init cyber framework
apollo::cyber::Init(argv[0]);
// create listener node
auto listener_node = apollo::cyber::CreateNode("listener");
// create listener
auto listener =
listener_node->CreateReader<apollo::cyber::examples::proto::Chatter>(
"channel/chatter", MessageCallback);
apollo::cyber::WaitForShutdown();
return 0;
}
Service/Client
Message:
syntax = "proto2";
package apollo.cyber.examples.proto;
message Driver {
optional string content = 1;
optional uint64 msg_id = 2;
optional uint64 timestamp = 3;
};
Service/client:
#include "cyber/cyber.h"
#include "cyber/examples/proto/examples.pb.h"
using apollo::cyber::examples::proto::Driver;
int main(int argc, char* argv[]) {
apollo::cyber::Init(argv[0]);
std::shared_ptr<apollo::cyber::Node> node(
apollo::cyber::CreateNode("start_node"));
auto server = node->CreateService<Driver, Driver>(
"test_server", [](const std::shared_ptr<Driver>& request,
std::shared_ptr<Driver>& response) {
AINFO << "server: i am driver server";
static uint64_t id = 0;
++id;
response->set_msg_id(id);
response->set_timestamp(0);
});
auto client = node->CreateClient<Driver, Driver>("test_server");
auto driver_msg = std::make_shared<Driver>();
driver_msg->set_msg_id(0);
driver_msg->set_timestamp(0);
while (apollo::cyber::OK()) {
auto res = client->SendRequest(driver_msg);
if (res != nullptr) {
AINFO << "client: responese: " << res->ShortDebugString();
} else {
AINFO << "client: service may not ready.";
}
sleep(1);
}
apollo::cyber::WaitForShutdown();
return 0;
}
七,Apollo 整體框架