Apollo 10.0
自动驾驶开放平台
convert_ros_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_ROS_APOLLO_SINGLE_H_
18#define CYBER_ROS_APOLLO_SINGLE_H_
19
20#include <memory>
21#include <utility>
22
24
25#include "cyber/cyber.h"
27
28namespace apollo {
29namespace cyber {
30
31template <typename InType0, typename OutType0>
32class RosApolloMessageConverter<InputTypes<std::shared_ptr<InType0>>,
33 OutputTypes<std::shared_ptr<OutType0>>>
34 : public MessageConverter {
35 private:
36 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ = nullptr;
37
38 public:
41
42 bool Init() override {
44 if (!init_.load()) {
45 return false;
46 }
48 AERROR << "load config failed";
49 return false;
50 }
51
52 auto writer_attrs =
53 std::make_shared<apollo::cyber::proto::RoleAttributes>();
54 writer_attrs->set_channel_name(converter_conf_.apollo_channel_name_0());
55 apollo_attrs_.push_back(writer_attrs);
56 auto ros_topic_name_0 = converter_conf_.ros_topic_name_0();
57
58 apollo_writer_0_ =
59 cyber_node_->template CreateWriter<OutType0>(*writer_attrs);
60#ifdef RCLCPP__RCLCPP_HPP_
61 ros_subscriptions_.push_back(
62 std::move(ros_node_->create_subscription<InType0>(
63 ros_topic_name_0, 10,
64 std::bind(
66 InputTypes<std::shared_ptr<InType0>>,
67 OutputTypes<std::shared_ptr<OutType0>>>::TopicCallback,
68 this, std::placeholders::_1))));
69 ros_spin_thread_ =
70 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
71#endif
72 return true;
73 }
74
75 protected:
76 virtual bool ConvertMsg(InputTypes<std::shared_ptr<InType0>>& input,
77 OutputTypes<std::shared_ptr<OutType0>>& output) = 0;
78
79#ifdef RCLCPP__RCLCPP_HPP_
80 private:
81 void TopicCallback(std::shared_ptr<InType0> ros_msg0) {
82 auto out = std::make_shared<OutType0>();
83 typename InType0::SharedPtr internal_in_prt =
84 std::make_shared<InType0>(*ros_msg0.get());
85 auto in_container =
86 InputTypes<std::shared_ptr<InType0>>{std::make_tuple(internal_in_prt)};
87 auto out_container =
88 OutputTypes<std::shared_ptr<OutType0>>{std::make_tuple(out)};
89 this->ConvertMsg(in_container, out_container);
90 apollo_writer_0_->Write(out);
91 }
92#endif
93};
94
95template <typename InType0, typename OutType0, typename OutType1>
97 InputTypes<std::shared_ptr<InType0>>,
98 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>>
99 : public MessageConverter {
100 private:
101 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ = nullptr;
102 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ = nullptr;
103
104 public:
107
108 bool Init() override {
110 if (!init_.load()) {
111 return false;
112 }
114 return false;
115 }
116
117 apollo_attrs_.push_back(
118 std::make_shared<apollo::cyber::proto::RoleAttributes>());
120
121 apollo_attrs_.push_back(
122 std::make_shared<apollo::cyber::proto::RoleAttributes>());
124
125 auto ros_topic_name_0 = converter_conf_.ros_topic_name_0();
126
127 apollo_writer_0_ =
128 cyber_node_->template CreateWriter<OutType0>(*apollo_attrs_[0]);
129 apollo_writer_1_ =
130 cyber_node_->template CreateWriter<OutType1>(*apollo_attrs_[1]);
131#ifdef RCLCPP__RCLCPP_HPP_
132 ros_subscriptions_.push_back(
133 std::move(ros_node_->create_subscription<InType0>(
134 ros_topic_name_0, 10,
135 std::bind(
137 InputTypes<std::shared_ptr<InType0>>,
138 OutputTypes<std::shared_ptr<OutType0>,
139 std::shared_ptr<OutType1>>>::TopicCallback,
140 this, std::placeholders::_1))));
141 ros_spin_thread_ =
142 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
143#endif
144 return true;
145 }
146
147 protected:
148 virtual bool ConvertMsg(InputTypes<std::shared_ptr<InType0>>& input,
149 OutputTypes<std::shared_ptr<OutType0>,
150 std::shared_ptr<OutType1>>& output) = 0;
151
152#ifdef RCLCPP__RCLCPP_HPP_
153 private:
154 void TopicCallback(std::shared_ptr<InType0> ros_msg0) {
155 auto out_0 = std::make_shared<OutType0>();
156 auto out_1 = std::make_shared<OutType1>();
157 typename InType0::SharedPtr internal_in_prt =
158 std::make_shared<InType0>(*ros_msg0.get());
159 auto in_container =
160 InputTypes<std::shared_ptr<InType0>>{std::make_tuple(internal_in_prt)};
161 auto out_container =
162 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>{
163 std::make_tuple(out_0, out_1)};
164 this->ConvertMsg(in_container, out_container);
165 apollo_writer_0_->Write(out_0);
166 apollo_writer_1_->Write(out_1);
167 }
168#endif
169};
170
171template <typename InType0, typename OutType0, typename OutType1,
172 typename OutType2>
174 InputTypes<std::shared_ptr<InType0>>,
175 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
176 std::shared_ptr<OutType2>>> : public MessageConverter {
177 private:
178 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ = nullptr;
179 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ = nullptr;
180 std::shared_ptr<Writer<OutType2>> apollo_writer_2_ = nullptr;
181
182 public:
185
186 bool Init() override {
188 if (!init_.load()) {
189 return false;
190 }
192 return false;
193 }
194
195 apollo_attrs_.push_back(
196 std::make_shared<apollo::cyber::proto::RoleAttributes>());
198
199 apollo_attrs_.push_back(
200 std::make_shared<apollo::cyber::proto::RoleAttributes>());
202
203 apollo_attrs_.push_back(
204 std::make_shared<apollo::cyber::proto::RoleAttributes>());
206
207 auto ros_topic_name_0 = converter_conf_.ros_topic_name_0();
208
209 apollo_writer_0_ =
210 cyber_node_->template CreateWriter<OutType0>(*apollo_attrs_[0]);
211 apollo_writer_1_ =
212 cyber_node_->template CreateWriter<OutType1>(*apollo_attrs_[1]);
213 apollo_writer_2_ =
214 cyber_node_->template CreateWriter<OutType2>(*apollo_attrs_[2]);
215#ifdef RCLCPP__RCLCPP_HPP_
216 ros_subscriptions_.push_back(
217 std::move(ros_node_->create_subscription<InType0>(
218 ros_topic_name_0, 10,
219 std::bind(
221 InputTypes<std::shared_ptr<InType0>>,
222 OutputTypes<std::shared_ptr<OutType0>,
223 std::shared_ptr<OutType1>,
224 std::shared_ptr<OutType2>>>::TopicCallback,
225 this, std::placeholders::_1))));
226 ros_spin_thread_ =
227 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
228#endif
229 return true;
230 }
231
232 protected:
233 virtual bool ConvertMsg(
234 InputTypes<std::shared_ptr<InType0>>& input,
235 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
236 std::shared_ptr<OutType2>>& output) = 0;
237
238#ifdef RCLCPP__RCLCPP_HPP_
239 private:
240 void TopicCallback(std::shared_ptr<InType0> ros_msg0) {
241 auto out_0 = std::make_shared<OutType0>();
242 auto out_1 = std::make_shared<OutType1>();
243 auto out_2 = std::make_shared<OutType2>();
244 typename InType0::SharedPtr internal_in_prt =
245 std::make_shared<InType0>(*ros_msg0.get());
246 auto in_container =
247 InputTypes<std::shared_ptr<InType0>>{std::make_tuple(internal_in_prt)};
248 auto out_container =
249 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
250 std::shared_ptr<OutType2>>{
251 std::make_tuple(out_0, out_1, out_2)};
252 this->ConvertMsg(in_container, out_container);
253 apollo_writer_0_->Write(out_0);
254 apollo_writer_1_->Write(out_1);
255 apollo_writer_2_->Write(out_2);
256 }
257#endif
258};
259
260template <typename InType0, typename OutType0, typename OutType1,
261 typename OutType2, typename OutType3>
263 InputTypes<std::shared_ptr<InType0>>,
264 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
265 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>>
266 : public MessageConverter {
267 private:
268 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ = nullptr;
269 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ = nullptr;
270 std::shared_ptr<Writer<OutType2>> apollo_writer_2_ = nullptr;
271 std::shared_ptr<Writer<OutType3>> apollo_writer_3_ = nullptr;
272
273 public:
276
277 bool Init() override {
279 if (!init_.load()) {
280 return false;
281 }
283 return false;
284 }
285
286 apollo_attrs_.push_back(
287 std::make_shared<apollo::cyber::proto::RoleAttributes>());
289
290 apollo_attrs_.push_back(
291 std::make_shared<apollo::cyber::proto::RoleAttributes>());
293
294 apollo_attrs_.push_back(
295 std::make_shared<apollo::cyber::proto::RoleAttributes>());
297
298 apollo_attrs_.push_back(
299 std::make_shared<apollo::cyber::proto::RoleAttributes>());
301
302 auto ros_topic_name_0 = converter_conf_.ros_topic_name_0();
303
304 apollo_writer_0_ =
305 cyber_node_->template CreateWriter<OutType0>(*apollo_attrs_[0]);
306 apollo_writer_1_ =
307 cyber_node_->template CreateWriter<OutType1>(*apollo_attrs_[1]);
308 apollo_writer_2_ =
309 cyber_node_->template CreateWriter<OutType2>(*apollo_attrs_[2]);
310 apollo_writer_3_ =
311 cyber_node_->template CreateWriter<OutType3>(*apollo_attrs_[3]);
312#ifdef RCLCPP__RCLCPP_HPP_
313 ros_subscriptions_.push_back(
314 std::move(ros_node_->create_subscription<InType0>(
315 ros_topic_name_0, 10,
316 std::bind(
318 InputTypes<std::shared_ptr<InType0>>,
319 OutputTypes<std::shared_ptr<OutType0>,
320 std::shared_ptr<OutType1>,
321 std::shared_ptr<OutType2>,
322 std::shared_ptr<OutType3>>>::TopicCallback,
323 this, std::placeholders::_1))));
324 ros_spin_thread_ =
325 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
326#endif
327 return true;
328 }
329
330 protected:
331 virtual bool ConvertMsg(
332 InputTypes<std::shared_ptr<InType0>>& input,
333 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
334 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>&
335 output) = 0;
336
337#ifdef RCLCPP__RCLCPP_HPP_
338 private:
339 void TopicCallback(std::shared_ptr<InType0> ros_msg0) {
340 auto out_0 = std::make_shared<OutType0>();
341 auto out_1 = std::make_shared<OutType1>();
342 auto out_2 = std::make_shared<OutType2>();
343 auto out_3 = std::make_shared<OutType3>();
344 typename InType0::SharedPtr internal_in_prt =
345 std::make_shared<InType0>(*ros_msg0.get());
346 auto in_container =
347 InputTypes<std::shared_ptr<InType0>>{std::make_tuple(internal_in_prt)};
348 auto out_container =
349 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
350 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>{
351 std::make_tuple(out_0, out_1, out_2, out_3)};
352 this->ConvertMsg(in_container, out_container);
353 apollo_writer_0_->Write(out_0);
354 apollo_writer_1_->Write(out_1);
355 apollo_writer_2_->Write(out_2);
356 apollo_writer_3_->Write(out_3);
357 }
358#endif
359};
360
361} // namespace cyber
362} // namespace apollo
363
364#endif // CYBER_APOLLO_ROS_MESSAGE_CONVERTER_H_
std::unique_ptr< apollo::cyber::Node > cyber_node_
std::vector< std::shared_ptr< apollo::cyber::proto::RoleAttributes > > apollo_attrs_
bool LoadConfig(ConverterConf *config)
virtual bool ConvertMsg(InputTypes< std::shared_ptr< InType0 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 > > &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 >, std::shared_ptr< OutType2 > > &output)=0
virtual bool ConvertMsg(InputTypes< std::shared_ptr< InType0 > > &input, OutputTypes< std::shared_ptr< OutType0 > > &output)=0
virtual bool ConvertMsg(const std::shared_ptr< R0 > &ros_msg0, const std::shared_ptr< R1 > &ros_msg1, const std::shared_ptr< R2 > &ros_msg2, const std::shared_ptr< R3 > &ros_msg3, std::shared_ptr< M0 > &apollo_msg0, std::shared_ptr< M1 > &apollo_msg1, std::shared_ptr< M2 > &apollo_msg2, std::shared_ptr< M3 > &apollo_msg3)=0
#define AERROR
Definition log.h:44
class register implement
Definition arena_queue.h:37
Definition future.h:29