48 {
51 return false;
52 }
54 return false;
55 }
56
57 auto writer_attrs =
58 std::make_shared<apollo::cyber::proto::RoleAttributes>();
63
64 apollo_writer_0_ =
65 cyber_node_->template CreateWriter<OutType0>(*writer_attrs);
66#ifdef RCLCPP__RCLCPP_HPP_
67 ros_msg_subs_.push_back(
68 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
69 ros_node_, ros_topic_name_0)));
70 ros_msg_subs_.push_back(
71 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
72 ros_node_, ros_topic_name_1)));
73 syncApproximate_ = std::make_shared<
74 message_filters::Synchronizer<approximate_sync_policy>>(
75 approximate_sync_policy(10),
76 *dynamic_cast<message_filters::Subscriber<InType0>*>(
77 ros_msg_subs_[0].get()),
78 *dynamic_cast<message_filters::Subscriber<InType1>*>(
79 ros_msg_subs_[1].get()));
80 syncApproximate_->registerCallback(
82 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>,
83 OutputTypes<std::shared_ptr<OutType0>>>::TopicCallback,
84 this);
85
86 ros_spin_thread_ =
87 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
88#endif
89 return true;
90 }
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_0
optional string ros_topic_name_0
optional string ros_topic_name_1