34 InputTypes<
std::shared_ptr<InType0>, std::shared_ptr<InType1>,
35 std::shared_ptr<InType2>, std::shared_ptr<InType3>>,
38#ifdef RCLCPP__RCLCPP_HPP_
39 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1,
41 approximate_sync_policy;
42 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
45 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
61 std::make_shared<apollo::cyber::proto::RoleAttributes>();
70 cyber_node_->template CreateWriter<OutType0>(*writer_attrs);
71#ifdef RCLCPP__RCLCPP_HPP_
72 ros_msg_subs_.push_back(
73 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
74 ros_node_, ros_topic_name_0)));
75 ros_msg_subs_.push_back(
76 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
77 ros_node_, ros_topic_name_1)));
78 ros_msg_subs_.push_back(
79 std::move(std::make_shared<message_filters::Subscriber<InType2>>(
80 ros_node_, ros_topic_name_2)));
81 ros_msg_subs_.push_back(
82 std::move(std::make_shared<message_filters::Subscriber<InType3>>(
83 ros_node_, ros_topic_name_3)));
84 syncApproximate_ = std::make_shared<
85 message_filters::Synchronizer<approximate_sync_policy>>(
86 approximate_sync_policy(10),
87 *
dynamic_cast<message_filters::Subscriber<InType0>*
>(
88 ros_msg_subs_[0].get()),
89 *
dynamic_cast<message_filters::Subscriber<InType1>*
>(
90 ros_msg_subs_[1].get()),
91 *
dynamic_cast<message_filters::Subscriber<InType2>*
>(
92 ros_msg_subs_[2].get()),
93 *
dynamic_cast<message_filters::Subscriber<InType3>*
>(
94 ros_msg_subs_[3].get()));
95 syncApproximate_->registerCallback(
97 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
98 std::shared_ptr<InType2>, std::shared_ptr<InType3>>,
99 OutputTypes<std::shared_ptr<OutType0>>>::TopicCallback,
103 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
110 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
111 std::shared_ptr<InType2>, std::shared_ptr<InType3>>& input,
112 OutputTypes<std::shared_ptr<OutType0>>& output) = 0;
114#ifdef RCLCPP__RCLCPP_HPP_
116 void TopicCallback(std::shared_ptr<InType0> ros_msg0,
117 std::shared_ptr<InType1> ros_msg1,
118 std::shared_ptr<InType2> ros_msg2,
119 std::shared_ptr<InType3> ros_msg3) {
120 auto out = std::make_shared<OutType0>();
121 typename InType0::SharedPtr internal_in_prt_0 =
122 std::make_shared<InType0>(*ros_msg0.get());
123 typename InType1::SharedPtr internal_in_prt_1 =
124 std::make_shared<InType1>(*ros_msg1.get());
125 typename InType2::SharedPtr internal_in_prt_2 =
126 std::make_shared<InType2>(*ros_msg2.get());
127 typename InType3::SharedPtr internal_in_prt_3 =
128 std::make_shared<InType3>(*ros_msg3.get());
131 std::shared_ptr<InType2>, std::shared_ptr<InType3>>{
132 std::make_tuple(internal_in_prt_0, internal_in_prt_1,
133 internal_in_prt_2, internal_in_prt_3)};
136 this->
ConvertMsg(in_container, out_container);
137 apollo_writer_0_->Write(out);
145 InputTypes<
std::shared_ptr<InType0>, std::shared_ptr<InType1>,
146 std::shared_ptr<InType2>, std::shared_ptr<InType3>>,
147 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>>
150#ifdef RCLCPP__RCLCPP_HPP_
151 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1,
153 approximate_sync_policy;
154 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
157 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
158 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ =
nullptr;
174 std::make_shared<apollo::cyber::proto::RoleAttributes>());
178 std::make_shared<apollo::cyber::proto::RoleAttributes>());
190#ifdef RCLCPP__RCLCPP_HPP_
191 ros_msg_subs_.push_back(
192 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
193 ros_node_, ros_topic_name_0)));
194 ros_msg_subs_.push_back(
195 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
196 ros_node_, ros_topic_name_1)));
197 ros_msg_subs_.push_back(
198 std::move(std::make_shared<message_filters::Subscriber<InType2>>(
199 ros_node_, ros_topic_name_2)));
200 ros_msg_subs_.push_back(
201 std::move(std::make_shared<message_filters::Subscriber<InType3>>(
202 ros_node_, ros_topic_name_3)));
203 syncApproximate_ = std::make_shared<
204 message_filters::Synchronizer<approximate_sync_policy>>(
205 approximate_sync_policy(10),
206 *
dynamic_cast<message_filters::Subscriber<InType0>*
>(
207 ros_msg_subs_[0].get()),
208 *
dynamic_cast<message_filters::Subscriber<InType1>*
>(
209 ros_msg_subs_[1].get()),
210 *
dynamic_cast<message_filters::Subscriber<InType2>*
>(
211 ros_msg_subs_[2].get()),
212 *
dynamic_cast<message_filters::Subscriber<InType3>*
>(
213 ros_msg_subs_[3].get()));
214 syncApproximate_->registerCallback(
216 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
217 std::shared_ptr<InType2>, std::shared_ptr<InType3>>,
219 std::shared_ptr<OutType1>>>::TopicCallback,
223 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
230 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
231 std::shared_ptr<InType2>, std::shared_ptr<InType3>>& input,
232 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>&
235#ifdef RCLCPP__RCLCPP_HPP_
237 void TopicCallback(std::shared_ptr<InType0> ros_msg0,
238 std::shared_ptr<InType1> ros_msg1,
239 std::shared_ptr<InType2> ros_msg2,
240 std::shared_ptr<InType3> ros_msg3) {
241 auto out_0 = std::make_shared<OutType0>();
242 auto out_1 = std::make_shared<OutType1>();
243 typename InType0::SharedPtr internal_in_prt_0 =
244 std::make_shared<InType0>(*ros_msg0.get());
245 typename InType1::SharedPtr internal_in_prt_1 =
246 std::make_shared<InType1>(*ros_msg1.get());
247 typename InType2::SharedPtr internal_in_prt_2 =
248 std::make_shared<InType2>(*ros_msg2.get());
249 typename InType3::SharedPtr internal_in_prt_3 =
250 std::make_shared<InType3>(*ros_msg3.get());
253 std::shared_ptr<InType2>, std::shared_ptr<InType3>>{
254 std::make_tuple(internal_in_prt_0, internal_in_prt_1,
255 internal_in_prt_2, internal_in_prt_3)};
258 std::make_tuple(out_0, out_1)};
259 this->
ConvertMsg(in_container, out_container);
260 apollo_writer_0_->Write(out_0);
261 apollo_writer_1_->Write(out_1);
270 InputTypes<
std::shared_ptr<InType0>, std::shared_ptr<InType1>,
271 std::shared_ptr<InType2>, std::shared_ptr<InType3>>,
272 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
275#ifdef RCLCPP__RCLCPP_HPP_
276 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1,
278 approximate_sync_policy;
279 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
282 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
283 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ =
nullptr;
284 std::shared_ptr<Writer<OutType2>> apollo_writer_2_ =
nullptr;
300 std::make_shared<apollo::cyber::proto::RoleAttributes>());
304 std::make_shared<apollo::cyber::proto::RoleAttributes>());
308 std::make_shared<apollo::cyber::proto::RoleAttributes>());
322#ifdef RCLCPP__RCLCPP_HPP_
323 ros_msg_subs_.push_back(
324 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
325 ros_node_, ros_topic_name_0)));
326 ros_msg_subs_.push_back(
327 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
328 ros_node_, ros_topic_name_1)));
329 ros_msg_subs_.push_back(
330 std::move(std::make_shared<message_filters::Subscriber<InType2>>(
331 ros_node_, ros_topic_name_2)));
332 ros_msg_subs_.push_back(
333 std::move(std::make_shared<message_filters::Subscriber<InType3>>(
334 ros_node_, ros_topic_name_3)));
335 syncApproximate_ = std::make_shared<
336 message_filters::Synchronizer<approximate_sync_policy>>(
337 approximate_sync_policy(10),
338 *
dynamic_cast<message_filters::Subscriber<InType0>*
>(
339 ros_msg_subs_[0].get()),
340 *
dynamic_cast<message_filters::Subscriber<InType1>*
>(
341 ros_msg_subs_[1].get()),
342 *
dynamic_cast<message_filters::Subscriber<InType2>*
>(
343 ros_msg_subs_[2].get()),
344 *
dynamic_cast<message_filters::Subscriber<InType3>*
>(
345 ros_msg_subs_[3].get()));
346 syncApproximate_->registerCallback(
348 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
349 std::shared_ptr<InType2>, std::shared_ptr<InType3>>,
350 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
351 std::shared_ptr<OutType2>>>::TopicCallback,
355 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
362 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
363 std::shared_ptr<InType2>, std::shared_ptr<InType3>>& input,
364 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
365 std::shared_ptr<OutType2>>& output) = 0;
367#ifdef RCLCPP__RCLCPP_HPP_
369 void TopicCallback(std::shared_ptr<InType0> ros_msg0,
370 std::shared_ptr<InType1> ros_msg1,
371 std::shared_ptr<InType2> ros_msg2,
372 std::shared_ptr<InType3> ros_msg3) {
373 auto out_0 = std::make_shared<OutType0>();
374 auto out_1 = std::make_shared<OutType1>();
375 auto out_2 = std::make_shared<OutType2>();
376 typename InType0::SharedPtr internal_in_prt_0 =
377 std::make_shared<InType0>(*ros_msg0.get());
378 typename InType1::SharedPtr internal_in_prt_1 =
379 std::make_shared<InType1>(*ros_msg1.get());
380 typename InType2::SharedPtr internal_in_prt_2 =
381 std::make_shared<InType2>(*ros_msg2.get());
382 typename InType3::SharedPtr internal_in_prt_3 =
383 std::make_shared<InType3>(*ros_msg3.get());
386 std::shared_ptr<InType2>, std::shared_ptr<InType3>>{
387 std::make_tuple(internal_in_prt_0, internal_in_prt_1,
388 internal_in_prt_2, internal_in_prt_3)};
391 std::shared_ptr<OutType2>>{
392 std::make_tuple(out_0, out_1, out_2)};
393 this->
ConvertMsg(in_container, out_container);
394 apollo_writer_0_->Write(out_0);
395 apollo_writer_1_->Write(out_1);
396 apollo_writer_2_->Write(out_2);
405 InputTypes<
std::shared_ptr<InType0>, std::shared_ptr<InType1>,
406 std::shared_ptr<InType2>, std::shared_ptr<InType3>>,
407 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
408 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>>
411#ifdef RCLCPP__RCLCPP_HPP_
412 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1,
414 approximate_sync_policy;
415 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
418 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
419 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ =
nullptr;
420 std::shared_ptr<Writer<OutType2>> apollo_writer_2_ =
nullptr;
421 std::shared_ptr<Writer<OutType3>> apollo_writer_3_ =
nullptr;
437 std::make_shared<apollo::cyber::proto::RoleAttributes>());
441 std::make_shared<apollo::cyber::proto::RoleAttributes>());
445 std::make_shared<apollo::cyber::proto::RoleAttributes>());
449 std::make_shared<apollo::cyber::proto::RoleAttributes>());
465#ifdef RCLCPP__RCLCPP_HPP_
466 ros_msg_subs_.push_back(
467 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
468 ros_node_, ros_topic_name_0)));
469 ros_msg_subs_.push_back(
470 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
471 ros_node_, ros_topic_name_1)));
472 ros_msg_subs_.push_back(
473 std::move(std::make_shared<message_filters::Subscriber<InType2>>(
474 ros_node_, ros_topic_name_2)));
475 ros_msg_subs_.push_back(
476 std::move(std::make_shared<message_filters::Subscriber<InType3>>(
477 ros_node_, ros_topic_name_3)));
478 syncApproximate_ = std::make_shared<
479 message_filters::Synchronizer<approximate_sync_policy>>(
480 approximate_sync_policy(10),
481 *
dynamic_cast<message_filters::Subscriber<InType0>*
>(
482 ros_msg_subs_[0].get()),
483 *
dynamic_cast<message_filters::Subscriber<InType1>*
>(
484 ros_msg_subs_[1].get()),
485 *
dynamic_cast<message_filters::Subscriber<InType2>*
>(
486 ros_msg_subs_[2].get()),
487 *
dynamic_cast<message_filters::Subscriber<InType3>*
>(
488 ros_msg_subs_[3].get()));
489 syncApproximate_->registerCallback(
491 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
492 std::shared_ptr<InType2>, std::shared_ptr<InType3>>,
493 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
494 std::shared_ptr<OutType2>,
495 std::shared_ptr<OutType3>>>::TopicCallback,
499 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
506 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
507 std::shared_ptr<InType2>, std::shared_ptr<InType3>>& input,
508 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
509 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>&
512#ifdef RCLCPP__RCLCPP_HPP_
514 void TopicCallback(std::shared_ptr<InType0> ros_msg0,
515 std::shared_ptr<InType1> ros_msg1,
516 std::shared_ptr<InType2> ros_msg2,
517 std::shared_ptr<InType3> ros_msg3) {
518 auto out_0 = std::make_shared<OutType0>();
519 auto out_1 = std::make_shared<OutType1>();
520 auto out_2 = std::make_shared<OutType2>();
521 auto out_3 = std::make_shared<OutType3>();
522 typename InType0::SharedPtr internal_in_prt_0 =
523 std::make_shared<InType0>(*ros_msg0.get());
524 typename InType1::SharedPtr internal_in_prt_1 =
525 std::make_shared<InType1>(*ros_msg1.get());
526 typename InType2::SharedPtr internal_in_prt_2 =
527 std::make_shared<InType2>(*ros_msg2.get());
528 typename InType3::SharedPtr internal_in_prt_3 =
529 std::make_shared<InType3>(*ros_msg3.get());
532 std::shared_ptr<InType2>, std::shared_ptr<InType3>>{
533 std::make_tuple(internal_in_prt_0, internal_in_prt_1,
534 internal_in_prt_2, internal_in_prt_3)};
537 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>{
538 std::make_tuple(out_0, out_1, out_2, out_3)};
539 this->
ConvertMsg(in_container, out_container);
540 apollo_writer_0_->Write(out_0);
541 apollo_writer_1_->Write(out_1);
542 apollo_writer_2_->Write(out_2);
543 apollo_writer_3_->Write(out_3);
virtual bool ConvertMsg(const std::shared_ptr< R0 > &ros_msg0, const std::shared_ptr< R1 > &ros_msg1, const std::shared_ptr< R2 > &ros_msg2, const std::shared_ptr< R3 > &ros_msg3, std::shared_ptr< M0 > &apollo_msg0, std::shared_ptr< M1 > &apollo_msg1, std::shared_ptr< M2 > &apollo_msg2, std::shared_ptr< M3 > &apollo_msg3)=0