57 if (!LoadConfig(&converter_conf_)) {
62 reader_cfg_0.
channel_name = converter_conf_.apollo_channel_name_0();
65 reader_cfg_1.
channel_name = converter_conf_.apollo_channel_name_1();
66 auto apollo_reader_1 =
67 cyber_node_->template CreateReader<InType1>(reader_cfg_1);
68 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
70 auto apollo_blocker_1 =
73#ifdef RCLCPP__RCLCPP_HPP_
74 auto ros_publisher_0 =
75 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
76 ros_publishers_.push_back(std::move(ros_publisher_0));
77 auto func = [
this, ros_publisher_0,
78 apollo_blocker_1](
const std::shared_ptr<InType0> in) {
80 auto func = [
this, apollo_blocker_1](
const std::shared_ptr<InType0> in) {
82 auto out = std::make_shared<OutType0>();
83 if (!apollo_blocker_1->IsPublishedEmpty()) {
84 auto msg1 = apollo_blocker_1->GetLatestPublishedPtr();
87 std::make_tuple(in, msg1)};
90 this->ConvertMsg(in_container, out_container);
91#ifdef RCLCPP__RCLCPP_HPP_
92 ros_publisher_0->publish(*out);
96 auto apollo_reader_0 =
97 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
98 apollo_readers_.push_back(std::move(apollo_reader_0));
99 apollo_readers_.push_back(std::move(apollo_reader_1));
132 if (!LoadConfig(&converter_conf_)) {
137 reader_cfg_0.
channel_name = converter_conf_.apollo_channel_name_0();
140 reader_cfg_1.
channel_name = converter_conf_.apollo_channel_name_1();
141 auto apollo_reader_1 =
142 cyber_node_->template CreateReader<InType1>(reader_cfg_1);
144 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
145 std::string ros_topic_name_1 = converter_conf_.ros_topic_name_1();
147 auto apollo_blocker_1 =
151#ifdef RCLCPP__RCLCPP_HPP_
152 auto ros_publisher_0 =
153 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
154 auto ros_publisher_1 =
155 ros_node_->create_publisher<OutType1>(ros_topic_name_1, 10);
156 ros_publishers_.push_back(std::move(ros_publisher_0));
157 ros_publishers_.push_back(std::move(ros_publisher_1));
158 auto func = [
this, apollo_blocker_1, ros_publisher_0,
159 ros_publisher_1](
const std::shared_ptr<InType0> in) {
161 auto func = [
this, apollo_blocker_1](
const std::shared_ptr<InType0> in) {
163 if (!apollo_blocker_1->IsPublishedEmpty()) {
164 auto msg1 = apollo_blocker_1->GetLatestPublishedPtr();
165 auto out_0 = std::make_shared<OutType0>();
166 auto out_1 = std::make_shared<OutType1>();
169 std::make_tuple(in, msg1)};
172 std::make_tuple(out_0, out_1)};
173 this->ConvertMsg(in_container, out_container);
174#ifdef RCLCPP__RCLCPP_HPP_
175 ros_publisher_0->publish(*out_0);
176 ros_publisher_1->publish(*out_1);
180 auto apollo_reader_0 =
181 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
182 apollo_readers_.push_back(std::move(apollo_reader_0));
183 apollo_readers_.push_back(std::move(apollo_reader_1));
191 InputTypes<
std::shared_ptr<InType0>, std::shared_ptr<InType1>>,
192 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
198 bool Init()
override;
202 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>& input,
203 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
204 std::shared_ptr<OutType2>>& output) = 0;
217 if (!LoadConfig(&converter_conf_)) {
222 reader_cfg_0.
channel_name = converter_conf_.apollo_channel_name_0();
225 reader_cfg_1.
channel_name = converter_conf_.apollo_channel_name_1();
226 auto apollo_reader_1 =
227 cyber_node_->template CreateReader<InType1>(reader_cfg_1);
229 auto apollo_blocker_1 =
233 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
234 std::string ros_topic_name_1 = converter_conf_.ros_topic_name_1();
235 std::string ros_topic_name_2 = converter_conf_.ros_topic_name_2();
237#ifdef RCLCPP__RCLCPP_HPP_
238 auto ros_publisher_0 =
239 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
240 auto ros_publisher_1 =
241 ros_node_->create_publisher<OutType1>(ros_topic_name_1, 10);
242 auto ros_publisher_2 =
243 ros_node_->create_publisher<OutType2>(ros_topic_name_2, 10);
244 ros_publishers_.push_back(std::move(ros_publisher_0));
245 ros_publishers_.push_back(std::move(ros_publisher_1));
246 ros_publishers_.push_back(std::move(ros_publisher_2));
247 auto func = [
this, apollo_blocker_1, ros_publisher_0, ros_publisher_1,
248 ros_publisher_2](
const std::shared_ptr<InType0> in) {
250 auto func = [
this, apollo_blocker_1](
const std::shared_ptr<InType0> in) {
252 if (!apollo_blocker_1->IsPublishedEmpty()) {
253 auto msg1 = apollo_blocker_1->GetLatestPublishedPtr();
254 auto out_0 = std::make_shared<OutType0>();
255 auto out_1 = std::make_shared<OutType1>();
256 auto out_2 = std::make_shared<OutType2>();
259 std::make_tuple(in, msg1)};
262 std::shared_ptr<OutType2>>{
263 std::make_tuple(out_0, out_1, out_2)};
264 this->ConvertMsg(in_container, out_container);
265#ifdef RCLCPP__RCLCPP_HPP_
266 ros_publisher_0->publish(*out_0);
267 ros_publisher_1->publish(*out_1);
268 ros_publisher_2->publish(*out_2);
272 auto apollo_reader_0 =
273 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
274 apollo_readers_.push_back(std::move(apollo_reader_0));
275 apollo_readers_.push_back(std::move(apollo_reader_1));
283 InputTypes<
std::shared_ptr<InType0>, std::shared_ptr<InType1>>,
284 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
285 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>>
291 bool Init()
override;
295 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>& input,
296 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
297 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>&
306 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>>
::Init() {
311 if (!LoadConfig(&converter_conf_)) {
316 reader_cfg_0.
channel_name = converter_conf_.apollo_channel_name_0();
319 reader_cfg_1.
channel_name = converter_conf_.apollo_channel_name_1();
320 auto apollo_reader_1 =
321 cyber_node_->template CreateReader<InType1>(reader_cfg_1);
323 auto apollo_blocker_1 =
327 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
328 std::string ros_topic_name_1 = converter_conf_.ros_topic_name_1();
329 std::string ros_topic_name_2 = converter_conf_.ros_topic_name_2();
330 std::string ros_topic_name_3 = converter_conf_.ros_topic_name_3();
332#ifdef RCLCPP__RCLCPP_HPP_
333 auto ros_publisher_0 =
334 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
335 auto ros_publisher_1 =
336 ros_node_->create_publisher<OutType1>(ros_topic_name_1, 10);
337 auto ros_publisher_2 =
338 ros_node_->create_publisher<OutType2>(ros_topic_name_2, 10);
339 auto ros_publisher_3 =
340 ros_node_->create_publisher<OutType2>(ros_topic_name_3, 10);
341 ros_publishers_.push_back(std::move(ros_publisher_0));
342 ros_publishers_.push_back(std::move(ros_publisher_1));
343 ros_publishers_.push_back(std::move(ros_publisher_2));
344 ros_publishers_.push_back(std::move(ros_publisher_3));
345 auto func = [
this, apollo_blocker_1, ros_publisher_0, ros_publisher_1,
347 ros_publisher_3](
const std::shared_ptr<InType0> in) {
349 auto func = [
this, apollo_blocker_1](
const std::shared_ptr<InType0> in) {
351 if (!apollo_blocker_1->IsPublishedEmpty()) {
352 auto msg1 = apollo_blocker_1->GetLatestPublishedPtr();
353 auto out_0 = std::make_shared<OutType0>();
354 auto out_1 = std::make_shared<OutType1>();
355 auto out_2 = std::make_shared<OutType2>();
356 auto out_3 = std::make_shared<OutType3>();
359 std::make_tuple(in, msg1)};
362 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>{
363 std::make_tuple(out_0, out_1, out_2, out_3)};
364 this->ConvertMsg(in_container, out_container);
365#ifdef RCLCPP__RCLCPP_HPP_
366 ros_publisher_0->publish(*out_0);
367 ros_publisher_1->publish(*out_1);
368 ros_publisher_2->publish(*out_2);
369 ros_publisher_3->publish(*out_2);
373 auto apollo_reader_0 =
374 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
375 apollo_readers_.push_back(std::move(apollo_reader_0));
376 apollo_readers_.push_back(std::move(apollo_reader_1));