Apollo 10.0
自动驾驶开放平台
|
#include <odometry_parser.h>
Public 成员函数 | |
OdometryParser () | |
~OdometryParser () | |
void | imuCallback (std::shared_ptr< RosImuMsg > msg) |
void | gpsCallback (std::shared_ptr< RosNavMsg > msg) |
void | publishOdometry () |
virtual bool | ConvertMsg (InputTypes< RosWrapMsgPtr > &, OutputTypes< OutputWrapMsgPtr > &) |
convert the message between ros and apollo | |
![]() | |
RosApolloMessageConverter () | |
RosApolloMessageConverter () | |
~RosApolloMessageConverter () override | |
~RosApolloMessageConverter () override | |
bool | Init () override |
bool | Init () override |
![]() | |
MessageConverter () | |
virtual | ~MessageConverter () |
bool | IsInit () const |
额外继承的成员函数 | |
![]() | |
virtual bool | ConvertMsg (const std::shared_ptr< InputTypes< RosWrapMsgPtr > > &ros_msg0, const std::shared_ptr< OutputTypes< OutputWrapMsgPtr > > &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 |
![]() | |
bool | LoadConfig (ConverterConf *config) |
![]() | |
std::atomic< bool > | init_ |
std::unique_ptr< apollo::cyber::Node > | cyber_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_ |
在文件 odometry_parser.h 第 76 行定义.
|
inline |
在文件 odometry_parser.h 第 80 行定义.
|
inline |
在文件 odometry_parser.h 第 104 行定义.
|
virtual |
convert the message between ros and apollo
InputTypes | input message container |
OutputTypes | output message container |
在文件 odometry_parser.cc 第 132 行定义.
void apollo::cyber::OdometryParser::gpsCallback | ( | std::shared_ptr< RosNavMsg > | msg | ) |
在文件 odometry_parser.cc 第 59 行定义.
void apollo::cyber::OdometryParser::imuCallback | ( | std::shared_ptr< RosImuMsg > | msg | ) |
在文件 odometry_parser.cc 第 23 行定义.
void apollo::cyber::OdometryParser::publishOdometry | ( | ) |
在文件 odometry_parser.cc 第 89 行定义.