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

#include <imu_msg_converter.h>

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

Public 成员函数

 ImuMsgConverter ()
 
 ~ImuMsgConverter ()
 
virtual bool ConvertMsg (InputTypes< RosImuMsgPtr > &, OutputTypes< ImuMsgPtr, CorrectedImuMsgPtr > &)
 convert the message between ros and apollo
 
- Public 成员函数 继承自 apollo::cyber::RosApolloMessageConverter< InputTypes< RosImuMsgPtr >, OutputTypes< ImuMsgPtr, CorrectedImuMsgPtr > >
 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< RosImuMsgPtr >, OutputTypes< ImuMsgPtr, CorrectedImuMsgPtr > >
virtual bool ConvertMsg (const std::shared_ptr< InputTypes< RosImuMsgPtr > > &ros_msg0, const std::shared_ptr< OutputTypes< ImuMsgPtr, CorrectedImuMsgPtr > > &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_
 

详细描述

在文件 imu_msg_converter.h55 行定义.

构造及析构函数说明

◆ ImuMsgConverter()

apollo::cyber::ImuMsgConverter::ImuMsgConverter ( )
inline

在文件 imu_msg_converter.h59 行定义.

59{}

◆ ~ImuMsgConverter()

apollo::cyber::ImuMsgConverter::~ImuMsgConverter ( )
inline

在文件 imu_msg_converter.h60 行定义.

60{}

成员函数说明

◆ ConvertMsg()

bool apollo::cyber::ImuMsgConverter::ConvertMsg ( InputTypes< RosImuMsgPtr > &  in,
OutputTypes< ImuMsgPtr, CorrectedImuMsgPtr > &  out 
)
virtual

convert the message between ros and apollo

参数
InputTypesinput message container
OutputTypesoutput message container
返回
result, true for success

在文件 imu_msg_converter.cc23 行定义.

25 {
26#ifdef ENABLE_ROS_MSG
27 auto ros_imu_ptr = std::get<0>(in.values);
28 auto& ros_imu = (*ros_imu_ptr);
29
30 auto imu_msg = std::get<0>(out.values);
31 auto corrected_imu_msg = std::get<1>(out.values);
32
33 // ros header time is unix time,
34 // while measurement_time of apollo imu is gps time
35 double unix_msg_time =
36 ros_imu.header.stamp.sec + ros_imu.header.stamp.nanosec / 1e9;
37 imu_msg->mutable_header()->set_timestamp_sec(unix_msg_time);
38 imu_msg->mutable_header()->set_module_name("gnss");
39
40 imu_msg->set_measurement_time(unix_msg_time);
41 imu_msg->set_measurement_span(0.0);
42 imu_msg->mutable_linear_acceleration()->set_x(ros_imu.linear_acceleration.x);
43 imu_msg->mutable_linear_acceleration()->set_y(ros_imu.linear_acceleration.y);
44 imu_msg->mutable_linear_acceleration()->set_z(ros_imu.linear_acceleration.z);
45 imu_msg->mutable_angular_velocity()->set_x(ros_imu.angular_velocity.x);
46 imu_msg->mutable_angular_velocity()->set_y(ros_imu.angular_velocity.y);
47 imu_msg->mutable_angular_velocity()->set_z(ros_imu.angular_velocity.z);
48
49 corrected_imu_msg->mutable_header()->set_timestamp_sec(unix_msg_time);
50 corrected_imu_msg->mutable_header()->set_module_name("gnss");
51 corrected_imu_msg->mutable_imu()->mutable_linear_acceleration()->set_x(
52 ros_imu.linear_acceleration.x);
53 corrected_imu_msg->mutable_imu()->mutable_linear_acceleration()->set_y(
54 ros_imu.linear_acceleration.y);
55 corrected_imu_msg->mutable_imu()->mutable_linear_acceleration()->set_z(
56 ros_imu.linear_acceleration.z);
57 corrected_imu_msg->mutable_imu()->mutable_angular_velocity()->set_x(
58 ros_imu.angular_velocity.x);
59 corrected_imu_msg->mutable_imu()->mutable_angular_velocity()->set_y(
60 ros_imu.angular_velocity.y);
61 corrected_imu_msg->mutable_imu()->mutable_angular_velocity()->set_z(
62 ros_imu.angular_velocity.z);
63 double quaternion[4];
64 double euler_angles[3];
65
66 quaternion[0] = ros_imu.orientation.x;
67 quaternion[1] = ros_imu.orientation.y;
68 quaternion[2] = ros_imu.orientation.z;
69 quaternion[3] = ros_imu.orientation.w;
70
71 QuaternionToEuler(quaternion, euler_angles);
72 auto heading = QuaternionToHeading(euler_angles[2]);
73 corrected_imu_msg->mutable_imu()->mutable_euler_angles()->set_x(
74 euler_angles[0]);
75 corrected_imu_msg->mutable_imu()->mutable_euler_angles()->set_y(
76 euler_angles[1]);
77 corrected_imu_msg->mutable_imu()->mutable_euler_angles()->set_z(
78 euler_angles[2]);
79
80#endif
81 return true;
82}
double QuaternionToHeading(double yaw)
void QuaternionToEuler(const double quaternion[4], double att[3])

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