137 {
140 return false;
141 }
143 return false;
144 }
145
147 std::make_shared<apollo::cyber::proto::RoleAttributes>());
149
151 std::make_shared<apollo::cyber::proto::RoleAttributes>());
153
156
157 apollo_writer_0_ =
159 apollo_writer_1_ =
161#ifdef RCLCPP__RCLCPP_HPP_
162 ros_msg_subs_.push_back(
163 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
164 ros_node_, ros_topic_name_0)));
165 ros_msg_subs_.push_back(
166 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
167 ros_node_, ros_topic_name_1)));
168 syncApproximate_ = std::make_shared<
169 message_filters::Synchronizer<approximate_sync_policy>>(
170 approximate_sync_policy(10),
171 *dynamic_cast<message_filters::Subscriber<InType0>*>(
172 ros_msg_subs_[0].get()),
173 *dynamic_cast<message_filters::Subscriber<InType1>*>(
174 ros_msg_subs_[1].get()));
175 syncApproximate_->registerCallback(
177 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>,
178 OutputTypes<std::shared_ptr<OutType0>,
179 std::shared_ptr<OutType1>>>::TopicCallback,
180 this);
181
182 ros_spin_thread_ =
183 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
184#endif
185 return true;
186 }
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_0
optional string apollo_channel_name_1
optional string ros_topic_name_0
optional string ros_topic_name_1