Apollo 10.0
自动驾驶开放平台
apollo::cyber::LocalizationEstimate类 参考

#include <localization_estimate.h>

类 apollo::cyber::LocalizationEstimate 继承关系图:
apollo::cyber::LocalizationEstimate 的协作图:

Public 成员函数

 LocalizationEstimate ()
 
 ~LocalizationEstimate ()
 
virtual bool ConvertMsg (InputTypes< InputMsgPtr > &, OutputTypes< LocalizationMsgPtr, TransformMsgPtr > &)
 convert the message between ros and apollo
 
- Public 成员函数 继承自 apollo::cyber::RosApolloMessageConverter< InputTypes< InputMsgPtr >, OutputTypes< LocalizationMsgPtr, TransformMsgPtr > >
 RosApolloMessageConverter ()
 
 RosApolloMessageConverter ()
 
 ~RosApolloMessageConverter () override
 
 ~RosApolloMessageConverter () override
 
bool Init () override
 
bool Init () override
 
- Public 成员函数 继承自 apollo::cyber::MessageConverter
 MessageConverter ()
 
virtual ~MessageConverter ()
 
bool IsInit () const
 

额外继承的成员函数

- Protected 成员函数 继承自 apollo::cyber::RosApolloMessageConverter< InputTypes< InputMsgPtr >, OutputTypes< LocalizationMsgPtr, TransformMsgPtr > >
virtual bool ConvertMsg (const std::shared_ptr< InputTypes< InputMsgPtr > > &ros_msg0, const std::shared_ptr< OutputTypes< LocalizationMsgPtr, TransformMsgPtr > > &ros_msg1, const std::shared_ptr< NullType > &ros_msg2, const std::shared_ptr< NullType > &ros_msg3, std::shared_ptr< NullType > &apollo_msg0, std::shared_ptr< NullType > &apollo_msg1, std::shared_ptr< NullType > &apollo_msg2, std::shared_ptr< NullType > &apollo_msg3)=0
 
virtual bool ConvertMsg (InputTypes &input, OutputTypes &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_
 

详细描述

在文件 localization_estimate.h53 行定义.

构造及析构函数说明

◆ LocalizationEstimate()

apollo::cyber::LocalizationEstimate::LocalizationEstimate ( )
inline

在文件 localization_estimate.h58 行定义.

58{}

◆ ~LocalizationEstimate()

apollo::cyber::LocalizationEstimate::~LocalizationEstimate ( )
inline

在文件 localization_estimate.h59 行定义.

59{}

成员函数说明

◆ ConvertMsg()

bool apollo::cyber::LocalizationEstimate::ConvertMsg ( InputTypes< InputMsgPtr > &  in,
OutputTypes< LocalizationMsgPtr, TransformMsgPtr > &  out 
)
virtual

convert the message between ros and apollo

参数
InputMsgPtrshared pointer of input message
OutputMsgPtrshared pointer of output message
返回
result, true for success

在文件 localization_estimate.cc22 行定义.

24 {
25#ifdef ENABLE_ROS_MSG
26 auto ros_odometry_ptr = std::get<0>(in.values);
27 auto& ros_odometry = (*ros_odometry_ptr);
28 auto localization_estimate = std::get<0>(out.values);
29 auto tf = std::get<1>(out.values);
30
31 auto unix_msg_time =
32 ros_odometry.header.stamp.sec + ros_odometry.header.stamp.nanosec / 1e9;
33 localization_estimate->mutable_header()->set_timestamp_sec(unix_msg_time);
34 localization_estimate->mutable_header()->set_module_name("localization");
35 localization_estimate->set_measurement_time(unix_msg_time);
36 localization_estimate->mutable_pose()->mutable_position()->set_x(
37 ros_odometry.pose.pose.position.x);
38 localization_estimate->mutable_pose()->mutable_position()->set_y(
39 ros_odometry.pose.pose.position.y);
40 localization_estimate->mutable_pose()->mutable_position()->set_z(
41 ros_odometry.pose.pose.position.z);
42 localization_estimate->mutable_pose()->mutable_linear_velocity()->set_x(
43 ros_odometry.twist.twist.linear.x);
44 localization_estimate->mutable_pose()->mutable_linear_velocity()->set_y(
45 ros_odometry.twist.twist.linear.y);
46 localization_estimate->mutable_pose()->mutable_linear_velocity()->set_z(
47 ros_odometry.twist.twist.linear.z);
48 localization_estimate->mutable_pose()->mutable_angular_velocity()->set_x(
49 ros_odometry.twist.twist.angular.x);
50 localization_estimate->mutable_pose()->mutable_angular_velocity()->set_y(
51 ros_odometry.twist.twist.angular.y);
52 localization_estimate->mutable_pose()->mutable_angular_velocity()->set_z(
53 ros_odometry.twist.twist.angular.z);
54 localization_estimate->mutable_pose()->mutable_orientation()->set_qx(
55 ros_odometry.pose.pose.orientation.x);
56 localization_estimate->mutable_pose()->mutable_orientation()->set_qy(
57 ros_odometry.pose.pose.orientation.y);
58 localization_estimate->mutable_pose()->mutable_orientation()->set_qz(
59 ros_odometry.pose.pose.orientation.z);
60 localization_estimate->mutable_pose()->mutable_orientation()->set_qw(
61 ros_odometry.pose.pose.orientation.w);
62
63 auto single_tf = tf->add_transforms();
64 single_tf->mutable_header()->set_timestamp_sec(unix_msg_time);
65 single_tf->mutable_header()->set_frame_id("world");
66 single_tf->set_child_frame_id("localization");
67 single_tf->mutable_transform()->mutable_translation()->set_x(
68 ros_odometry.pose.pose.position.x);
69 single_tf->mutable_transform()->mutable_translation()->set_y(
70 ros_odometry.pose.pose.position.y);
71 single_tf->mutable_transform()->mutable_translation()->set_z(
72 ros_odometry.pose.pose.position.z);
73 single_tf->mutable_transform()->mutable_rotation()->set_qx(
74 ros_odometry.pose.pose.orientation.x);
75 single_tf->mutable_transform()->mutable_rotation()->set_qy(
76 ros_odometry.pose.pose.orientation.y);
77 single_tf->mutable_transform()->mutable_rotation()->set_qz(
78 ros_odometry.pose.pose.orientation.z);
79 single_tf->mutable_transform()->mutable_rotation()->set_qw(
80 ros_odometry.pose.pose.orientation.w);
81#endif
82 return true;
83}

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