Subscribe and show costmap images.
This commit is contained in:
parent
6ade8fb818
commit
7b189e5177
|
|
@ -28,6 +28,7 @@ class Api:
|
|||
web.get('/api/build_info', self.build_info),
|
||||
web.get('/api/env', self.env),
|
||||
web.get('/api/status', self.status),
|
||||
web.get('/api/costmap_image', self.costmap_image),
|
||||
web.static("/assets", ui_static_directory),
|
||||
# we're not actually using key anywhere, but doing this allows react router
|
||||
# to work correctly.
|
||||
|
|
@ -67,8 +68,11 @@ class Api:
|
|||
if not project_state:
|
||||
resp = {"status": False, "message": "project_state not found."}
|
||||
return web.json_response(resp)
|
||||
project_state["status"] = True
|
||||
return web.json_response(project_state)
|
||||
resp = {
|
||||
"status": True,
|
||||
"message": project_state
|
||||
}
|
||||
return web.json_response(resp)
|
||||
|
||||
async def env(self, request):
|
||||
env = self._facts.get_env()
|
||||
|
|
@ -80,3 +84,10 @@ class Api:
|
|||
status = "Nothing received!"
|
||||
resp = {"message": status}
|
||||
return web.json_response(resp)
|
||||
|
||||
async def costmap_image(self, request):
|
||||
(image_format, image_data) = self._facts.get_costmap_image()
|
||||
if (not image_format) or (not image_data):
|
||||
raise web.HTTPUnsupportedMediaType()
|
||||
resp = web.Response(body=image_data, content_type='image/{}'.format(image_format))
|
||||
return resp
|
||||
|
|
|
|||
|
|
@ -19,6 +19,15 @@ class Facts:
|
|||
def __init__(self):
|
||||
self._start_time = time.monotonic()
|
||||
self._status_string = None
|
||||
self._costmap_image_format = None
|
||||
self._costmap_image_data = None
|
||||
|
||||
def set_costmap_image(self, image_format, image_data):
|
||||
self._costmap_image_format = image_format
|
||||
self._costmap_image_data = image_data
|
||||
|
||||
def get_costmap_image(self):
|
||||
return (self._costmap_image_format, self._costmap_image_data)
|
||||
|
||||
def set_status_string(self, status):
|
||||
self._status_string = status
|
||||
|
|
|
|||
|
|
@ -10,6 +10,7 @@
|
|||
#
|
||||
import rclpy
|
||||
from std_msgs.msg import String
|
||||
from sensor_msgs.msg import CompressedImage
|
||||
import asyncio
|
||||
|
||||
class Ros:
|
||||
|
|
@ -19,10 +20,17 @@ class Ros:
|
|||
self._node = rclpy.create_node('am_i_up')
|
||||
|
||||
self._node.create_subscription(String, "status", self.status_sub, 1)
|
||||
self._node.create_subscription(CompressedImage, "image/compressed", self.image_sub, 1)
|
||||
|
||||
def status_sub(self, msg):
|
||||
self._facts.set_status_string(msg.data)
|
||||
|
||||
def image_sub(self, msg):
|
||||
if msg.format != "jpg" and msg.format != "png":
|
||||
# I don't know what to do with this image....
|
||||
return
|
||||
self._facts.set_costmap_image(msg.format, bytes(msg.data))
|
||||
|
||||
async def run(self):
|
||||
while rclpy.ok():
|
||||
rclpy.spin_once(self._node, timeout_sec=0)
|
||||
|
|
|
|||
|
|
@ -16,8 +16,8 @@ import asyncio
|
|||
|
||||
def main():
|
||||
facts = Facts()
|
||||
api = Api(facts)
|
||||
ros = Ros(facts)
|
||||
api = Api(facts)
|
||||
|
||||
future = asyncio.gather(api.run(), ros.run())
|
||||
asyncio.get_event_loop().run_until_complete(future)
|
||||
|
|
|
|||
|
|
@ -1,3 +1,4 @@
|
|||
<launch>
|
||||
<node pkg="am_i_up" exec="server" name="am_i_up"/>
|
||||
<node pkg="data_simulator" exec="image_publisher" name="image_publisher" />
|
||||
</launch>
|
||||
|
|
|
|||
Loading…
Reference in New Issue