238 {
241 return false;
242 }
244 return false;
245 }
246
248 std::make_shared<apollo::cyber::proto::RoleAttributes>());
250
252 std::make_shared<apollo::cyber::proto::RoleAttributes>());
254
256 std::make_shared<apollo::cyber::proto::RoleAttributes>());
258
261
262 apollo_writer_0_ =
264 apollo_writer_1_ =
266 apollo_writer_2_ =
268#ifdef RCLCPP__RCLCPP_HPP_
269 ros_msg_subs_.push_back(
270 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
271 ros_node_, ros_topic_name_0)));
272 ros_msg_subs_.push_back(
273 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
274 ros_node_, ros_topic_name_1)));
275 syncApproximate_ = std::make_shared<
276 message_filters::Synchronizer<approximate_sync_policy>>(
277 approximate_sync_policy(10),
278 *dynamic_cast<message_filters::Subscriber<InType0>*>(
279 ros_msg_subs_[0].get()),
280 *dynamic_cast<message_filters::Subscriber<InType1>*>(
281 ros_msg_subs_[1].get()));
282 syncApproximate_->registerCallback(
284 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>,
285 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
286 std::shared_ptr<OutType2>>>::TopicCallback,
287 this);
288
289 ros_spin_thread_ =
290 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
291#endif
292 return true;
293 }
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 apollo_channel_name_2
optional string apollo_channel_name_0
optional string apollo_channel_name_1
optional string ros_topic_name_0
optional string ros_topic_name_1