Browse Source

添加发布localizer_pose话题

fujiankuan 3 years ago
parent
commit
e30b2b23d7
1 changed files with 3 additions and 0 deletions
  1. 3 0
      src/ros/catkin/src/rtk_hcp2_baselink/src/main.cpp

+ 3 - 0
src/ros/catkin/src/rtk_hcp2_baselink/src/main.cpp

@@ -36,6 +36,7 @@ static double ghead0 = 0;
 
 ros::Publisher pose_pub;
 ros::Publisher twist_pub;
+ros::Publisher localizer_pub;
 
 QString mstrHCP2;
 
@@ -343,6 +344,7 @@ void SerialGPSDecodeSen(QString strsen)
 
     pose_pub.publish(xPose);
     twist_pub.publish(xtwist);
+     localizer_pub.publish(xPose);
 
     //    std::cout<<"current pose"<<std::endl;
 }
@@ -543,6 +545,7 @@ int main(int argc, char *argv[])
 
     pose_pub = private_nh.advertise<geometry_msgs::PoseStamped>(_pose_topic, 10);
     twist_pub = private_nh.advertise<geometry_msgs::TwistStamped>(_twist_topic, 10);
+    localizer_pub = private_nh.advertise<geometry_msgs::PoseStamped>("/localizer_pose",10);
 
     // static tf::TransformBroadcaster br;
     // tf::Transform transform;