127 {
130 return false;
131 }
133 return false;
134 }
135
138
141 auto apollo_reader_1 =
142 cyber_node_->template CreateReader<InType1>(reader_cfg_1);
143
146
147 auto apollo_blocker_1 =
150
151#ifdef RCLCPP__RCLCPP_HPP_
152 auto ros_publisher_0 =
153 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
154 auto ros_publisher_1 =
155 ros_node_->create_publisher<OutType1>(ros_topic_name_1, 10);
156 ros_publishers_.push_back(std::move(ros_publisher_0));
157 ros_publishers_.push_back(std::move(ros_publisher_1));
158 auto func = [
this, apollo_blocker_1, ros_publisher_0,
159 ros_publisher_1](const std::shared_ptr<InType0> in) {
160#else
161 auto func = [
this, apollo_blocker_1](
const std::shared_ptr<InType0> in) {
162#endif
163 if (!apollo_blocker_1->IsPublishedEmpty()) {
164 auto msg1 = apollo_blocker_1->GetLatestPublishedPtr();
165 auto out_0 = std::make_shared<OutType0>();
166 auto out_1 = std::make_shared<OutType1>();
167 auto in_container =
168 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>{
169 std::make_tuple(in, msg1)};
170 auto out_container =
171 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>{
172 std::make_tuple(out_0, out_1)};
173 this->
ConvertMsg(in_container, out_container);
174#ifdef RCLCPP__RCLCPP_HPP_
175 ros_publisher_0->publish(*out_0);
176 ros_publisher_1->publish(*out_1);
177#endif
178 }
179 };
180 auto apollo_reader_0 =
181 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
184
185 return true;
186}
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
optional string ros_topic_name_1