34 InputTypes<
std::shared_ptr<InType0>, std::shared_ptr<InType1>,
35 std::shared_ptr<InType2>>,
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>();
69 cyber_node_->template CreateWriter<OutType0>(*writer_attrs);
70#ifdef RCLCPP__RCLCPP_HPP_
71 ros_msg_subs_.push_back(
72 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
73 ros_node_, ros_topic_name_0)));
74 ros_msg_subs_.push_back(
75 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
76 ros_node_, ros_topic_name_1)));
77 ros_msg_subs_.push_back(
78 std::move(std::make_shared<message_filters::Subscriber<InType2>>(
79 ros_node_, ros_topic_name_2)));
80 syncApproximate_ = std::make_shared<
81 message_filters::Synchronizer<approximate_sync_policy>>(
82 approximate_sync_policy(10),
83 *
dynamic_cast<message_filters::Subscriber<InType0>*
>(
84 ros_msg_subs_[0].get()),
85 *
dynamic_cast<message_filters::Subscriber<InType1>*
>(
86 ros_msg_subs_[1].get()),
87 *
dynamic_cast<message_filters::Subscriber<InType2>*
>(
88 ros_msg_subs_[2].get()));
89 syncApproximate_->registerCallback(
91 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
92 std::shared_ptr<InType2>>,
93 OutputTypes<std::shared_ptr<OutType0>>>::TopicCallback,
97 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
104 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
105 std::shared_ptr<InType2>>& input,
106 OutputTypes<std::shared_ptr<OutType0>>& output) = 0;
108#ifdef RCLCPP__RCLCPP_HPP_
110 void TopicCallback(std::shared_ptr<InType0> ros_msg0,
111 std::shared_ptr<InType1> ros_msg1,
112 std::shared_ptr<InType2> ros_msg2) {
113 auto out = std::make_shared<OutType0>();
114 typename InType0::SharedPtr internal_in_prt_0 =
115 std::make_shared<InType0>(*ros_msg0.get());
116 typename InType1::SharedPtr internal_in_prt_1 =
117 std::make_shared<InType1>(*ros_msg1.get());
118 typename InType2::SharedPtr internal_in_prt_2 =
119 std::make_shared<InType2>(*ros_msg2.get());
122 std::shared_ptr<InType2>>{std::make_tuple(
123 internal_in_prt_0, internal_in_prt_1, internal_in_prt_2)};
126 this->
ConvertMsg(in_container, out_container);
127 apollo_writer_0_->Write(out);
135 InputTypes<
std::shared_ptr<InType0>, std::shared_ptr<InType1>,
136 std::shared_ptr<InType2>>,
137 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>>
140#ifdef RCLCPP__RCLCPP_HPP_
141 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1,
143 approximate_sync_policy;
144 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
147 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
148 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ =
nullptr;
164 std::make_shared<apollo::cyber::proto::RoleAttributes>());
168 std::make_shared<apollo::cyber::proto::RoleAttributes>());
179#ifdef RCLCPP__RCLCPP_HPP_
180 ros_msg_subs_.push_back(
181 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
182 ros_node_, ros_topic_name_0)));
183 ros_msg_subs_.push_back(
184 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
185 ros_node_, ros_topic_name_1)));
186 ros_msg_subs_.push_back(
187 std::move(std::make_shared<message_filters::Subscriber<InType2>>(
188 ros_node_, ros_topic_name_2)));
189 syncApproximate_ = std::make_shared<
190 message_filters::Synchronizer<approximate_sync_policy>>(
191 approximate_sync_policy(10),
192 *
dynamic_cast<message_filters::Subscriber<InType0>*
>(
193 ros_msg_subs_[0].get()),
194 *
dynamic_cast<message_filters::Subscriber<InType1>*
>(
195 ros_msg_subs_[1].get()),
196 *
dynamic_cast<message_filters::Subscriber<InType2>*
>(
197 ros_msg_subs_[2].get()));
198 syncApproximate_->registerCallback(
200 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
201 std::shared_ptr<InType2>>,
203 std::shared_ptr<OutType1>>>::TopicCallback,
207 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
214 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
215 std::shared_ptr<InType2>>& input,
216 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>&
219#ifdef RCLCPP__RCLCPP_HPP_
221 void TopicCallback(std::shared_ptr<InType0> ros_msg0,
222 std::shared_ptr<InType1> ros_msg1,
223 std::shared_ptr<InType2> ros_msg2) {
224 auto out_0 = std::make_shared<OutType0>();
225 auto out_1 = std::make_shared<OutType1>();
226 typename InType0::SharedPtr internal_in_prt_0 =
227 std::make_shared<InType0>(*ros_msg0.get());
228 typename InType1::SharedPtr internal_in_prt_1 =
229 std::make_shared<InType1>(*ros_msg1.get());
230 typename InType2::SharedPtr internal_in_prt_2 =
231 std::make_shared<InType2>(*ros_msg2.get());
234 std::shared_ptr<InType2>>{std::make_tuple(
235 internal_in_prt_0, internal_in_prt_1, internal_in_prt_2)};
238 std::make_tuple(out_0, out_1)};
239 this->
ConvertMsg(in_container, out_container);
240 apollo_writer_0_->Write(out_0);
241 apollo_writer_1_->Write(out_1);
249 InputTypes<
std::shared_ptr<InType0>, std::shared_ptr<InType1>,
250 std::shared_ptr<InType2>>,
251 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
254#ifdef RCLCPP__RCLCPP_HPP_
255 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1,
257 approximate_sync_policy;
258 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
261 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
262 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ =
nullptr;
263 std::shared_ptr<Writer<OutType2>> apollo_writer_2_ =
nullptr;
279 std::make_shared<apollo::cyber::proto::RoleAttributes>());
283 std::make_shared<apollo::cyber::proto::RoleAttributes>());
287 std::make_shared<apollo::cyber::proto::RoleAttributes>());
300#ifdef RCLCPP__RCLCPP_HPP_
301 ros_msg_subs_.push_back(
302 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
303 ros_node_, ros_topic_name_0)));
304 ros_msg_subs_.push_back(
305 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
306 ros_node_, ros_topic_name_1)));
307 ros_msg_subs_.push_back(
308 std::move(std::make_shared<message_filters::Subscriber<InType2>>(
309 ros_node_, ros_topic_name_2)));
310 syncApproximate_ = std::make_shared<
311 message_filters::Synchronizer<approximate_sync_policy>>(
312 approximate_sync_policy(10),
313 *
dynamic_cast<message_filters::Subscriber<InType0>*
>(
314 ros_msg_subs_[0].get()),
315 *
dynamic_cast<message_filters::Subscriber<InType1>*
>(
316 ros_msg_subs_[1].get()),
317 *
dynamic_cast<message_filters::Subscriber<InType2>*
>(
318 ros_msg_subs_[2].get()));
319 syncApproximate_->registerCallback(
321 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
322 std::shared_ptr<InType2>>,
323 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
324 std::shared_ptr<OutType2>>>::TopicCallback,
328 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
335 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
336 std::shared_ptr<InType2>>& input,
337 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
338 std::shared_ptr<OutType2>>& output) = 0;
340#ifdef RCLCPP__RCLCPP_HPP_
342 void TopicCallback(std::shared_ptr<InType0> ros_msg0,
343 std::shared_ptr<InType1> ros_msg1,
344 std::shared_ptr<InType2> ros_msg2) {
345 auto out_0 = std::make_shared<OutType0>();
346 auto out_1 = std::make_shared<OutType1>();
347 auto out_2 = std::make_shared<OutType2>();
348 typename InType0::SharedPtr internal_in_prt_0 =
349 std::make_shared<InType0>(*ros_msg0.get());
350 typename InType1::SharedPtr internal_in_prt_1 =
351 std::make_shared<InType1>(*ros_msg1.get());
352 typename InType2::SharedPtr internal_in_prt_2 =
353 std::make_shared<InType2>(*ros_msg2.get());
356 std::shared_ptr<InType2>>{std::make_tuple(
357 internal_in_prt_0, internal_in_prt_1, internal_in_prt_2)};
360 std::shared_ptr<OutType2>>{
361 std::make_tuple(out_0, out_1, out_2)};
362 this->
ConvertMsg(in_container, out_container);
363 apollo_writer_0_->Write(out_0);
364 apollo_writer_1_->Write(out_1);
365 apollo_writer_2_->Write(out_2);
374 InputTypes<
std::shared_ptr<InType0>, std::shared_ptr<InType1>,
375 std::shared_ptr<InType2>>,
376 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
377 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>>
380#ifdef RCLCPP__RCLCPP_HPP_
381 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1>
382 approximate_sync_policy;
383 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
386 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
387 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ =
nullptr;
388 std::shared_ptr<Writer<OutType2>> apollo_writer_2_ =
nullptr;
389 std::shared_ptr<Writer<OutType3>> apollo_writer_3_ =
nullptr;
405 std::make_shared<apollo::cyber::proto::RoleAttributes>());
409 std::make_shared<apollo::cyber::proto::RoleAttributes>());
413 std::make_shared<apollo::cyber::proto::RoleAttributes>());
417 std::make_shared<apollo::cyber::proto::RoleAttributes>());
432#ifdef RCLCPP__RCLCPP_HPP_
433 ros_msg_subs_.push_back(
434 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
435 ros_node_, ros_topic_name_0)));
436 ros_msg_subs_.push_back(
437 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
438 ros_node_, ros_topic_name_1)));
439 ros_msg_subs_.push_back(
440 std::move(std::make_shared<message_filters::Subscriber<InType2>>(
441 ros_node_, ros_topic_name_2)));
442 syncApproximate_ = std::make_shared<
443 message_filters::Synchronizer<approximate_sync_policy>>(
444 approximate_sync_policy(10),
445 *
dynamic_cast<message_filters::Subscriber<InType0>*
>(
446 ros_msg_subs_[0].get()),
447 *
dynamic_cast<message_filters::Subscriber<InType1>*
>(
448 ros_msg_subs_[1].get()),
449 *
dynamic_cast<message_filters::Subscriber<InType2>*
>(
450 ros_msg_subs_[2].get()));
451 syncApproximate_->registerCallback(
453 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
454 std::shared_ptr<InType2>>,
455 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
456 std::shared_ptr<OutType2>,
457 std::shared_ptr<OutType3>>>::TopicCallback,
461 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
468 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
469 std::shared_ptr<InType2>>& input,
470 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
471 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>&
474#ifdef RCLCPP__RCLCPP_HPP_
476 void TopicCallback(std::shared_ptr<InType0> ros_msg0,
477 std::shared_ptr<InType1> ros_msg1,
478 std::shared_ptr<InType2> ros_msg2) {
479 auto out_0 = std::make_shared<OutType0>();
480 auto out_1 = std::make_shared<OutType1>();
481 auto out_2 = std::make_shared<OutType2>();
482 auto out_3 = std::make_shared<OutType3>();
483 typename InType0::SharedPtr internal_in_prt_0 =
484 std::make_shared<InType0>(*ros_msg0.get());
485 typename InType1::SharedPtr internal_in_prt_1 =
486 std::make_shared<InType1>(*ros_msg1.get());
487 typename InType2::SharedPtr internal_in_prt_2 =
488 std::make_shared<InType1>(*ros_msg2.get());
491 std::shared_ptr<InType2>>{std::make_tuple(
492 internal_in_prt_0, internal_in_prt_1, internal_in_prt_2)};
495 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>{
496 std::make_tuple(out_0, out_1, out_2, out_3)};
497 this->
ConvertMsg(in_container, out_container);
498 apollo_writer_0_->Write(out_0);
499 apollo_writer_1_->Write(out_1);
500 apollo_writer_2_->Write(out_2);
501 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