events_service.h
Go to the documentation of this file.
1 // SkyWay WebRTC Gateway Caller(以下Caller)を利用して、
2 // WebRTC Gateway内で発生したイベントを取得するためのクラス
3 // Callerから帰ってきたイベントを通知するためのROS Serviceを提供する
4 //
5 // クライアントから要求がくると、まず終了処理中ではないか確認を行う。
6 // 終了処理中でなければ、オブザーバに対して通知を行う。
7 // 通知を受けたオブザーバーは、Callerからイベントを取得して戻り値として返す。
8 // 戻り値を受け取ったらServiceとして返す。
9 
10 // TODO: unit test
11 
12 #ifndef SKYWAY_EVENT_SERVICE_H
13 #define SKYWAY_EVENT_SERVICE_H
14 
15 #include <fruit/fruit.h>
16 #include <ros/ros.h>
17 #include <skyway/SkyWayEvents.h>
18 
19 #include <functional>
20 #include <string>
21 
23  public:
24  virtual ~EventsService() = default;
25  virtual void Shutdown() {}
26 };
27 
29  private:
32  std::string name_;
33  std::function<std::string()> callback_;
34  bool is_running_ = true;
35 
36  // エンドユーザプログラムから与えられたメッセージをCallerに与え、レスポンスをServiceのClientに返す
37  bool callback(skyway::SkyWayEvents::Request &req,
38  skyway::SkyWayEvents::Response &res);
39 
40  public:
41  // コンストラクタでは、サービス名とCaller内のSender Objectを受け取る
42  INJECT(EventsServiceImpl(ASSISTED(std::string) name,
43  ASSISTED(std::function<std::string()>) callback));
45  virtual void Shutdown() override {
46  is_running_ = false;
47  service_.shutdown();
48  }
49 };
50 
51 using EventsServiceFactory = std::function<std::unique_ptr<EventsService>(
52  std::string, std::function<std::string()>)>;
53 
54 fruit::Component<EventsServiceFactory> getEventsServiceComponent();
55 
56 #endif
fruit::Component< EventsServiceFactory > getEventsServiceComponent()
std::function< std::unique_ptr< EventsService >(std::string, std::function< std::string()>)> EventsServiceFactory
ros::ServiceServer service_
std::string name_
virtual void Shutdown()
std::function< std::string()> callback_
virtual ~EventsService()=default
ros::NodeHandle nh_
virtual void Shutdown() override


skyway
Author(s): Toshiya Nakakura
autogenerated on Sat Apr 15 2023 02:08:21