-
Notifications
You must be signed in to change notification settings - Fork 331
/
manual_composition.cpp
57 lines (48 loc) · 2.25 KB
/
manual_composition.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
// Copyright 2016 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT 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 <memory>
#include "composition/client_component.hpp"
#include "composition/listener_component.hpp"
#include "composition/talker_component.hpp"
#include "composition/server_component.hpp"
#include "rclcpp/rclcpp.hpp"
int main(int argc, char * argv[])
{
// Force flush of the stdout buffer.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
// Initialize any global resources needed by the middleware and the client library.
// This will also parse command line arguments one day (as of Beta 1 they are not used).
// You must call this before using any other part of the ROS system.
// This should be called once per process.
rclcpp::init(argc, argv);
// Create an executor that will be responsible for execution of callbacks for a set of nodes.
// With this version, all callbacks will be called from within this thread (the main one).
rclcpp::executors::SingleThreadedExecutor exec;
rclcpp::NodeOptions options;
// Add some nodes to the executor which provide work for the executor during its "spin" function.
// An example of available work is executing a subscription callback, or a timer callback.
auto talker = std::make_shared<composition::Talker>(options);
exec.add_node(talker);
auto listener = std::make_shared<composition::Listener>(options);
exec.add_node(listener);
auto server = std::make_shared<composition::Server>(options);
exec.add_node(server);
auto client = std::make_shared<composition::Client>(options);
exec.add_node(client);
// spin will block until work comes in, execute work as it becomes available, and keep blocking.
// It will only be interrupted by Ctrl-C.
exec.spin();
rclcpp::shutdown();
return 0;
}