Skip to content

Commit

Permalink
Test script for ticket ros-visualization#1826
Browse files Browse the repository at this point in the history
  • Loading branch information
MichaelGrupp committed May 14, 2024
1 parent b820db8 commit 0bc8926
Showing 1 changed file with 14 additions and 8 deletions.
22 changes: 14 additions & 8 deletions src/test/map_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,30 +3,36 @@
from nav_msgs.msg import OccupancyGrid
import rospy
import math
from PIL import Image
from PIL.ImageOps import flip, grayscale, invert

topic = "moving_map"
publisher = rospy.Publisher(topic, OccupancyGrid)
publisher = rospy.Publisher(topic, OccupancyGrid, queue_size=1)

rospy.init_node("map_test")

grid = OccupancyGrid()

t = 0

image = flip(grayscale(Image.open("../../images/splash.png")))

while not rospy.is_shutdown():
grid.header.frame_id = "map"
grid.header.stamp = rospy.Time.now()
grid.info.map_load_time = rospy.Time.now()
grid.info.resolution = 1.0
grid.info.width = 3
grid.info.height = 3
grid.info.resolution = 0.02
grid.info.width = image.width
grid.info.height = image.height
grid.info.origin.position.x = math.cos(t)
grid.info.origin.position.y = math.sin(t)
grid.info.origin.orientation.w = 1.0
grid.data = [0, 20, 40, 60, 80, 100, 120, -10, -100]

# Publish the MarkerArray
image = invert(image)
grid.data = [x - 128 for x in image.getdata()]

# Publish the OccupancyGrid
publisher.publish(grid)

rospy.sleep(0.05)
t += 0.1
rospy.sleep(2)
t += 1

0 comments on commit 0bc8926

Please sign in to comment.