212 {
215 return false;
216 }
218 return false;
219 }
220
223
226 auto apollo_reader_1 =
227 cyber_node_->template CreateReader<InType1>(reader_cfg_1);
228
229 auto apollo_blocker_1 =
232
236
237#ifdef RCLCPP__RCLCPP_HPP_
238 auto ros_publisher_0 =
239 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
240 auto ros_publisher_1 =
241 ros_node_->create_publisher<OutType1>(ros_topic_name_1, 10);
242 auto ros_publisher_2 =
243 ros_node_->create_publisher<OutType2>(ros_topic_name_2, 10);
244 ros_publishers_.push_back(std::move(ros_publisher_0));
245 ros_publishers_.push_back(std::move(ros_publisher_1));
246 ros_publishers_.push_back(std::move(ros_publisher_2));
247 auto func = [
this, apollo_blocker_1, ros_publisher_0, ros_publisher_1,
248 ros_publisher_2](const std::shared_ptr<InType0> in) {
249#else
250 auto func = [
this, apollo_blocker_1](
const std::shared_ptr<InType0> in) {
251#endif
252 if (!apollo_blocker_1->IsPublishedEmpty()) {
253 auto msg1 = apollo_blocker_1->GetLatestPublishedPtr();
254 auto out_0 = std::make_shared<OutType0>();
255 auto out_1 = std::make_shared<OutType1>();
256 auto out_2 = std::make_shared<OutType2>();
257 auto in_container =
258 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>{
259 std::make_tuple(in, msg1)};
260 auto out_container =
261 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
262 std::shared_ptr<OutType2>>{
263 std::make_tuple(out_0, out_1, out_2)};
264 this->
ConvertMsg(in_container, out_container);
265#ifdef RCLCPP__RCLCPP_HPP_
266 ros_publisher_0->publish(*out_0);
267 ros_publisher_1->publish(*out_1);
268 ros_publisher_2->publish(*out_2);
269#endif
270 }
271 };
272 auto apollo_reader_0 =
273 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
276
277 return true;
278}
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 ros_topic_name_2
optional string apollo_channel_name_0
optional string apollo_channel_name_1
optional string ros_topic_name_0
optional string ros_topic_name_1