|
@@ -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;
|