55 if (!LoadConfig(&converter_conf_)) {
60 reader_cfg_0.
channel_name = converter_conf_.apollo_channel_name_0();
62 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
64#ifdef RCLCPP__RCLCPP_HPP_
65 auto ros_publisher_0 =
66 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
68 auto func = [
this, ros_publisher_0](
const std::shared_ptr<InType0> in) {
70 auto func = [
this](
const std::shared_ptr<InType0> in) {
72 std::shared_ptr<OutType0> out(
new OutType0);
77 this->ConvertMsg(in_container, out_container);
78 AERROR <<
"out of convert";
79#ifdef RCLCPP__RCLCPP_HPP_
80 ros_publisher_0->publish(*out);
82 AERROR <<
"after ros publish";
84 auto apollo_reader_0 =
85 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
86 apollo_readers_.push_back(std::move(apollo_reader_0));
116 if (!LoadConfig(&converter_conf_)) {
121 reader_cfg_0.
channel_name = converter_conf_.apollo_channel_name_0();
123 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
124 std::string ros_topic_name_1 = converter_conf_.ros_topic_name_1();
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) {
136 auto func = [
this](
const std::shared_ptr<InType0> in) {
138 auto out_0 = std::make_shared<OutType0>();
139 auto out_1 = std::make_shared<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);
151 auto apollo_reader_0 =
152 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
153 apollo_readers_.push_back(std::move(apollo_reader_0));
187 if (!LoadConfig(&converter_conf_)) {
192 reader_cfg_0.
channel_name = converter_conf_.apollo_channel_name_0();
194 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
195 std::string ros_topic_name_1 = converter_conf_.ros_topic_name_1();
196 std::string ros_topic_name_2 = converter_conf_.ros_topic_name_2();
198#ifdef RCLCPP__RCLCPP_HPP_
199 auto ros_publisher_0 =
200 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
201 auto ros_publisher_1 =
202 ros_node_->create_publisher<OutType1>(ros_topic_name_1, 10);
203 auto ros_publisher_2 =
204 ros_node_->create_publisher<OutType2>(ros_topic_name_2, 10);
205 ros_publishers_.push_back(std::move(ros_publisher_0));
206 ros_publishers_.push_back(std::move(ros_publisher_1));
207 ros_publishers_.push_back(std::move(ros_publisher_2));
208 auto func = [
this, ros_publisher_0, ros_publisher_1,
209 ros_publisher_2](
const std::shared_ptr<InType0> in) {
211 auto func = [
this](
const std::shared_ptr<InType0> in) {
213 auto out_0 = std::make_shared<OutType0>();
214 auto out_1 = std::make_shared<OutType1>();
215 auto out_2 = std::make_shared<OutType2>();
220 std::shared_ptr<OutType2>>{
221 std::make_tuple(out_0, out_1, out_2)};
222 this->ConvertMsg(in_container, out_container);
223#ifdef RCLCPP__RCLCPP_HPP_
224 ros_publisher_0->publish(*out_0);
225 ros_publisher_1->publish(*out_1);
226 ros_publisher_2->publish(*out_2);
229 auto apollo_reader_0 =
230 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
231 apollo_readers_.push_back(std::move(apollo_reader_0));
240 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
241 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>>
247 bool Init()
override;
252 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
253 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>&
262 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>>
::Init() {
267 if (!LoadConfig(&converter_conf_)) {
272 reader_cfg_0.
channel_name = converter_conf_.apollo_channel_name_0();
274 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
275 std::string ros_topic_name_1 = converter_conf_.ros_topic_name_1();
276 std::string ros_topic_name_2 = converter_conf_.ros_topic_name_2();
277 std::string ros_topic_name_3 = converter_conf_.ros_topic_name_3();
279#ifdef RCLCPP__RCLCPP_HPP_
280 auto ros_publisher_0 =
281 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
282 auto ros_publisher_1 =
283 ros_node_->create_publisher<OutType1>(ros_topic_name_1, 10);
284 auto ros_publisher_2 =
285 ros_node_->create_publisher<OutType2>(ros_topic_name_2, 10);
286 auto ros_publisher_3 =
287 ros_node_->create_publisher<OutType2>(ros_topic_name_3, 10);
288 ros_publishers_.push_back(std::move(ros_publisher_0));
289 ros_publishers_.push_back(std::move(ros_publisher_1));
290 ros_publishers_.push_back(std::move(ros_publisher_2));
291 ros_publishers_.push_back(std::move(ros_publisher_3));
292 auto func = [
this, ros_publisher_0, ros_publisher_1, ros_publisher_2,
293 ros_publisher_3](
const std::shared_ptr<InType0> in) {
295 auto func = [
this](
const std::shared_ptr<InType0> in) {
297 auto out_0 = std::make_shared<OutType0>();
298 auto out_1 = std::make_shared<OutType1>();
299 auto out_2 = std::make_shared<OutType2>();
300 auto out_3 = std::make_shared<OutType3>();
305 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>{
306 std::make_tuple(out_0, out_1, out_2, out_3)};
307 this->ConvertMsg(in_container, out_container);
308#ifdef RCLCPP__RCLCPP_HPP_
309 ros_publisher_0->publish(*out_0);
310 ros_publisher_1->publish(*out_1);
311 ros_publisher_2->publish(*out_2);
312 ros_publisher_3->publish(*out_2);
315 auto apollo_reader_0 =
316 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
317 apollo_readers_.push_back(std::move(apollo_reader_0));