5 from sensor_msgs.msg
import Image
8 rostopic info /camera/depth/image_rect 9 Type: sensor_msgs/Image 11 rosmsg show sensor_msgs/Image 12 std_msgs/Header header 25 lockfilepath =
"/run/shm/xtion.raw.lock" 26 framefilepath =
"/run/shm/xtion.raw" 28 if os.path.exists(lockfilepath):
31 open(lockfilepath,
'w')
33 framefile = open(framefilepath,
'w')
34 framefile.write(data.data)
37 if os.path.exists(lockfilepath):
38 os.remove(lockfilepath)
46 rospy.init_node(
'openni_imgrect_to_shm', anonymous=
False)
47 rospy.Subscriber(
"camera/depth/image_raw", Image, imgrect_callBack)
def imgrect_callBack(data)