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

#include <convert_apollo_double.h>

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

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 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > &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 OutType0, typename OutType1, typename OutType2>
class apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > >

在文件 convert_apollo_double.h190 行定义.

构造及析构函数说明

◆ ApolloRosMessageConverter()

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

在文件 convert_apollo_double.h195 行定义.

195{}

◆ ~ApolloRosMessageConverter()

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

在文件 convert_apollo_double.h196 行定义.

196{}

成员函数说明

◆ ConvertMsg()

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

◆ Init()

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

重载 apollo::cyber::MessageConverter .

在文件 convert_apollo_double.h212 行定义.

212 {
214 if (!init_.load()) {
215 return false;
216 }
218 return false;
219 }
220
221 apollo::cyber::ReaderConfig reader_cfg_0;
223
224 apollo::cyber::ReaderConfig reader_cfg_1;
226 auto apollo_reader_1 =
227 cyber_node_->template CreateReader<InType1>(reader_cfg_1);
228
229 auto apollo_blocker_1 =
230 blocker::BlockerManager::Instance()->GetBlocker<InType1>(
231 reader_cfg_1.channel_name);
232
233 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
234 std::string ros_topic_name_1 = converter_conf_.ros_topic_name_1();
235 std::string ros_topic_name_2 = converter_conf_.ros_topic_name_2();
236
237#ifdef RCLCPP__RCLCPP_HPP_
238 auto ros_publisher_0 =
239 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
240 auto ros_publisher_1 =
241 ros_node_->create_publisher<OutType1>(ros_topic_name_1, 10);
242 auto ros_publisher_2 =
243 ros_node_->create_publisher<OutType2>(ros_topic_name_2, 10);
244 ros_publishers_.push_back(std::move(ros_publisher_0));
245 ros_publishers_.push_back(std::move(ros_publisher_1));
246 ros_publishers_.push_back(std::move(ros_publisher_2));
247 auto func = [this, apollo_blocker_1, ros_publisher_0, ros_publisher_1,
248 ros_publisher_2](const std::shared_ptr<InType0> in) {
249#else
250 auto func = [this, apollo_blocker_1](const std::shared_ptr<InType0> in) {
251#endif
252 if (!apollo_blocker_1->IsPublishedEmpty()) {
253 auto msg1 = apollo_blocker_1->GetLatestPublishedPtr();
254 auto out_0 = std::make_shared<OutType0>();
255 auto out_1 = std::make_shared<OutType1>();
256 auto out_2 = std::make_shared<OutType2>();
257 auto in_container =
258 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>{
259 std::make_tuple(in, msg1)};
260 auto out_container =
261 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
262 std::shared_ptr<OutType2>>{
263 std::make_tuple(out_0, out_1, out_2)};
264 this->ConvertMsg(in_container, out_container);
265#ifdef RCLCPP__RCLCPP_HPP_
266 ros_publisher_0->publish(*out_0);
267 ros_publisher_1->publish(*out_1);
268 ros_publisher_2->publish(*out_2);
269#endif
270 }
271 };
272 auto apollo_reader_0 =
273 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
274 apollo_readers_.push_back(std::move(apollo_reader_0));
275 apollo_readers_.push_back(std::move(apollo_reader_1));
276
277 return true;
278}
virtual bool ConvertMsg(InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > &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()

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