Apollo ROSやめるってよ
2019年1月8日、ROSベースであったBaiduの自動運転OSS、Apolloに大きな変化がありました。
これまでROSベースで開発してきたがver3.5以降ではROSのサポートを諦めBaidu独自フレームワークのCyber RTに移行するとのことです。
産業用途で使用できるレベルに仕上げたいとのことなのでBaiduはROS1は産業用には不安定すぎてそのままでは使えない、かといってROS2開発を待っているのでは時間がかかりすぎるという判断をしたのでしょう。
ROS1ベースの自動運転OSSを開発している筆者にはちょっとショックでした。
そこでCyber RTのドキュメントを読んで見たところこれ結構簡単そうだしROSつかったことある人ならすぐ使えそうという印象で出来はかなりよさそうという感じでした。
というわけで今回は軽く使ってみてわかったCyber RTおよびApollo 3.5の概要を備忘録代わりにまとめていきたいと思います。
Cyber RT
Cyber RTは自動運転向けのオープンソースなフレームワークであり処理の高速化や優先度設定によるスケジューリングに重点をおいています。惜しむらくは対応OSがUbuntu 14.04のみであることでしょうか。
Cyber RTは多数のモジュール間のメッセージパッシングで動作するROSに類似のフレームワークであり、bazelをベースにしたビルドシステム、protobufによるシリアライズ・デシリアライズ、glogによるロギングシステム、rvizに類似のCyber_visualizer、roslaunchの代替となるcyber_launch、rqt_topic_monitor的な何かであるcyber_monitor、rosbagに類似のcyber_recordもすでに存在し、過去のソフトウェア資産や公式ビルドサーバーによるバイナリ配布と言ったエコシステム的な部分を除けばロボット開発に必要なツールはほぼ揃っているという印象を受けました。
Cyber RTはROSでいうノード、ノードレット的な書き方の両方に対応しているようで以下のようなサンプルコードが上がっていました。
Talker/Listener
Talker/ListenerはROSでいうノードに該当する書き方です。
# include "cyber/cyber.h"
# include "cyber/proto/chatter.pb.h"
# include "cyber/time/rate.h"
# include "cyber/time/time.h"
using apollo::cyber::Rate;
using apollo::cyber::Time;
using apollo::cyber::proto::Chatter;
int main(int argc, char *argv[]) {
// init cyber framework
apollo::cyber::Init(argv[0]);
// create talker node
std::shared_ptr<apollo::cyber::Node> 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<apollo::cyber::proto::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;
}
# include "cyber/cyber.h"
# include "cyber/proto/chatter.pb.h"
void MessageCallback(
const std::shared_ptr<apollo::cyber::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::proto::Chatter>(
"channel/chatter", MessageCallback);
apollo::cyber::WaitForShutdown();
return 0;
}
正直ほとんどROSと書き方は変わらないです。
ROS書いたことがある人ならスムーズに実装することができるでしょう。
ちなみにROSでいうtopicはCyber RTではChannelというようです。
Component
ComponentはROSでいうノードレットに該当する書き方です。
# include <memory>
# 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 CommonComponentSample : public Component<Driver, Driver> {
public:
bool Init() override;
bool Proc(const std::shared_ptr<Driver>& msg0,
const std::shared_ptr<Driver>& msg1) override;
};
CYBER_REGISTER_COMPONENT(CommonComponentSample)
# include "cyber/examples/common_component_example/common_component_example.h"
# include "cyber/class_loader/class_loader.h"
# include "cyber/component/component.h"
bool CommonComponentSample::Init() {
AINFO << "Commontest component init";
return true;
}
bool CommonComponentSample::Proc(const std::shared_ptr<Driver>& msg0,
const std::shared_ptr<Driver>& msg1) {
AINFO << "Start common component Proc [" << msg0->msg_id() << "] ["
<< msg1->msg_id() << "]";
return true;
}
非常に素直な書き方でわかりやすいと感じました。
Apolloのndt_localizationやperception周りはComponentで作成されているようです。
やはりこのあたりは速度を出したかったのでしょう。
まとめ
今回はApolloで新規に採用されたROSに変わるフレームワークであるCyber RTの概要を紹介しました。
所感としてはかなりシンプルなフレームワークで覚えやすいと感じました。
今後はこのフレームワークがどのように動いているか等掘り下げて解説できればと思います。