Apollo 10.0
自动驾驶开放平台
apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 > > > 模板类 参考abstract

#include <convert_apollo_quadruple.h>

类 apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 > > > 继承关系图:
apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 > > > 的协作图:

Public 成员函数

 ApolloRosMessageConverter ()
 
 ~ApolloRosMessageConverter () override
 
bool Init () override
 
- Public 成员函数 继承自 apollo::cyber::MessageConverter
 MessageConverter ()
 
virtual ~MessageConverter ()
 
bool IsInit () const
 

Protected 成员函数

virtual bool ConvertMsg (InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 > > &output)=0
 
- Protected 成员函数 继承自 apollo::cyber::MessageConverter
bool LoadConfig (ConverterConf *config)
 

额外继承的成员函数

- Protected 属性 继承自 apollo::cyber::MessageConverter
std::atomic< bool > init_
 
std::unique_ptr< apollo::cyber::Nodecyber_node_
 
std::vector< std::shared_ptr< apollo::cyber::proto::RoleAttributes > > apollo_attrs_
 
std::vector< std::shared_ptr< apollo::cyber::ReaderBase > > apollo_readers_
 
std::vector< std::shared_ptr< apollo::cyber::WriterBase > > apollo_writers_
 
const std::string node_name_ = "converter_base"
 
ConverterConf converter_conf_
 

详细描述

template<typename InType0, typename InType1, typename InType2, typename InType3, typename OutType0, typename OutType1>
class apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 > > >

在文件 convert_apollo_quadruple.h138 行定义.

构造及析构函数说明

◆ ApolloRosMessageConverter()

template<typename InType0 , typename InType1 , typename InType2 , typename InType3 , typename OutType0 , typename OutType1 >
apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 > > >::ApolloRosMessageConverter ( )
inline

在文件 convert_apollo_quadruple.h144 行定义.

144{}

◆ ~ApolloRosMessageConverter()

template<typename InType0 , typename InType1 , typename InType2 , typename InType3 , typename OutType0 , typename OutType1 >
apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 > > >::~ApolloRosMessageConverter ( )
inlineoverride

在文件 convert_apollo_quadruple.h145 行定义.

145{}

成员函数说明

◆ ConvertMsg()

template<typename InType0 , typename InType1 , typename InType2 , typename InType3 , typename OutType0 , typename OutType1 >
virtual bool apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 > > >::ConvertMsg ( InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > > &  input,
OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 > > &  output 
)
protectedpure virtual

◆ Init()

template<typename InType0 , typename InType1 , typename InType2 , typename InType3 , typename OutType0 , typename OutType1 >
bool apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 > > >::Init ( )
overridevirtual

重载 apollo::cyber::MessageConverter .

在文件 convert_apollo_quadruple.h162 行定义.

162 {
164 if (!init_.load()) {
165 return false;
166 }
168 return false;
169 }
170
171 apollo::cyber::ReaderConfig reader_cfg_0;
173
174 apollo::cyber::ReaderConfig reader_cfg_1;
176 auto apollo_reader_1 =
177 cyber_node_->template CreateReader<InType1>(reader_cfg_1);
178
179 apollo::cyber::ReaderConfig reader_cfg_2;
181 auto apollo_reader_2 =
182 cyber_node_->template CreateReader<InType2>(reader_cfg_2);
183
184 apollo::cyber::ReaderConfig reader_cfg_3;
186 auto apollo_reader_3 =
187 cyber_node_->template CreateReader<InType3>(reader_cfg_3);
188
189 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
190 std::string ros_topic_name_1 = converter_conf_.ros_topic_name_1();
191
192 auto apollo_blocker_1 =
193 blocker::BlockerManager::Instance()->GetBlocker<InType1>(
194 reader_cfg_1.channel_name);
195 auto apollo_blocker_2 =
196 blocker::BlockerManager::Instance()->GetBlocker<InType2>(
197 reader_cfg_2.channel_name);
198 auto apollo_blocker_3 =
199 blocker::BlockerManager::Instance()->GetBlocker<InType3>(
200 reader_cfg_3.channel_name);
201
202#ifdef RCLCPP__RCLCPP_HPP_
203 auto ros_publisher_0 =
204 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
205 auto ros_publisher_1 =
206 ros_node_->create_publisher<OutType1>(ros_topic_name_1, 10);
207 ros_publishers_.push_back(std::move(ros_publisher_0));
208 ros_publishers_.push_back(std::move(ros_publisher_1));
209 auto func = [this, apollo_blocker_1, apollo_blocker_2, apollo_blocker_3,
210 ros_publisher_0,
211 ros_publisher_1](const std::shared_ptr<InType0> in) {
212#else
213 auto func = [this, apollo_blocker_1, apollo_blocker_2,
214 apollo_blocker_3](const std::shared_ptr<InType0> in) {
215#endif
216 if (!apollo_blocker_1->IsPublishedEmpty() &&
217 !apollo_blocker_2->IsPublishedEmpty() &&
218 !apollo_blocker_3->IsPublishedEmpty()) {
219 auto msg1 = apollo_blocker_1->GetLatestPublishedPtr();
220 auto msg2 = apollo_blocker_2->GetLatestPublishedPtr();
221 auto msg3 = apollo_blocker_3->GetLatestPublishedPtr();
222 auto out_0 = std::make_shared<OutType0>();
223 auto out_1 = std::make_shared<OutType1>();
224 auto in_container =
225 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
226 std::shared_ptr<InType2>, std::shared_ptr<InType3>>{
227 std::make_tuple(in, msg1, msg2, msg3)};
228 auto out_container =
229 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>{
230 std::make_tuple(out_0, out_1)};
231 this->ConvertMsg(in_container, out_container);
232#ifdef RCLCPP__RCLCPP_HPP_
233 ros_publisher_0->publish(*out_0);
234 ros_publisher_1->publish(*out_1);
235#endif
236 }
237 };
238 auto apollo_reader_0 =
239 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
240 apollo_readers_.push_back(std::move(apollo_reader_0));
241 apollo_readers_.push_back(std::move(apollo_reader_1));
242 apollo_readers_.push_back(std::move(apollo_reader_2));
243 apollo_readers_.push_back(std::move(apollo_reader_3));
244
245 return true;
246}
virtual bool ConvertMsg(InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 > > &output)=0
std::unique_ptr< apollo::cyber::Node > cyber_node_
std::vector< std::shared_ptr< apollo::cyber::ReaderBase > > apollo_readers_
bool LoadConfig(ConverterConf *config)
static const std::shared_ptr< BlockerManager > & Instance()

该类的文档由以下文件生成: