111 {
114 return false;
115 }
117 return false;
118 }
119
122
125
126#ifdef RCLCPP__RCLCPP_HPP_
127 auto ros_publisher_0 =
128 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
129 auto ros_publisher_1 =
130 ros_node_->create_publisher<OutType1>(ros_topic_name_1, 10);
131 ros_publishers_.push_back(std::move(ros_publisher_0));
132 ros_publishers_.push_back(std::move(ros_publisher_1));
133 auto func = [
this, ros_publisher_0,
134 ros_publisher_1](const std::shared_ptr<InType0> in) {
135#else
136 auto func = [
this](
const std::shared_ptr<InType0> in) {
137#endif
138 auto out_0 = std::make_shared<OutType0>();
139 auto out_1 = std::make_shared<OutType1>();
140 auto in_container =
141 InputTypes<std::shared_ptr<InType0>>{std::make_tuple(in)};
142 auto out_container =
143 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>{
144 std::make_tuple(out_0, out_1)};
145 this->
ConvertMsg(in_container, out_container);
146#ifdef RCLCPP__RCLCPP_HPP_
147 ros_publisher_0->publish(*out_0);
148 ros_publisher_1->publish(*out_1);
149#endif
150 };
151 auto apollo_reader_0 =
152 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
154
155 return true;
156}
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)
optional string apollo_channel_name_0
optional string ros_topic_name_0
optional string ros_topic_name_1