57 {
60 return false;
61 }
63 return false;
64 }
65
68
71 auto apollo_reader_1 =
72 cyber_node_->template CreateReader<InType1>(reader_cfg_1);
73
76 auto apollo_reader_2 =
77 cyber_node_->template CreateReader<InType2>(reader_cfg_2);
78
80
81 auto apollo_blocker_1 =
84 auto apollo_blocker_2 =
87#ifdef RCLCPP__RCLCPP_HPP_
88 auto ros_publisher_0 =
89 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
90 ros_publishers_.push_back(std::move(ros_publisher_0));
91 auto func = [
this, ros_publisher_0, apollo_blocker_1,
92 apollo_blocker_2](const std::shared_ptr<InType0> in) {
93#else
94 auto func = [
this, apollo_blocker_1,
95 apollo_blocker_2](const std::shared_ptr<InType0> in) {
96#endif
97 auto out = std::make_shared<OutType0>();
98 if (!apollo_blocker_1->IsPublishedEmpty() &&
99 !apollo_blocker_2->IsPublishedEmpty()) {
100 auto msg1 = apollo_blocker_1->GetLatestPublishedPtr();
101 auto msg2 = apollo_blocker_2->GetLatestPublishedPtr();
102 auto in_container =
103 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
104 std::shared_ptr<InType2>>{std::make_tuple(in, msg1, msg2)};
105 auto out_container =
106 OutputTypes<std::shared_ptr<OutType0>>{std::make_tuple(out)};
107 this->
ConvertMsg(in_container, out_container);
108#ifdef RCLCPP__RCLCPP_HPP_
109 ros_publisher_0->publish(*out);
110#endif
111 }
112 };
113 auto apollo_reader_0 =
114 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
118
119 return true;
120}
std::atomic< bool > init_
std::unique_ptr< apollo::cyber::Node > cyber_node_
std::vector< std::shared_ptr< apollo::cyber::ReaderBase > > apollo_readers_
ConverterConf converter_conf_
bool LoadConfig(ConverterConf *config)
static const std::shared_ptr< BlockerManager > & Instance()
optional string apollo_channel_name_2
optional string apollo_channel_name_0
optional string apollo_channel_name_1
optional string ros_topic_name_0