52 {
55 return false;
56 }
58 return false;
59 }
60
63
66 auto apollo_reader_1 =
67 cyber_node_->template CreateReader<InType1>(reader_cfg_1);
69
70 auto apollo_blocker_1 =
73#ifdef RCLCPP__RCLCPP_HPP_
74 auto ros_publisher_0 =
75 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
76 ros_publishers_.push_back(std::move(ros_publisher_0));
77 auto func = [
this, ros_publisher_0,
78 apollo_blocker_1](const std::shared_ptr<InType0> in) {
79#else
80 auto func = [
this, apollo_blocker_1](
const std::shared_ptr<InType0> in) {
81#endif
82 auto out = std::make_shared<OutType0>();
83 if (!apollo_blocker_1->IsPublishedEmpty()) {
84 auto msg1 = apollo_blocker_1->GetLatestPublishedPtr();
85 auto in_container =
86 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>{
87 std::make_tuple(in, msg1)};
88 auto out_container =
89 OutputTypes<std::shared_ptr<OutType0>>{std::make_tuple(out)};
91#ifdef RCLCPP__RCLCPP_HPP_
92 ros_publisher_0->publish(*out);
93#endif
94 }
95 };
96 auto apollo_reader_0 =
97 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
100
101 return true;
102}
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_0
optional string apollo_channel_name_1
optional string ros_topic_name_0