26#include "cyber/proto/simple.pb.h"
27#include "modules/common_msgs/sensor_msgs/heading.pb.h"
31#if __has_include("sensor_msgs/msg/nav_sat_fix.hpp")
32#include "sensor_msgs/msg/nav_sat_fix.hpp"
33#define ROS_NAVFOUND_FOUND
36#if __has_include("nav_msgs/msg/odometry.hpp")
37#include "nav_msgs/msg/odometry.hpp"
38#define ROS_ODOMETRY_FOUND
41#if defined(ROS_NAVFOUND_FOUND) && defined(ROS_ODOMETRY_FOUND)
46using RosNavMsg = sensor_msgs::msg::NavSatFix;
65 InputTypes<RosNavMsgPtr, RosOdometryMsgPtr>,
66 OutputTypes<OutputMsgPtr>> {
virtual bool ConvertMsg(InputTypes< RosNavMsgPtr, RosOdometryMsgPtr > &, OutputTypes< OutputMsgPtr > &)
convert the message between ros and apollo
#define CYBER_PLUGIN_MANAGER_REGISTER_PLUGIN(name, base)
std::shared_ptr< RosOdometryMsg > RosOdometryMsgPtr
std::shared_ptr< RosNavMsg > RosNavMsgPtr
std::shared_ptr< OutputMsg > OutputMsgPtr