Plotting data with mayavi via the subscriber node
Hi, I want a real time 3d plot of the data points from my topic so i wrote a basic subscriber and expected it to work. This is my code
#!/usr/bin/env python
import rospy
from sensor_msgs.msg import LaserScan
# import matplotlib.pyplot as plt
import numpy as np
import math
import mayavi.mlab as mlab
import time
def callback(data):
rospy.loginfo("I heard %f %f %f", math.degrees(data.angle_increment), math.degrees(data.angle_min), math.degrees(data.angle_max) )
theta = np.arange(data.angle_min, data.angle_max+data.angle_increment, data.angle_increment)
rospy.loginfo("%s %s", str(len(theta)), str(len(data.ranges)) )
z=np.ones(len(theta))
# plt.ylabel('distance')
# plt.xlabel('angle')
# plt.xticks(data.angle_min, data.angle_max, data.angle_increment)
mlab.clf()
mla*b.plot3d(theta, data.ranges,z)
# time.sleep(0.001)
# plt.pause(0.001)
# plt.clf()
def listener():
rospy.init_node('listener', anonymous=True)
rospy.Subscriber("scan", LaserScan, callback)
# spin() simply keeps python from exiting until this node is stopped
rospy.spin()
if __name__ == '__main__':
listener()
I get the following error:
QPixmap: It is not safe to use pixmaps outside the GUI thread
QObject::startTimer: QTimer can only be used with threads started with QThread
I tried writing the callback function as a inner(nested) function even that did not resolve the issue, i've also tried the same with matplotlib, a similar sort of error showed up, which says TkInter is not running in the main thread.
Any help is appreciated. Cheers.