Problem in Map buildiing using Gmapping
I have created a bag file using the attached code of bagconvert.py, The code is pasted,
!/usr/bin/env python
import rospy import rosbag from sensormsgs.msg import LaserScan from math import pi from tf2msgs.msg import TFMessage from geometry_msgs.msg import TransformStamped import tf
def maketfmsg(x, y, theta, t): trans = TransformStamped() trans.header.stamp = t trans.header.frameid = '/odom' trans.childframeid = '/laser' trans.transform.translation.x = x trans.transform.translation.y = y q = tf.transformations.quaternionfrom_euler(0, 0, theta) trans.transform.rotation.x = q[0] trans.transform.rotation.y = q[1] trans.transform.rotation.z = q[2] trans.transform.rotation.w = q[3]
msg = TFMessage()
msg.transforms.append(trans)
return msg
with open('intel.clf') as dataset: with rosbag.Bag('intel.bag', 'w') as bag: for line in dataset.readlines(): line = line.strip() tokens = line.split(' ') if len(tokens) <= 2: continue if tokens[0] == 'FLASER': msg = LaserScan() num_scans = int(tokens[1])
if num_scans != 180 or len(tokens) < num_scans + 9:
rospy.logwarn("unsupported scan format")
continue
msg.header.frame_id = 'laser'
t = rospy.Time(float(tokens[(num_scans + 8)]))
msg.header.stamp = t
msg.angle_min = -90.0 / 180.0 * pi
msg.angle_max = 90.0 / 180.0 * pi
msg.angle_increment = pi / num_scans
msg.time_increment = 0.2 / 360.0
msg.scan_time = 0.2
msg.range_min = 0.001
msg.range_max = 50.0
msg.ranges = [float(r) for r in tokens[2:(num_scans + 2)]]
bag.write('laser', msg, t)
odom_x, odom_y, odom_theta = [float(r) for r in tokens[(num_scans + 2):(num_scans + 5)]]
tf_msg = make_tf_msg(odom_x, odom_y, odom_theta, t)
bag.write('tf', tf_msg, t)
elif tokens[0] == 'ODOM':
odom_x, odom_y, odom_theta = [float(t) for t in tokens[1:4]]
t = rospy.Time(float(tokens[7]))
tf_msg = make_tf_msg(odom_x, odom_y, odom_theta, t)
bag.write('tf', tf_msg, t)
Now a file called intel.bag is created. now I am following the tutorial of building a map from logged data, roscore rosparam set usesimtime true rosrun gmapping slamgmapping scan:=laser rosbag play intel.bag After this in the Rviz window no map is built, and in the gmapping terminal an error message is shown "[ WARN] [1478603677.898065363]: Failed to compute laser pose, aborting initialization ("baselink" passed to lookupTransform argument target_frame does not exist. )". Please provide a solution.
Asked by user_123 on 2016-11-08 07:23:17 UTC
Comments