def navigation(): request_json = request.json if "start_lat" not in request_json: return jsonify([]) if "start_lon" not in request_json: return jsonify([]) if "end_lat" not in request_json: return jsonify([]) if "end_lon" not in request_json: return jsonify([]) start_latlon = str(request_json["start_lat"]) + "," + \ str(request_json["start_lon"]) end_latlon = str(request_json["end_lat"]) + "," + \ str(request_json["end_lon"]) url = "http://navi-env.axty8vi3ic.us-west-2." \ "elasticbeanstalk.com/dreamview/navigation?origin=" + \ start_latlon + "&destination=" + end_latlon + "&heading=0" res = requests.get(url) if res.status_code != 200: return jsonify([]) # send to ros navigation_info = navigation_pb2.NavigationInfo() navigation_info.ParseFromString(res.content) routing_pub.publish(navigation_info) # send to browser latlon_path = [] for path in navigation_info.navigation_path: for point in path.path.path_point: lons, lats = projector(point.x, point.y, inverse=True) latlon_path.append({'lat': lats, 'lng': lons}) if len(latlon_path) > 0: latlon_path[0]['human'] = True return jsonify(latlon_path)
boundary.setMap(map); } """) doc.asis('}\n') doc.asis('<script src="' + api_url + '"></script>') self.html = doc.getvalue() return self.html if __name__ == "__main__": import google.protobuf.text_format as text_format if len(sys.argv) < 2: print "usage: python map_viewer.py dbmap_file [utm_zone=10]" sys.exit(0) map_file = sys.argv[1] utm_zone = 10 if len(sys.argv) >= 3: utm_zone = int(sys.argv[2]) dbmap = navigation_pb2.NavigationInfo() proto_utils.get_pb_from_file(map_file, dbmap) with open(map_file, 'r') as file_in: text_format.Merge(file_in.read(), dbmap) viewer = DBMapViewer(utm_zone) viewer.add(dbmap) html = viewer.generate() with open('dbmap.html', 'w') as f: f.write(html)
############################################################################### import rospy import sys import json from modules.map.relative_map.proto import navigation_pb2 if __name__ == '__main__': navi_files = sys.argv[1:] rospy.init_node("navigator_offline", anonymous=True) navigation_pub = rospy.Publisher("/apollo/navigation", navigation_pb2.NavigationInfo, queue_size=1) # generate navigation info navigation_info = navigation_pb2.NavigationInfo() priority = 0 for fdata in navi_files: print("processing " + fdata) navigation_path = navigation_info.navigation_path.add() navigation_path.path_priority = priority priority += 1 navigation_path.path.name = "navigation" f = open(fdata, 'r') cnt = 0 for line in f: cnt += 1 if cnt < 3: continue json_point = json.loads(line)