26#include "cyber/proto/simple.pb.h"
27#include "modules/common_msgs/localization_msgs/localization.pb.h"
28#include "modules/common_msgs/transform_msgs/transform.pb.h"
32#if __has_include("nav_msgs/msg/odometry.hpp")
33#include "nav_msgs/msg/odometry.hpp"
38using InputMsg = nav_msgs::msg::Odometry;
55 InputTypes<InputMsgPtr>,
56 OutputTypes<LocalizationMsgPtr, TransformMsgPtr>> {
virtual bool ConvertMsg(InputTypes< InputMsgPtr > &, OutputTypes< LocalizationMsgPtr, TransformMsgPtr > &)
convert the message between ros and apollo
#define CYBER_PLUGIN_MANAGER_REGISTER_PLUGIN(name, base)
std::shared_ptr< LocalizationMsg > LocalizationMsgPtr
std::shared_ptr< InputMsg > InputMsgPtr
std::shared_ptr< TransformMsg > TransformMsgPtr