Get lat long.
This commit is contained in:
parent
7b189e5177
commit
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)
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -21,6 +21,13 @@ class Facts:
|
||||||
self._status_string = None
|
self._status_string = None
|
||||||
self._costmap_image_format = None
|
self._costmap_image_format = None
|
||||||
self._costmap_image_data = None
|
self._costmap_image_data = None
|
||||||
|
self._lat_lon = (None, None)
|
||||||
|
|
||||||
|
def set_lat_long(self, lat, lon):
|
||||||
|
self._lat_lon = (lat, lon)
|
||||||
|
|
||||||
|
def get_lat_long(self):
|
||||||
|
return self._lat_lon
|
||||||
|
|
||||||
def set_costmap_image(self, image_format, image_data):
|
def set_costmap_image(self, image_format, image_data):
|
||||||
self._costmap_image_format = image_format
|
self._costmap_image_format = image_format
|
||||||
|
|
|
||||||
|
|
@ -11,6 +11,7 @@
|
||||||
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:
|
||||||
|
|
@ -21,10 +22,14 @@ class Ros:
|
||||||
|
|
||||||
self._node.create_subscription(String, "status", self.status_sub, 1)
|
self._node.create_subscription(String, "status", self.status_sub, 1)
|
||||||
self._node.create_subscription(CompressedImage, "image/compressed", self.image_sub, 1)
|
self._node.create_subscription(CompressedImage, "image/compressed", self.image_sub, 1)
|
||||||
|
self._node.create_subscription(NavSatFix, "navsatfix", self.navsat_sub, 1)
|
||||||
|
|
||||||
def status_sub(self, msg):
|
def status_sub(self, msg):
|
||||||
self._facts.set_status_string(msg.data)
|
self._facts.set_status_string(msg.data)
|
||||||
|
|
||||||
|
def navsat_sub(self, msg):
|
||||||
|
self._facts.set_lat_long(msg.latitude, msg.longitude)
|
||||||
|
|
||||||
def image_sub(self, msg):
|
def image_sub(self, msg):
|
||||||
if msg.format != "jpg" and msg.format != "png":
|
if msg.format != "jpg" and msg.format != "png":
|
||||||
# I don't know what to do with this image....
|
# I don't know what to do with this image....
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue