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

#include <convert_apollo_single.h>

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

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

在文件 convert_apollo_single.h238 行定义.

构造及析构函数说明

◆ ApolloRosMessageConverter()

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

在文件 convert_apollo_single.h244 行定义.

244{}

◆ ~ApolloRosMessageConverter()

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

在文件 convert_apollo_single.h245 行定义.

245{}

成员函数说明

◆ ConvertMsg()

template<typename InType0 , typename OutType0 , typename OutType1 , typename OutType2 , typename OutType3 >
virtual bool apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 >, std::shared_ptr< OutType3 > > >::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 
)
protectedpure virtual

◆ Init()

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

重载 apollo::cyber::MessageConverter .

在文件 convert_apollo_single.h262 行定义.

262 {
264 if (!init_.load()) {
265 return false;
266 }
268 return false;
269 }
270
271 apollo::cyber::ReaderConfig reader_cfg_0;
273
274 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
275 std::string ros_topic_name_1 = converter_conf_.ros_topic_name_1();
276 std::string ros_topic_name_2 = converter_conf_.ros_topic_name_2();
277 std::string ros_topic_name_3 = converter_conf_.ros_topic_name_3();
278
279#ifdef RCLCPP__RCLCPP_HPP_
280 auto ros_publisher_0 =
281 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
282 auto ros_publisher_1 =
283 ros_node_->create_publisher<OutType1>(ros_topic_name_1, 10);
284 auto ros_publisher_2 =
285 ros_node_->create_publisher<OutType2>(ros_topic_name_2, 10);
286 auto ros_publisher_3 =
287 ros_node_->create_publisher<OutType2>(ros_topic_name_3, 10);
288 ros_publishers_.push_back(std::move(ros_publisher_0));
289 ros_publishers_.push_back(std::move(ros_publisher_1));
290 ros_publishers_.push_back(std::move(ros_publisher_2));
291 ros_publishers_.push_back(std::move(ros_publisher_3));
292 auto func = [this, ros_publisher_0, ros_publisher_1, ros_publisher_2,
293 ros_publisher_3](const std::shared_ptr<InType0> in) {
294#else
295 auto func = [this](const std::shared_ptr<InType0> in) {
296#endif
297 auto out_0 = std::make_shared<OutType0>();
298 auto out_1 = std::make_shared<OutType1>();
299 auto out_2 = std::make_shared<OutType2>();
300 auto out_3 = std::make_shared<OutType3>();
301 auto in_container =
302 InputTypes<std::shared_ptr<InType0>>{std::make_tuple(in)};
303 auto out_container =
304 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
305 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>{
306 std::make_tuple(out_0, out_1, out_2, out_3)};
307 this->ConvertMsg(in_container, out_container);
308#ifdef RCLCPP__RCLCPP_HPP_
309 ros_publisher_0->publish(*out_0);
310 ros_publisher_1->publish(*out_1);
311 ros_publisher_2->publish(*out_2);
312 ros_publisher_3->publish(*out_2);
313#endif
314 };
315 auto apollo_reader_0 =
316 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
317 apollo_readers_.push_back(std::move(apollo_reader_0));
318
319 return true;
320}
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
std::unique_ptr< apollo::cyber::Node > cyber_node_
std::vector< std::shared_ptr< apollo::cyber::ReaderBase > > apollo_readers_
bool LoadConfig(ConverterConf *config)

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