Compare commits
3 Commits
7b189e5177
...
0113cd4a12
| Author | SHA1 | Date |
|---|---|---|
|
|
0113cd4a12 | |
|
|
b2e862d4ac | |
|
|
67bbd8f1b9 |
|
|
@ -29,6 +29,7 @@ class Api:
|
||||||
web.get('/api/env', self.env),
|
web.get('/api/env', self.env),
|
||||||
web.get('/api/status', self.status),
|
web.get('/api/status', self.status),
|
||||||
web.get('/api/costmap_image', self.costmap_image),
|
web.get('/api/costmap_image', self.costmap_image),
|
||||||
|
web.get("/api/position", self.position),
|
||||||
web.static("/assets", ui_static_directory),
|
web.static("/assets", ui_static_directory),
|
||||||
# we're not actually using key anywhere, but doing this allows react router
|
# we're not actually using key anywhere, but doing this allows react router
|
||||||
# to work correctly.
|
# to work correctly.
|
||||||
|
|
@ -91,3 +92,15 @@ class Api:
|
||||||
raise web.HTTPUnsupportedMediaType()
|
raise web.HTTPUnsupportedMediaType()
|
||||||
resp = web.Response(body=image_data, content_type='image/{}'.format(image_format))
|
resp = web.Response(body=image_data, content_type='image/{}'.format(image_format))
|
||||||
return resp
|
return resp
|
||||||
|
|
||||||
|
async def position(self, request):
|
||||||
|
resp = {}
|
||||||
|
(lat, lon) = self._facts.get_lat_long()
|
||||||
|
if not lat or not lon:
|
||||||
|
resp["status"] = False
|
||||||
|
return web.json_response(resp)
|
||||||
|
resp["status"] = True
|
||||||
|
resp["latitude"] = lat
|
||||||
|
resp["longitude"] = lon
|
||||||
|
return web.json_response(resp)
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -15,25 +15,26 @@ import os
|
||||||
import yaml
|
import yaml
|
||||||
from ament_index_python import get_package_share_directory
|
from ament_index_python import get_package_share_directory
|
||||||
|
|
||||||
|
from am_i_up.Ros import Ros
|
||||||
|
|
||||||
class Facts:
|
class Facts:
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
|
self._ros = Ros()
|
||||||
|
|
||||||
self._start_time = time.monotonic()
|
self._start_time = time.monotonic()
|
||||||
self._status_string = None
|
self._status_string = None
|
||||||
self._costmap_image_format = None
|
|
||||||
self._costmap_image_data = None
|
|
||||||
|
|
||||||
def set_costmap_image(self, image_format, image_data):
|
async def run(self):
|
||||||
self._costmap_image_format = image_format
|
await self._ros.run()
|
||||||
self._costmap_image_data = image_data
|
|
||||||
|
def get_lat_long(self):
|
||||||
|
return self._ros.get_lat_long()
|
||||||
|
|
||||||
def get_costmap_image(self):
|
def get_costmap_image(self):
|
||||||
return (self._costmap_image_format, self._costmap_image_data)
|
return self._ros.get_costmap_image()
|
||||||
|
|
||||||
def set_status_string(self, status):
|
|
||||||
self._status_string = status
|
|
||||||
|
|
||||||
def get_status(self):
|
def get_status(self):
|
||||||
return self._status_string
|
return self._ros.get_status_string()
|
||||||
|
|
||||||
def get_uptime(self):
|
def get_uptime(self):
|
||||||
return time.monotonic() - self._start_time
|
return time.monotonic() - self._start_time
|
||||||
|
|
|
||||||
|
|
@ -11,28 +11,45 @@
|
||||||
import rclpy
|
import rclpy
|
||||||
from std_msgs.msg import String
|
from std_msgs.msg import String
|
||||||
from sensor_msgs.msg import CompressedImage
|
from sensor_msgs.msg import CompressedImage
|
||||||
|
from sensor_msgs.msg import NavSatFix
|
||||||
import asyncio
|
import asyncio
|
||||||
|
|
||||||
class Ros:
|
class Ros:
|
||||||
def __init__(self, facts):
|
def __init__(self):
|
||||||
rclpy.init()
|
rclpy.init()
|
||||||
self._facts = facts
|
|
||||||
self._node = rclpy.create_node('am_i_up')
|
self._node = rclpy.create_node('am_i_up')
|
||||||
|
|
||||||
self._node.create_subscription(String, "status", self.status_sub, 1)
|
self._status_sub = self._node.create_subscription(String, "status", self._status_callback, 1)
|
||||||
self._node.create_subscription(CompressedImage, "image/compressed", self.image_sub, 1)
|
self._image_sub = self._node.create_subscription(CompressedImage, "image/compressed", self._image_callback, 1)
|
||||||
|
self._navsat_sub = self._node.create_subscription(NavSatFix, "navsatfix", self._navsat_callback, 1)
|
||||||
|
|
||||||
def status_sub(self, msg):
|
self._status_string = None
|
||||||
self._facts.set_status_string(msg.data)
|
self._lat_long = None
|
||||||
|
self._costmap_image = None
|
||||||
|
|
||||||
def image_sub(self, msg):
|
def get_status_string(self):
|
||||||
if msg.format != "jpg" and msg.format != "png":
|
return self._status_string
|
||||||
# I don't know what to do with this image....
|
|
||||||
return
|
def get_lat_long(self):
|
||||||
self._facts.set_costmap_image(msg.format, bytes(msg.data))
|
return self._lat_long
|
||||||
|
|
||||||
|
def get_costmap_image(self):
|
||||||
|
return self._costmap_image
|
||||||
|
|
||||||
async def run(self):
|
async def run(self):
|
||||||
while rclpy.ok():
|
while rclpy.ok():
|
||||||
rclpy.spin_once(self._node, timeout_sec=0)
|
rclpy.spin_once(self._node, timeout_sec=0)
|
||||||
await asyncio.sleep(1e-4)
|
await asyncio.sleep(1e-4)
|
||||||
|
|
||||||
|
def _status_callback(self, msg):
|
||||||
|
self._status_string = msg.data
|
||||||
|
|
||||||
|
def _navsat_callback(self, msg):
|
||||||
|
self._lat_long = (msg.latitude, msg.longitude)
|
||||||
|
|
||||||
|
def _image_callback(self, msg):
|
||||||
|
if msg.format != "jpg" and msg.format != "png":
|
||||||
|
# I don't know what to do with this image....
|
||||||
|
return
|
||||||
|
self._costmap_image = (msg.format, bytes(msg.data))
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -10,14 +10,12 @@
|
||||||
#
|
#
|
||||||
from am_i_up.Api import Api
|
from am_i_up.Api import Api
|
||||||
from am_i_up.Facts import Facts
|
from am_i_up.Facts import Facts
|
||||||
from am_i_up.Ros import Ros
|
|
||||||
|
|
||||||
import asyncio
|
import asyncio
|
||||||
|
|
||||||
def main():
|
def main():
|
||||||
facts = Facts()
|
facts = Facts()
|
||||||
ros = Ros(facts)
|
|
||||||
api = Api(facts)
|
api = Api(facts)
|
||||||
|
|
||||||
future = asyncio.gather(api.run(), ros.run())
|
future = asyncio.gather(api.run(), facts.run())
|
||||||
asyncio.get_event_loop().run_until_complete(future)
|
asyncio.get_event_loop().run_until_complete(future)
|
||||||
|
|
|
||||||
|
|
@ -1,4 +1,5 @@
|
||||||
<launch>
|
<launch>
|
||||||
<node pkg="am_i_up" exec="server" name="am_i_up"/>
|
<node pkg="am_i_up" exec="server" name="am_i_up"/>
|
||||||
<node pkg="data_simulator" exec="image_publisher" name="image_publisher" />
|
<node pkg="data_simulator" exec="image_publisher" name="image_publisher" />
|
||||||
|
<node pkg="data_simulator" exec="position_publisher" name="position_publisher" />
|
||||||
</launch>
|
</launch>
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue