33 InputTypes<
std::shared_ptr<InType0>, std::shared_ptr<InType1>>,
36#ifdef RCLCPP__RCLCPP_HPP_
37 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1>
38 approximate_sync_policy;
39 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
42 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
58 std::make_shared<apollo::cyber::proto::RoleAttributes>();
65 cyber_node_->template CreateWriter<OutType0>(*writer_attrs);
66#ifdef RCLCPP__RCLCPP_HPP_
67 ros_msg_subs_.push_back(
68 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
69 ros_node_, ros_topic_name_0)));
70 ros_msg_subs_.push_back(
71 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
72 ros_node_, ros_topic_name_1)));
73 syncApproximate_ = std::make_shared<
74 message_filters::Synchronizer<approximate_sync_policy>>(
75 approximate_sync_policy(10),
76 *
dynamic_cast<message_filters::Subscriber<InType0>*
>(
77 ros_msg_subs_[0].get()),
78 *
dynamic_cast<message_filters::Subscriber<InType1>*
>(
79 ros_msg_subs_[1].get()));
80 syncApproximate_->registerCallback(
82 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>,
83 OutputTypes<std::shared_ptr<OutType0>>>::TopicCallback,
87 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
94 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>& input,
95 OutputTypes<std::shared_ptr<OutType0>>& output) = 0;
97#ifdef RCLCPP__RCLCPP_HPP_
99 void TopicCallback(std::shared_ptr<InType0> ros_msg0,
100 std::shared_ptr<InType1> ros_msg1) {
101 auto out = std::make_shared<OutType0>();
102 typename InType0::SharedPtr internal_in_prt_0 =
103 std::make_shared<InType0>(*ros_msg0.get());
104 typename InType1::SharedPtr internal_in_prt_1 =
105 std::make_shared<InType1>(*ros_msg1.get());
108 std::make_tuple(internal_in_prt_0, internal_in_prt_1)};
111 this->
ConvertMsg(in_container, out_container);
112 apollo_writer_0_->Write(out);
120 InputTypes<
std::shared_ptr<InType0>, std::shared_ptr<InType1>>,
121 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>>
124#ifdef RCLCPP__RCLCPP_HPP_
125 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1>
126 approximate_sync_policy;
127 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
130 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
131 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ =
nullptr;
147 std::make_shared<apollo::cyber::proto::RoleAttributes>());
151 std::make_shared<apollo::cyber::proto::RoleAttributes>());
161#ifdef RCLCPP__RCLCPP_HPP_
162 ros_msg_subs_.push_back(
163 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
164 ros_node_, ros_topic_name_0)));
165 ros_msg_subs_.push_back(
166 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
167 ros_node_, ros_topic_name_1)));
168 syncApproximate_ = std::make_shared<
169 message_filters::Synchronizer<approximate_sync_policy>>(
170 approximate_sync_policy(10),
171 *
dynamic_cast<message_filters::Subscriber<InType0>*
>(
172 ros_msg_subs_[0].get()),
173 *
dynamic_cast<message_filters::Subscriber<InType1>*
>(
174 ros_msg_subs_[1].get()));
175 syncApproximate_->registerCallback(
177 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>,
179 std::shared_ptr<OutType1>>>::TopicCallback,
183 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
190 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>& input,
191 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>&
194#ifdef RCLCPP__RCLCPP_HPP_
196 void TopicCallback(std::shared_ptr<InType0> ros_msg0,
197 std::shared_ptr<InType1> ros_msg1) {
198 auto out_0 = std::make_shared<OutType0>();
199 auto out_1 = std::make_shared<OutType1>();
200 typename InType0::SharedPtr internal_in_prt_0 =
201 std::make_shared<InType0>(*ros_msg0.get());
202 typename InType1::SharedPtr internal_in_prt_1 =
203 std::make_shared<InType1>(*ros_msg1.get());
206 std::make_tuple(internal_in_prt_0, internal_in_prt_1)};
209 std::make_tuple(out_0, out_1)};
210 this->
ConvertMsg(in_container, out_container);
211 apollo_writer_0_->Write(out_0);
212 apollo_writer_1_->Write(out_1);
220 InputTypes<
std::shared_ptr<InType0>, std::shared_ptr<InType1>>,
221 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
224#ifdef RCLCPP__RCLCPP_HPP_
225 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1>
226 approximate_sync_policy;
227 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
230 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
231 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ =
nullptr;
232 std::shared_ptr<Writer<OutType2>> apollo_writer_2_ =
nullptr;
248 std::make_shared<apollo::cyber::proto::RoleAttributes>());
252 std::make_shared<apollo::cyber::proto::RoleAttributes>());
256 std::make_shared<apollo::cyber::proto::RoleAttributes>());
268#ifdef RCLCPP__RCLCPP_HPP_
269 ros_msg_subs_.push_back(
270 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
271 ros_node_, ros_topic_name_0)));
272 ros_msg_subs_.push_back(
273 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
274 ros_node_, ros_topic_name_1)));
275 syncApproximate_ = std::make_shared<
276 message_filters::Synchronizer<approximate_sync_policy>>(
277 approximate_sync_policy(10),
278 *
dynamic_cast<message_filters::Subscriber<InType0>*
>(
279 ros_msg_subs_[0].get()),
280 *
dynamic_cast<message_filters::Subscriber<InType1>*
>(
281 ros_msg_subs_[1].get()));
282 syncApproximate_->registerCallback(
284 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>,
285 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
286 std::shared_ptr<OutType2>>>::TopicCallback,
290 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
297 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>& input,
298 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
299 std::shared_ptr<OutType2>>& output) = 0;
301#ifdef RCLCPP__RCLCPP_HPP_
303 void TopicCallback(std::shared_ptr<InType0> ros_msg0,
304 std::shared_ptr<InType1> ros_msg1) {
305 auto out_0 = std::make_shared<OutType0>();
306 auto out_1 = std::make_shared<OutType1>();
307 auto out_2 = std::make_shared<OutType2>();
308 typename InType0::SharedPtr internal_in_prt_0 =
309 std::make_shared<InType0>(*ros_msg0.get());
310 typename InType1::SharedPtr internal_in_prt_1 =
311 std::make_shared<InType1>(*ros_msg1.get());
314 std::make_tuple(internal_in_prt_0, internal_in_prt_1)};
317 std::shared_ptr<OutType2>>{
318 std::make_tuple(out_0, out_1, out_2)};
319 this->
ConvertMsg(in_container, out_container);
320 apollo_writer_0_->Write(out_0);
321 apollo_writer_1_->Write(out_1);
322 apollo_writer_2_->Write(out_2);
330 InputTypes<
std::shared_ptr<InType0>, std::shared_ptr<InType1>>,
331 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
332 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>>
335#ifdef RCLCPP__RCLCPP_HPP_
336 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1>
337 approximate_sync_policy;
338 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
341 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
342 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ =
nullptr;
343 std::shared_ptr<Writer<OutType2>> apollo_writer_2_ =
nullptr;
344 std::shared_ptr<Writer<OutType3>> apollo_writer_3_ =
nullptr;
360 std::make_shared<apollo::cyber::proto::RoleAttributes>());
364 std::make_shared<apollo::cyber::proto::RoleAttributes>());
368 std::make_shared<apollo::cyber::proto::RoleAttributes>());
372 std::make_shared<apollo::cyber::proto::RoleAttributes>());
386#ifdef RCLCPP__RCLCPP_HPP_
387 ros_msg_subs_.push_back(
388 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
389 ros_node_, ros_topic_name_0)));
390 ros_msg_subs_.push_back(
391 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
392 ros_node_, ros_topic_name_1)));
393 syncApproximate_ = std::make_shared<
394 message_filters::Synchronizer<approximate_sync_policy>>(
395 approximate_sync_policy(10),
396 *
dynamic_cast<message_filters::Subscriber<InType0>*
>(
397 ros_msg_subs_[0].get()),
398 *
dynamic_cast<message_filters::Subscriber<InType1>*
>(
399 ros_msg_subs_[1].get()));
400 syncApproximate_->registerCallback(
402 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>,
403 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
404 std::shared_ptr<OutType2>,
405 std::shared_ptr<OutType3>>>::TopicCallback,
409 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
416 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>& input,
417 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
418 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>&
421#ifdef RCLCPP__RCLCPP_HPP_
423 void TopicCallback(std::shared_ptr<InType0> ros_msg0,
424 std::shared_ptr<InType1> ros_msg1) {
425 auto out_0 = std::make_shared<OutType0>();
426 auto out_1 = std::make_shared<OutType1>();
427 auto out_2 = std::make_shared<OutType2>();
428 auto out_3 = std::make_shared<OutType3>();
429 typename InType0::SharedPtr internal_in_prt_0 =
430 std::make_shared<InType0>(*ros_msg0.get());
431 typename InType1::SharedPtr internal_in_prt_1 =
432 std::make_shared<InType1>(*ros_msg1.get());
435 std::make_tuple(internal_in_prt_0, internal_in_prt_1)};
438 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>{
439 std::make_tuple(out_0, out_1, out_2, out_3)};
440 this->
ConvertMsg(in_container, out_container);
441 apollo_writer_0_->Write(out_0);
442 apollo_writer_1_->Write(out_1);
443 apollo_writer_2_->Write(out_2);
444 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