427 {
430 return false;
431 }
433 return false;
434 }
435
437 std::make_shared<apollo::cyber::proto::RoleAttributes>());
439
441 std::make_shared<apollo::cyber::proto::RoleAttributes>());
443
445 std::make_shared<apollo::cyber::proto::RoleAttributes>());
447
449 std::make_shared<apollo::cyber::proto::RoleAttributes>());
451
456
457 apollo_writer_0_ =
459 apollo_writer_1_ =
461 apollo_writer_2_ =
463 apollo_writer_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 }
std::atomic< bool > init_
std::unique_ptr< apollo::cyber::Node > cyber_node_
std::vector< std::shared_ptr< apollo::cyber::proto::RoleAttributes > > apollo_attrs_
ConverterConf converter_conf_
bool LoadConfig(ConverterConf *config)
optional string apollo_channel_name_2
optional string ros_topic_name_3
optional string ros_topic_name_2
optional string apollo_channel_name_0
optional string apollo_channel_name_3
optional string apollo_channel_name_1
optional string ros_topic_name_0
optional string ros_topic_name_1