Apollo 10.0
自动驾驶开放平台
convert_ros_quadruple.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2024 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
17#ifndef CYBER_ROS_APOLLO_TRIPLE_H_
18#define CYBER_ROS_APOLLO_TRIPLE_H_
19
20#include <memory>
21#include <utility>
22
24
25#include "cyber/cyber.h"
27
28namespace apollo {
29namespace cyber {
30
31template <typename InType0, typename InType1, typename InType2,
32 typename InType3, typename OutType0>
34 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
35 std::shared_ptr<InType2>, std::shared_ptr<InType3>>,
36 OutputTypes<std::shared_ptr<OutType0>>> : public MessageConverter {
37 private:
38#ifdef RCLCPP__RCLCPP_HPP_
39 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1,
40 InType2, InType3>
41 approximate_sync_policy;
42 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
43 syncApproximate_;
44#endif
45 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ = nullptr;
46
47 public:
50
51 bool Init() override {
53 if (!init_.load()) {
54 return false;
55 }
57 return false;
58 }
59
60 auto writer_attrs =
61 std::make_shared<apollo::cyber::proto::RoleAttributes>();
62 writer_attrs->set_channel_name(converter_conf_.apollo_channel_name_0());
63 apollo_attrs_.push_back(writer_attrs);
64 auto ros_topic_name_0 = converter_conf_.ros_topic_name_0();
65 auto ros_topic_name_1 = converter_conf_.ros_topic_name_1();
66 auto ros_topic_name_2 = converter_conf_.ros_topic_name_2();
67 auto ros_topic_name_3 = converter_conf_.ros_topic_name_3();
68
69 apollo_writer_0_ =
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,
100 this);
101
102 ros_spin_thread_ =
103 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
104#endif
105 return true;
106 }
107
108 protected:
109 virtual bool ConvertMsg(
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;
113
114#ifdef RCLCPP__RCLCPP_HPP_
115 private:
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());
129 auto in_container =
130 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
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)};
134 auto out_container =
135 OutputTypes<std::shared_ptr<OutType0>>{std::make_tuple(out)};
136 this->ConvertMsg(in_container, out_container);
137 apollo_writer_0_->Write(out);
138 }
139#endif
140};
141
142template <typename InType0, typename InType1, typename InType2,
143 typename InType3, typename OutType0, typename OutType1>
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>>>
148 : public MessageConverter {
149 private:
150#ifdef RCLCPP__RCLCPP_HPP_
151 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1,
152 InType2, InType3>
153 approximate_sync_policy;
154 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
155 syncApproximate_;
156#endif
157 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ = nullptr;
158 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ = nullptr;
159
160 public:
163
164 bool Init() override {
166 if (!init_.load()) {
167 return false;
168 }
170 return false;
171 }
172
173 apollo_attrs_.push_back(
174 std::make_shared<apollo::cyber::proto::RoleAttributes>());
176
177 apollo_attrs_.push_back(
178 std::make_shared<apollo::cyber::proto::RoleAttributes>());
180
181 auto ros_topic_name_0 = converter_conf_.ros_topic_name_0();
182 auto ros_topic_name_1 = converter_conf_.ros_topic_name_1();
183 auto ros_topic_name_2 = converter_conf_.ros_topic_name_2();
184 auto ros_topic_name_3 = converter_conf_.ros_topic_name_3();
185
186 apollo_writer_0_ =
187 cyber_node_->template CreateWriter<OutType0>(*apollo_attrs_[0]);
188 apollo_writer_1_ =
189 cyber_node_->template CreateWriter<OutType1>(*apollo_attrs_[1]);
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>>,
218 OutputTypes<std::shared_ptr<OutType0>,
219 std::shared_ptr<OutType1>>>::TopicCallback,
220 this);
221
222 ros_spin_thread_ =
223 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
224#endif
225 return true;
226 }
227
228 protected:
229 virtual bool ConvertMsg(
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>>&
233 output) = 0;
234
235#ifdef RCLCPP__RCLCPP_HPP_
236 private:
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());
251 auto in_container =
252 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
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)};
256 auto out_container =
257 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>{
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);
262 }
263#endif
264};
265
266template <typename InType0, typename InType1, typename InType2,
267 typename InType3, typename OutType0, typename OutType1,
268 typename OutType2>
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>,
273 std::shared_ptr<OutType2>>> : public MessageConverter {
274 private:
275#ifdef RCLCPP__RCLCPP_HPP_
276 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1,
277 InType2, InType3>
278 approximate_sync_policy;
279 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
280 syncApproximate_;
281#endif
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;
285
286 public:
289
290 bool Init() override {
292 if (!init_.load()) {
293 return false;
294 }
296 return false;
297 }
298
299 apollo_attrs_.push_back(
300 std::make_shared<apollo::cyber::proto::RoleAttributes>());
302
303 apollo_attrs_.push_back(
304 std::make_shared<apollo::cyber::proto::RoleAttributes>());
306
307 apollo_attrs_.push_back(
308 std::make_shared<apollo::cyber::proto::RoleAttributes>());
310
311 auto ros_topic_name_0 = converter_conf_.ros_topic_name_0();
312 auto ros_topic_name_1 = converter_conf_.ros_topic_name_1();
313 auto ros_topic_name_2 = converter_conf_.ros_topic_name_2();
314 auto ros_topic_name_3 = converter_conf_.ros_topic_name_3();
315
316 apollo_writer_0_ =
317 cyber_node_->template CreateWriter<OutType0>(*apollo_attrs_[0]);
318 apollo_writer_1_ =
319 cyber_node_->template CreateWriter<OutType1>(*apollo_attrs_[1]);
320 apollo_writer_2_ =
321 cyber_node_->template CreateWriter<OutType2>(*apollo_attrs_[2]);
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,
352 this);
353
354 ros_spin_thread_ =
355 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
356#endif
357 return true;
358 }
359
360 protected:
361 virtual bool ConvertMsg(
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;
366
367#ifdef RCLCPP__RCLCPP_HPP_
368 private:
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());
384 auto in_container =
385 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
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)};
389 auto out_container =
390 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
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);
397 }
398#endif
399};
400
401template <typename InType0, typename InType1, typename InType2,
402 typename InType3, typename OutType0, typename OutType1,
403 typename OutType2, typename OutType3>
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>>>
409 : public MessageConverter {
410 private:
411#ifdef RCLCPP__RCLCPP_HPP_
412 typedef message_filters::sync_policies::ApproximateTime<InType0, InType1,
413 InType2, InType3>
414 approximate_sync_policy;
415 std::shared_ptr<message_filters::Synchronizer<approximate_sync_policy>>
416 syncApproximate_;
417#endif
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;
422
423 public:
426
427 bool Init() override {
429 if (!init_.load()) {
430 return false;
431 }
433 return false;
434 }
435
436 apollo_attrs_.push_back(
437 std::make_shared<apollo::cyber::proto::RoleAttributes>());
439
440 apollo_attrs_.push_back(
441 std::make_shared<apollo::cyber::proto::RoleAttributes>());
443
444 apollo_attrs_.push_back(
445 std::make_shared<apollo::cyber::proto::RoleAttributes>());
447
448 apollo_attrs_.push_back(
449 std::make_shared<apollo::cyber::proto::RoleAttributes>());
451
452 auto ros_topic_name_0 = converter_conf_.ros_topic_name_0();
453 auto ros_topic_name_1 = converter_conf_.ros_topic_name_1();
454 auto ros_topic_name_2 = converter_conf_.ros_topic_name_2();
455 auto ros_topic_name_3 = converter_conf_.ros_topic_name_3();
456
457 apollo_writer_0_ =
458 cyber_node_->template CreateWriter<OutType0>(*apollo_attrs_[0]);
459 apollo_writer_1_ =
460 cyber_node_->template CreateWriter<OutType1>(*apollo_attrs_[1]);
461 apollo_writer_2_ =
462 cyber_node_->template CreateWriter<OutType2>(*apollo_attrs_[2]);
463 apollo_writer_3_ =
464 cyber_node_->template CreateWriter<OutType3>(*apollo_attrs_[3]);
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,
496 this);
497
498 ros_spin_thread_ =
499 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
500#endif
501 return true;
502 }
503
504 protected:
505 virtual bool ConvertMsg(
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>>&
510 output) = 0;
511
512#ifdef RCLCPP__RCLCPP_HPP_
513 private:
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());
530 auto in_container =
531 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
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)};
535 auto out_container =
536 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
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);
544 }
545#endif
546};
547
548} // namespace cyber
549} // namespace apollo
550
551#endif // CYBER_APOLLO_ROS_MESSAGE_CONVERTER_H_
std::unique_ptr< apollo::cyber::Node > cyber_node_
std::vector< std::shared_ptr< apollo::cyber::proto::RoleAttributes > > apollo_attrs_
bool LoadConfig(ConverterConf *config)
virtual bool ConvertMsg(InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > &output)=0
virtual bool ConvertMsg(InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 >, std::shared_ptr< OutType3 > > &output)=0
virtual bool ConvertMsg(InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > > &input, OutputTypes< std::shared_ptr< OutType0 > > &output)=0
virtual bool ConvertMsg(InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 > > &output)=0
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
class register implement
Definition arena_queue.h:37
Definition future.h:29