Apollo 10.0
自动驾驶开放平台
convert_apollo_single.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2024 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
17#ifndef CYBER_APOLLO_ROS_SINGLE_H_
18#define CYBER_APOLLO_ROS_SINGLE_H_
19
20#include <memory>
21#include <string>
22#include <utility>
23
25
26#include "cyber/cyber.h"
29
30namespace apollo {
31namespace cyber {
32
33template <typename InType0, typename OutType0>
34class ApolloRosMessageConverter<InputTypes<std::shared_ptr<InType0>>,
35 OutputTypes<std::shared_ptr<OutType0>>>
36 : public MessageConverter {
37 public:
40
41 bool Init() override;
42
43 protected:
44 virtual bool ConvertMsg(InputTypes<std::shared_ptr<InType0>>& input,
45 OutputTypes<std::shared_ptr<OutType0>>& output) = 0;
46};
47
48template <typename InType0, typename OutType0>
52 if (!init_.load()) {
53 return false;
54 }
55 if (!LoadConfig(&converter_conf_)) {
56 return false;
57 }
58
59 apollo::cyber::ReaderConfig reader_cfg_0;
60 reader_cfg_0.channel_name = converter_conf_.apollo_channel_name_0();
61
62 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
63
64#ifdef RCLCPP__RCLCPP_HPP_
65 auto ros_publisher_0 =
66 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
67 // ros_publishers_.push_back(ros_publisher_0);
68 auto func = [this, ros_publisher_0](const std::shared_ptr<InType0> in) {
69#else
70 auto func = [this](const std::shared_ptr<InType0> in) {
71#endif
72 std::shared_ptr<OutType0> out(new OutType0);
73 auto in_container =
74 InputTypes<std::shared_ptr<InType0>>{std::make_tuple(in)};
75 auto out_container =
76 OutputTypes<std::shared_ptr<OutType0>>{std::make_tuple(out)};
77 this->ConvertMsg(in_container, out_container);
78 AERROR << "out of convert";
79#ifdef RCLCPP__RCLCPP_HPP_
80 ros_publisher_0->publish(*out);
81#endif
82 AERROR << "after ros publish";
83 };
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));
87
88 return true;
89}
90
91template <typename InType0, typename OutType0, typename OutType1>
93 InputTypes<std::shared_ptr<InType0>>,
94 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>>
95 : public MessageConverter {
96 public:
99
100 bool Init() override;
101
102 protected:
103 virtual bool ConvertMsg(InputTypes<std::shared_ptr<InType0>>& input,
104 OutputTypes<std::shared_ptr<OutType0>,
105 std::shared_ptr<OutType1>>& output) = 0;
106};
107
108template <typename InType0, typename OutType0, typename OutType1>
111 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>>::Init() {
113 if (!init_.load()) {
114 return false;
115 }
116 if (!LoadConfig(&converter_conf_)) {
117 return false;
118 }
119
120 apollo::cyber::ReaderConfig reader_cfg_0;
121 reader_cfg_0.channel_name = converter_conf_.apollo_channel_name_0();
122
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();
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);
153 apollo_readers_.push_back(std::move(apollo_reader_0));
154
155 return true;
156}
157
158template <typename InType0, typename OutType0, typename OutType1,
159 typename OutType2>
161 InputTypes<std::shared_ptr<InType0>>,
162 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
163 std::shared_ptr<OutType2>>> : public MessageConverter {
164 public:
167
168 bool Init() override;
169
170 protected:
171 virtual bool ConvertMsg(
172 InputTypes<std::shared_ptr<InType0>>& input,
173 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
174 std::shared_ptr<OutType2>>& output) = 0;
175};
176
177template <typename InType0, typename OutType0, typename OutType1,
178 typename OutType2>
181 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
182 std::shared_ptr<OutType2>>>::Init() {
184 if (!init_.load()) {
185 return false;
186 }
187 if (!LoadConfig(&converter_conf_)) {
188 return false;
189 }
190
191 apollo::cyber::ReaderConfig reader_cfg_0;
192 reader_cfg_0.channel_name = converter_conf_.apollo_channel_name_0();
193
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();
197
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) {
210#else
211 auto func = [this](const std::shared_ptr<InType0> in) {
212#endif
213 auto out_0 = std::make_shared<OutType0>();
214 auto out_1 = std::make_shared<OutType1>();
215 auto out_2 = std::make_shared<OutType2>();
216 auto in_container =
217 InputTypes<std::shared_ptr<InType0>>{std::make_tuple(in)};
218 auto out_container =
219 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
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);
227#endif
228 };
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));
232
233 return true;
234}
235
236template <typename InType0, typename OutType0, typename OutType1,
237 typename OutType2, typename OutType3>
239 InputTypes<std::shared_ptr<InType0>>,
240 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
241 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>>
242 : public MessageConverter {
243 public:
246
247 bool Init() override;
248
249 protected:
250 virtual bool ConvertMsg(
251 InputTypes<std::shared_ptr<InType0>>& input,
252 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
253 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>&
254 output) = 0;
255};
256
257template <typename InType0, typename OutType0, typename OutType1,
258 typename OutType2, typename OutType3>
261 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
262 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>>::Init() {
264 if (!init_.load()) {
265 return false;
266 }
267 if (!LoadConfig(&converter_conf_)) {
268 return false;
269 }
270
271 apollo::cyber::ReaderConfig reader_cfg_0;
272 reader_cfg_0.channel_name = converter_conf_.apollo_channel_name_0();
273
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();
278
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) {
294#else
295 auto func = [this](const std::shared_ptr<InType0> in) {
296#endif
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>();
301 auto in_container =
302 InputTypes<std::shared_ptr<InType0>>{std::make_tuple(in)};
303 auto out_container =
304 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
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);
313#endif
314 };
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));
318
319 return true;
320}
321
322} // namespace cyber
323} // namespace apollo
324
325#endif // CYBER_APOLLO_ROS_MESSAGE_CONVERTER_H_
virtual bool ConvertMsg(InputTypes< std::shared_ptr< InType0 > > &input, OutputTypes< std::shared_ptr< OutType0 > > &output)=0
virtual bool ConvertMsg(InputTypes< std::shared_ptr< InType0 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > &output)=0
virtual bool ConvertMsg(InputTypes< std::shared_ptr< InType0 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 >, std::shared_ptr< OutType3 > > &output)=0
virtual bool ConvertMsg(InputTypes< std::shared_ptr< InType0 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 > > &output)=0
#define AERROR
Definition log.h:44
bool Init(const char *binary_name, const std::string &dag_info)
Definition init.cc:98
class register implement
Definition arena_queue.h:37
Definition future.h:29