小修改

This commit is contained in:
Robin Shaun 2020-10-21 11:16:14 +08:00
parent 10f8b01f73
commit 2ee8968d2c
2 changed files with 3 additions and 5 deletions

View File

@ -24,13 +24,13 @@ def odm_aloam_callback(msg):
local_pose.header.stamp = msg.header.stamp
local_pose.pose = msg.pose.pose
def callback(data):
def laser_scan_matcher_callback(data):
global laser_scan
laser_scan = data
def laser_scan_matcher():
global local_pose
pose2d_sub = rospy.Subscriber(vehicle_type+'_'+ vehicle_id+"/pose2D", Pose2D, callback)
pose2d_sub = rospy.Subscriber(vehicle_type+'_'+ vehicle_id+"/pose2D", Pose2D, laser_scan_matcher_callback)
rate = rospy.Rate(100)
while True:
local_pose.header.stamp = rospy.Time.now()

View File

@ -12,9 +12,7 @@ local_pose.header.frame_id = 'map'
quaternion = tf.transformations.quaternion_from_euler(0, -math.pi/2, math.pi/2)
q = Quaternion([quaternion[3],quaternion[0],quaternion[1],quaternion[2]])
def vins_callback(data):
#rospy.loginfo(str(data.pose.position.x)+','+str(data.pose.position.y)+','+str(data.pose.position.z))
def vins_callback(data):
local_pose.pose.position.x = data.pose.pose.position.x
local_pose.pose.position.y = data.pose.pose.position.y
local_pose.pose.position.z = data.pose.pose.position.z