51 {
54 return false;
55 }
57 return false;
58 }
59
60 auto writer_attrs =
61 std::make_shared<apollo::cyber::proto::RoleAttributes>();
68
69 apollo_writer_0_ =
70 cyber_node_->template CreateWriter<OutType0>(*writer_attrs);
71#ifdef RCLCPP__RCLCPP_HPP_
72 ros_msg_subs_.push_back(
73 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
74 ros_node_, ros_topic_name_0)));
75 ros_msg_subs_.push_back(
76 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
77 ros_node_, ros_topic_name_1)));
78 ros_msg_subs_.push_back(
79 std::move(std::make_shared<message_filters::Subscriber<InType2>>(
80 ros_node_, ros_topic_name_2)));
81 ros_msg_subs_.push_back(
82 std::move(std::make_shared<message_filters::Subscriber<InType3>>(
83 ros_node_, ros_topic_name_3)));
84 syncApproximate_ = std::make_shared<
85 message_filters::Synchronizer<approximate_sync_policy>>(
86 approximate_sync_policy(10),
87 *dynamic_cast<message_filters::Subscriber<InType0>*>(
88 ros_msg_subs_[0].get()),
89 *dynamic_cast<message_filters::Subscriber<InType1>*>(
90 ros_msg_subs_[1].get()),
91 *dynamic_cast<message_filters::Subscriber<InType2>*>(
92 ros_msg_subs_[2].get()),
93 *dynamic_cast<message_filters::Subscriber<InType3>*>(
94 ros_msg_subs_[3].get()));
95 syncApproximate_->registerCallback(
97 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
98 std::shared_ptr<InType2>, std::shared_ptr<InType3>>,
99 OutputTypes<std::shared_ptr<OutType0>>>::TopicCallback,
100 this);
101
102 ros_spin_thread_ =
103 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
104#endif
105 return true;
106 }
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 ros_topic_name_3
optional string ros_topic_name_2
optional string apollo_channel_name_0
optional string ros_topic_name_0
optional string ros_topic_name_1