350 {
353 return false;
354 }
356 return false;
357 }
358
360 std::make_shared<apollo::cyber::proto::RoleAttributes>());
362
364 std::make_shared<apollo::cyber::proto::RoleAttributes>());
366
368 std::make_shared<apollo::cyber::proto::RoleAttributes>());
370
372 std::make_shared<apollo::cyber::proto::RoleAttributes>());
374
377
378 apollo_writer_0_ =
380 apollo_writer_1_ =
382 apollo_writer_2_ =
384 apollo_writer_3_ =
386#ifdef RCLCPP__RCLCPP_HPP_
387 ros_msg_subs_.push_back(
388 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
389 ros_node_, ros_topic_name_0)));
390 ros_msg_subs_.push_back(
391 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
392 ros_node_, ros_topic_name_1)));
393 syncApproximate_ = std::make_shared<
394 message_filters::Synchronizer<approximate_sync_policy>>(
395 approximate_sync_policy(10),
396 *dynamic_cast<message_filters::Subscriber<InType0>*>(
397 ros_msg_subs_[0].get()),
398 *dynamic_cast<message_filters::Subscriber<InType1>*>(
399 ros_msg_subs_[1].get()));
400 syncApproximate_->registerCallback(
402 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>,
403 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
404 std::shared_ptr<OutType2>,
405 std::shared_ptr<OutType3>>>::TopicCallback,
406 this);
407
408 ros_spin_thread_ =
409 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
410#endif
411 return true;
412 }
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 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