From bef37694ec4369649db07ee51f91fd4fbb3d0f95 Mon Sep 17 00:00:00 2001 From: TiaSinghania <59597284+TiaSinghania@users.noreply.github.com> Date: Fri, 16 Aug 2024 16:41:24 -0700 Subject: [PATCH 1/8] reverted main back to how it was may 2024 --- .../buggy/scripts/auton/brake_controller.py | 93 ++++++++++++++++ .../scripts/auton/pure_pursuit_controller.py | 105 ++++++++++++++++++ .../buggy/scripts/util/rosbag_to_pose_csv.py | 11 +- .../buggy/scripts/validation/log_battery.py | 4 +- 4 files changed, 202 insertions(+), 11 deletions(-) create mode 100644 rb_ws/src/buggy/scripts/auton/brake_controller.py create mode 100755 rb_ws/src/buggy/scripts/auton/pure_pursuit_controller.py diff --git a/rb_ws/src/buggy/scripts/auton/brake_controller.py b/rb_ws/src/buggy/scripts/auton/brake_controller.py new file mode 100644 index 0000000..6c1e407 --- /dev/null +++ b/rb_ws/src/buggy/scripts/auton/brake_controller.py @@ -0,0 +1,93 @@ +#!/usr/bin/env python3 +import numpy as np +from controller import Controller + +class BrakeController: + MAX_LATERAL_ACCEL = 0.9 # in "g" based on regular vehicle + BRAKING_GAIN = 2.0 + def __init__(self, use_binary_braking = True): + # NOTE: Add more stuff here to keep track of PID stuff once I and D are implemented. + self.binary_braking = use_binary_braking + + @staticmethod + def calculate_lateral_accel(linear_speed: float, steering_angle: float) -> float: + """Calculate the lateral acceleration given speed and steering angle for the CENTER of the + buggy. + + Args: + linear_speed (float): m/s + steering_angle (float): deg + + Returns: + float: lateral accel in "g" + """ + if (steering_angle == 0.0): + return 0.0 + radius_front_wheel = Controller.WHEELBASE / np.sin(np.deg2rad(steering_angle)) + radius_rear_wheel = Controller.WHEELBASE / np.tan(np.deg2rad(steering_angle)) + + lat_accel_front_wheel = np.absolute((linear_speed**2)/radius_front_wheel) / 9.81 + lat_accel_rear_wheel = np.absolute((linear_speed**2)/radius_rear_wheel) / 9.81 + + lat_accel = (lat_accel_front_wheel + lat_accel_rear_wheel) / 2 + + return lat_accel + + def compute_braking(self, speed: float, steering_angle: float) -> float: + """Wrapper for the type of braking controller we're using + + Args: + speed (float): m/s + steering_angle (float): degrees + + Returns: + float: 0-1 (1 = full brake) + """ + if self.binary_braking: + return self._compute_binary_braking(speed, steering_angle) + else: + return self._compute_modulated_braking(speed, steering_angle) + + def _compute_binary_braking(self, speed: float, steering_angle: float) -> float: + """Binary braking - using lateral acceleration + + Args: + speed (float): m/s + steering_angle (float): degrees + + Returns: + float: 1 is brake, 0 is release + """ + lat_accel = BrakeController.calculate_lateral_accel(speed, steering_angle) + if (lat_accel > BrakeController.MAX_LATERAL_ACCEL): + return 1.0 + else: + return 0.0 + + def _compute_modulated_braking(self, speed: float, steering_angle: float) -> float: + """Using P controller for braking based on lateral acceleration of buggy. Modulated values + from 0-1 + + Args: + speed (float): _description_ + steering_angle (float): _description_ + + Returns: + float: _description_ + """ + lat_accel = BrakeController.calculate_lateral_accel(speed, steering_angle) + if (lat_accel < BrakeController.MAX_LATERAL_ACCEL): + return 0.0 + else: + error = lat_accel - BrakeController.MAX_LATERAL_ACCEL + brake_cmd = 1.0 * error * BrakeController.BRAKING_GAIN + brake_cmd = np.clip(brake_cmd, 0, 1) + return brake_cmd + +if __name__ == "__main__": + brake_controller = BrakeController() + speed = 15 + steering_angle = 4 + print("Lateral Accel: ", BrakeController.calculate_lateral_accel(speed, steering_angle)) + brake_cmd = brake_controller.compute_braking(speed, steering_angle) + print("Braking CMD: ", brake_cmd) \ No newline at end of file diff --git a/rb_ws/src/buggy/scripts/auton/pure_pursuit_controller.py b/rb_ws/src/buggy/scripts/auton/pure_pursuit_controller.py new file mode 100755 index 0000000..29e5922 --- /dev/null +++ b/rb_ws/src/buggy/scripts/auton/pure_pursuit_controller.py @@ -0,0 +1,105 @@ +import numpy as np + +import rospy +from sensor_msgs.msg import NavSatFix +from geometry_msgs.msg import Pose as ROSPose + +from pose import Pose +from trajectory import Trajectory +from controller import Controller +from world import World + + +class PurePursuitController(Controller): + """ + Pure Pursuit Controller + """ + + LOOK_AHEAD_DIST_CONST = 0.5 + MIN_LOOK_AHEAD_DIST = 0.5 + MAX_LOOK_AHEAD_DIST = 10 + + def __init__(self, buggy_name, start_index=0) -> None: + super(PurePursuitController, self).__init__(start_index, buggy_name) + self.debug_reference_pos_publisher = rospy.Publisher( + buggy_name + "/auton/debug/reference_navsat", NavSatFix, queue_size=1 + ) + self.debug_track_pos_publisher = rospy.Publisher( + buggy_name + "/auton/debug/track_navsat", NavSatFix, queue_size=1 + ) + self.debug_error_publisher = rospy.Publisher( + buggy_name + "/auton/debug/error", ROSPose, queue_size=1 + ) + + def compute_control( + self, current_pose: Pose, trajectory: Trajectory, current_speed: float + ): + """ + Computes the desired control output given the current state and reference trajectory + + Args: + current_pose (Pose): current pose (x, y, theta) (UTM coordinates) + trajectory (Trajectory): reference trajectory + current_speed (float): current speed of the buggy + + Returns: + float (desired steering angle) + """ + if self.current_traj_index >= trajectory.get_num_points() - 1: + return 0 + + # 10 is a good number to search forward along the index + traj_index = trajectory.get_closest_index_on_path( + current_pose.x, + current_pose.y, + start_index=self.current_traj_index, + end_index=self.current_traj_index + 10, + ) + self.current_traj_index = max(traj_index, self.current_traj_index) + traj_dist = trajectory.get_distance_from_index(traj_index) + + reference_position = trajectory.get_position_by_index(traj_index) + reference_error = current_pose.convert_point_from_global_to_local_frame( + reference_position + ) + + lookahead_dist = np.clip( + self.LOOK_AHEAD_DIST_CONST * current_speed, + self.MIN_LOOK_AHEAD_DIST, + self.MAX_LOOK_AHEAD_DIST, + ) + traj_dist += lookahead_dist + + track_position = trajectory.get_position_by_distance(traj_dist) + track_error = current_pose.convert_point_from_global_to_local_frame( + track_position + ) + + bearing = np.arctan2(track_error[1], track_error[0]) + steering_angle = np.arctan( + 2.0 * self.WHEELBASE * np.sin(bearing) / lookahead_dist + ) + steering_angle = np.clip(steering_angle, -np.pi / 9, np.pi / 9) + + # Publish track position for debugging + track_navsat = NavSatFix() + track_gps = World.world_to_gps(*track_position) + track_navsat.latitude = track_gps[0] + track_navsat.longitude = track_gps[1] + self.debug_track_pos_publisher.publish(track_navsat) + + # Publish reference position for debugging + reference_navsat = NavSatFix() + ref_pos = trajectory.get_position_by_distance(traj_dist - lookahead_dist) + ref_gps = World.world_to_gps(*ref_pos) + reference_navsat.latitude = ref_gps[0] + reference_navsat.longitude = ref_gps[1] + self.debug_reference_pos_publisher.publish(reference_navsat) + + # Publish error for debugging + error_pose = ROSPose() + error_pose.position.x = reference_error[0] + error_pose.position.y = reference_error[1] + self.debug_error_publisher.publish(error_pose) + + return steering_angle diff --git a/rb_ws/src/buggy/scripts/util/rosbag_to_pose_csv.py b/rb_ws/src/buggy/scripts/util/rosbag_to_pose_csv.py index e538466..9ae9bf2 100644 --- a/rb_ws/src/buggy/scripts/util/rosbag_to_pose_csv.py +++ b/rb_ws/src/buggy/scripts/util/rosbag_to_pose_csv.py @@ -1,7 +1,6 @@ #! /usr/bin/env python3 import argparse import csv - import rosbag from tf.transformations import euler_from_quaternion @@ -43,13 +42,9 @@ def main(): lon = msg.pose.pose.position.y orientation_q = msg.pose.pose.orientation - orientation_list = [ - orientation_q.x, - orientation_q.y, - orientation_q.z, - orientation_q.w, - ] - (_, _, yaw) = euler_from_quaternion(orientation_list) + orientation_list = [orientation_q.x, orientation_q.y, orientation_q.z, orientation_q.w] + (_, _, yaw) = euler_from_quaternion (orientation_list) + waypoints.append([str(lat), str(lon), str(yaw)]) diff --git a/rb_ws/src/buggy/scripts/validation/log_battery.py b/rb_ws/src/buggy/scripts/validation/log_battery.py index 9a2d7c6..b7b7f69 100755 --- a/rb_ws/src/buggy/scripts/validation/log_battery.py +++ b/rb_ws/src/buggy/scripts/validation/log_battery.py @@ -2,9 +2,7 @@ import csv import rospy -from sensor_msgs.msg import ( - BatteryState, -) # Callback function to print the subscribed data on the terminal +from sensor_msgs.msg import BatteryState # Callback function to print the subscribed data on the terminal # Should be culled or improved to actually log the battery levels, to a file, when ros bags should contain this if properly published?? From 72a04b310872b97f8e8afb0cf1f96450a23fd488 Mon Sep 17 00:00:00 2001 From: Jack He <45720415+Jackack@users.noreply.github.com> Date: Fri, 16 Aug 2024 16:48:05 -0700 Subject: [PATCH 2/8] added docs directory, ros diagram (#103) * added docs directory, ros diagram * Added steering cmd topic * format --- docs/architecture/node_interactions.md | 64 +++++++++++++++++++++++ docs/work_standard/rostopic_convention.md | 0 2 files changed, 64 insertions(+) create mode 100644 docs/architecture/node_interactions.md create mode 100644 docs/work_standard/rostopic_convention.md diff --git a/docs/architecture/node_interactions.md b/docs/architecture/node_interactions.md new file mode 100644 index 0000000..55d97e4 --- /dev/null +++ b/docs/architecture/node_interactions.md @@ -0,0 +1,64 @@ +# ROS Node Interaction Document +## Scope +The purpose of this file is to descirbe the architecture of the RD25 stack from a ROS node level. This document should be updated whenever any ROS topics are added, removed or modified. + +## Viewing On VSCode +Install `bierner.markdown-mermaid` from the extension marketplace to render the charts in VSCode markdown preview. + +## List of topics +| Topic Name | Type | is custom message | +| ---------- | ----------------------- | ------------------ | +| ego/state | BuggyState | yes | +| other_buggy/state | BuggyState | yes | +| ego/trajectory | BuggyTrajectory | yes | +| ego/steering_cmd | [Float64](https://docs.ros.org/en/melodic/api/std_msgs/html/msg/Float64.html) | no | +| add new topic here | | | + +## ROS Nodes Graph +Auton Loop [Sequence Diagram](https://en.wikipedia.org/wiki/Sequence_diagram#:~:text=A%20sequence%20diagram%20shows%2C%20as,order%20in%20which%20they%20occur.) + +```mermaid +sequenceDiagram +A->>B: "some/topic" +``` + +means A publishes a message of `some/topic` and B receives the message. + +```mermaid +sequenceDiagram + participant I as Ego State Estimator Node + participant P as Planner Node + participant C as Controller Node + participant S as Firmware Comms Node + + box Grey HBK 3DM-GQ7 INS + participant I + end + + box Purple Auton Core + participant P + participant C + end + + box Blue Communication with Sensors, Actuators and Other Buggy + participant S + end + + loop 100hz + I->>P: "ego/state" + I->>C: "ego/state" + end + + loop 10hz + S->>P: "other_buggy/state" + end + + loop 10hz + P->>C: "ego/trajectory" + end + + loop 100hz + C->>S: "ego/steering_cmd" + end +``` + diff --git a/docs/work_standard/rostopic_convention.md b/docs/work_standard/rostopic_convention.md new file mode 100644 index 0000000..e69de29 From 8ef51126799b40589c537df0fab40aa76c9427da Mon Sep 17 00:00:00 2001 From: Mehul Goel Date: Sun, 15 Sep 2024 14:57:26 -0400 Subject: [PATCH 3/8] Raceline creation (#105) * added raceline + added better ghost_nand * fixed config * updated raceline paths --------- Co-authored-by: Buggy --- rb_ws/src/buggy/launch/ghost_auton.launch | 4 +- .../src/buggy/paths/buggycourse_raceline.json | 3900 ++++++++--------- rb_ws/src/buggy/scripts/2d_sim/engine.py | 1 + 3 files changed, 1767 insertions(+), 2138 deletions(-) diff --git a/rb_ws/src/buggy/launch/ghost_auton.launch b/rb_ws/src/buggy/launch/ghost_auton.launch index ac261cd..76ce13c 100644 --- a/rb_ws/src/buggy/launch/ghost_auton.launch +++ b/rb_ws/src/buggy/launch/ghost_auton.launch @@ -1,12 +1,12 @@ - + - + diff --git a/rb_ws/src/buggy/paths/buggycourse_raceline.json b/rb_ws/src/buggy/paths/buggycourse_raceline.json index 27abf20..06ccafd 100644 --- a/rb_ws/src/buggy/paths/buggycourse_raceline.json +++ b/rb_ws/src/buggy/paths/buggycourse_raceline.json @@ -1,2138 +1,1766 @@ [ - { - "key": "557d6ecd-ed80-4baa-bd73-379e4d7e0f1b", - "lat": 40.441800057826605, - "lon": -79.94158554867244, - "active": false - }, - { - "key": "6dec6a0c-26fc-4b73-b2df-be731adfdeda", - "lat": 40.44138911912961, - "lon": -79.94176508046225, - "active": false - }, - { - "key": "bf7dc40a-322e-4721-8b73-bbc19e461ae0", - "lat": 40.44108078455541, - "lon": -79.9418978662388, - "active": false - }, - { - "key": "854b351f-1fa6-4804-84b8-bad111c28717", - "lat": 40.440811635159065, - "lon": -79.94201574748945, - "active": false - }, - { - "key": "c8f35b89-2437-428a-906c-7c070f2c57aa", - "lat": 40.44054970329411, - "lon": -79.94214040352455, - "active": false - }, - { - "key": "4ad1c4fd-838d-4c13-8d52-29be23fa2fa4", - "lat": 40.44042609562262, - "lon": -79.94219878967333, - "active": false - }, - { - "key": "a3f8b7cd-0bd3-4720-80dc-74412c4722a7", - "lat": 40.44035759615232, - "lon": -79.94223268314757, - "active": false - }, - { - "key": "2aaef5ac-34dc-4da1-a9cc-34f50eb2210e", - "lat": 40.44030046006532, - "lon": -79.94226960037116, - "active": false - }, - { - "key": "76a04233-3847-4aba-9d53-191b264fc636", - "lat": 40.440268642424996, - "lon": -79.94229983490447, - "active": false - }, - { - "key": "6c1a8490-663d-4e5e-9135-85a8b65c6da4", - "lat": 40.44024463714177, - "lon": -79.94233454862784, - "active": false - }, - { - "key": "fac350ce-e434-4bc0-ac77-bbbebea62d0f", - "lat": 40.440224907810126, - "lon": -79.9423761347105, - "active": false - }, - { - "key": "db4e0ace-1dd7-4374-8eb3-c99e960091ff", - "lat": 40.44020686812299, - "lon": -79.9424280034914, - "active": false - }, - { - "key": "2ece3a7d-e421-4f00-bcd9-f2fa19c514f1", - "lat": 40.4401936312068, - "lon": -79.9424720226942, - "active": false - }, - { - "key": "eafd6f2b-405c-4c45-8913-e7a45124cc07", - "lat": 40.44018285424629, - "lon": -79.94251311754437, - "active": false - }, - { - "key": "434f1b28-bce3-4166-9a69-64e3c2bab3c6", - "lat": 40.440174068679525, - "lon": -79.94255067238875, - "active": false - }, - { - "key": "d7fca52b-f1ef-49c3-89aa-d09aab111028", - "lat": 40.44016774307078, - "lon": -79.9425849950538, - "active": false - }, - { - "key": "6b15a79b-5bae-4674-b973-24105cc3fc0e", - "lat": 40.44015989462932, - "lon": -79.94262085685187, - "active": false - }, - { - "key": "e728c45e-ace8-4e72-a543-f5f9f6a16271", - "lat": 40.44015235773819, - "lon": -79.94265633387789, - "active": false - }, - { - "key": "6337def5-f713-4240-99a4-ca67d3034412", - "lat": 40.44014590556792, - "lon": -79.9426884035854, - "active": false - }, - { - "key": "9173f701-9169-4c34-9ceb-6ee7537b597d", - "lat": 40.44013830111759, - "lon": -79.94272175943527, - "active": false - }, - { - "key": "43785b86-3ab5-4801-9564-397efd7edf7c", - "lat": 40.44013192834385, - "lon": -79.94274899917808, - "active": false - }, - { - "key": "024ed97a-ca51-474e-9b79-17e0094aa279", - "lat": 40.44012353628019, - "lon": -79.9427838410542, - "active": false - }, - { - "key": "96be126d-a9f1-4c97-90ae-077fad6cac3b", - "lat": 40.44011446835821, - "lon": -79.94282015501396, - "active": false - }, - { - "key": "002d8b2f-5f37-47c5-99d4-41515be4662c", - "lat": 40.4401062541137, - "lon": -79.94284975418145, - "active": false - }, - { - "key": "5c3bc340-9105-4a5f-ae6e-2b2ab3343d1a", - "lat": 40.44009654949487, - "lon": -79.94287935429523, - "active": false - }, - { - "key": "2f45d9e2-eeea-4076-8749-b42c524816ec", - "lat": 40.44008874525628, - "lon": -79.94290183827034, - "active": false - }, - { - "key": "490e47f6-199d-454a-9132-1821f546f468", - "lat": 40.44007769441906, - "lon": -79.94293201740985, - "active": false - }, - { - "key": "14f44a74-f52b-4fdd-9dbe-70653e6fbc60", - "lat": 40.44006566443712, - "lon": -79.94296290246079, - "active": false - }, - { - "key": "7e5f33ee-2916-4115-a10b-58df9a71f74e", - "lat": 40.44005558013261, - "lon": -79.94298610027141, - "active": false - }, - { - "key": "54abd32a-483c-41ab-abf7-8d86c6a393c2", - "lat": 40.440044825378095, - "lon": -79.94300890408009, - "active": false - }, - { - "key": "4ddbd4e7-50d7-4488-ba70-507787f13aa2", - "lat": 40.44003368257203, - "lon": -79.9430320846492, - "active": false - }, - { - "key": "bce84f47-fee3-4904-9718-c9462a7116a5", - "lat": 40.44002209042284, - "lon": -79.94305568842675, - "active": false - }, - { - "key": "694c7d52-9373-4209-a51b-2f24f6241cb7", - "lat": 40.440010040391535, - "lon": -79.94307922940163, - "active": false - }, - { - "key": "d6280412-5cca-439a-beaf-f3afdc5f3b77", - "lat": 40.439997679048695, - "lon": -79.94310289358687, - "active": false - }, - { - "key": "630973e5-bdb1-4bc4-a475-f3acfdd9c66c", - "lat": 40.43998911405136, - "lon": -79.94311854930507, - "active": false - }, - { - "key": "f44d400b-147b-431d-9429-dd091b3aeb2f", - "lat": 40.439970876182045, - "lon": -79.9431497325715, - "active": false - }, - { - "key": "71d4473d-ff26-40b6-9364-b5b7ee6acb66", - "lat": 40.43996138156864, - "lon": -79.94316533520437, - "active": false - }, - { - "key": "f904ef06-6d78-4e21-97cd-b773fc51cba2", - "lat": 40.4399409766366, - "lon": -79.94319641682368, - "active": false - }, - { - "key": "d144115e-acd5-472b-b417-7e429c581dd5", - "lat": 40.43992461750124, - "lon": -79.94321979773947, - "active": false - }, - { - "key": "8728c090-6b4d-44dd-91a8-d9d9e1e53421", - "lat": 40.43990267805518, - "lon": -79.94325010269372, - "active": false - }, - { - "key": "8a2d521d-9285-4ee7-b822-50c38b19c115", - "lat": 40.43987422066489, - "lon": -79.94328746599899, - "active": false - }, - { - "key": "12cca678-f2e4-4608-a27a-6089ce09aab7", - "lat": 40.43985036004293, - "lon": -79.94331554799935, - "active": false - }, - { - "key": "f016800d-7ada-4908-9450-37f44ee1384e", - "lat": 40.439819711707116, - "lon": -79.94335160315944, - "active": false - }, - { - "key": "ecff449c-a20a-45d5-8645-4ac11d4e7bca", - "lat": 40.439789317861106, - "lon": -79.94338843985861, - "active": false - }, - { - "key": "b8a595c0-66b6-4d49-acbc-6ae99c70d74e", - "lat": 40.43976528501452, - "lon": -79.94341690820184, - "active": false - }, - { - "key": "b523da69-2042-4fef-ba99-cf2e08cc35f7", - "lat": 40.439736682936164, - "lon": -79.94345214813083, - "active": false - }, - { - "key": "3d0ce67c-beba-468b-a135-8bf7308ab749", - "lat": 40.43970847727155, - "lon": -79.94348734334174, - "active": false - }, - { - "key": "0c6d07bc-a819-4722-be98-3b607b2d51cb", - "lat": 40.439685713972416, - "lon": -79.94351581864235, - "active": false - }, - { - "key": "0dc4a77c-d958-484a-80c7-8724f105429d", - "lat": 40.43965818543157, - "lon": -79.94355171162415, - "active": false - }, - { - "key": "b26ac0bb-2bc0-4ffa-88ea-14155483e122", - "lat": 40.43963088748962, - "lon": -79.94358795067338, - "active": false - }, - { - "key": "dd541da9-d24b-435d-bfc8-d06dd514ae32", - "lat": 40.43960334649435, - "lon": -79.94362437684987, - "active": false - }, - { - "key": "10bd655a-305e-4b7c-b1b2-8d94da7c116c", - "lat": 40.43957524057067, - "lon": -79.94365963911616, - "active": false - }, - { - "key": "5378d37f-e18f-4b3d-8a52-7c64a2d75c83", - "lat": 40.43955243273444, - "lon": -79.94368729149015, - "active": false - }, - { - "key": "6ab85a9c-0433-4457-bdea-f65a5d832d87", - "lat": 40.43952985196559, - "lon": -79.94371510693492, - "active": false - }, - { - "key": "dd6111e9-a079-484f-aeef-7f0f31c5e981", - "lat": 40.43950316091657, - "lon": -79.9437463919141, - "active": false - }, - { - "key": "ad042b3f-6a51-446c-9447-b35b1097a3e4", - "lat": 40.43947742996715, - "lon": -79.94377767689345, - "active": false - }, - { - "key": "d9adf7af-676f-486a-af11-9a7b772d18f2", - "lat": 40.43944939474232, - "lon": -79.94380997106566, - "active": false - }, - { - "key": "c3607440-bb27-46d1-a411-0b51ed217205", - "lat": 40.43942198990266, - "lon": -79.94384290586784, - "active": false - }, - { - "key": "1aeca3a8-a6c4-4af6-9119-5def171fb052", - "lat": 40.439395619611, - "lon": -79.94387414169448, - "active": false - }, - { - "key": "47d5c03a-03d0-4ad4-bbf0-d02ec57bbb7a", - "lat": 40.43936869179148, - "lon": -79.94390531524947, - "active": false - }, - { - "key": "f3ede280-3e1b-426a-abb0-c344ab86077e", - "lat": 40.439341747362974, - "lon": -79.94393651472089, - "active": false - }, - { - "key": "b38ad123-01c6-4556-8578-7b096844517d", - "lat": 40.43931985702555, - "lon": -79.94396194772337, - "active": false - }, - { - "key": "46656886-5d57-40d6-9f8e-921e50775047", - "lat": 40.43929241789707, - "lon": -79.943993620711, - "active": false - }, - { - "key": "9d79415d-32cf-41a3-b388-50d571e0b4db", - "lat": 40.43926551903194, - "lon": -79.94402469725979, - "active": false - }, - { - "key": "f5774051-2d5d-432d-949d-ee5dbbaf5b3e", - "lat": 40.43923882421314, - "lon": -79.94405455624151, - "active": false - }, - { - "key": "bf0b6cc6-7de5-4292-a818-3c127667f698", - "lat": 40.43921292646347, - "lon": -79.94408367574798, - "active": false - }, - { - "key": "fb28331c-a3fa-4333-a01f-e7d5f66a5816", - "lat": 40.439192276622094, - "lon": -79.9441056645799, - "active": false - }, - { - "key": "21ff6984-7585-48b8-b46c-07953fab1687", - "lat": 40.43916712162242, - "lon": -79.94413190359477, - "active": false - }, - { - "key": "4d9a7cc0-4229-4384-b06e-15eb0f264518", - "lat": 40.43914139054455, - "lon": -79.94415839490787, - "active": false - }, - { - "key": "b5409543-e636-4822-b41d-0d24c2240a18", - "lat": 40.4391158303605, - "lon": -79.9441858469528, - "active": false - }, - { - "key": "d71a6341-fb4b-4f69-a44b-72227a38692f", - "lat": 40.4390908208169, - "lon": -79.94421465220522, - "active": false - }, - { - "key": "83e48c16-34e5-4a70-b46b-7060c2cdea7c", - "lat": 40.439068136133486, - "lon": -79.9442444749034, - "active": false - }, - { - "key": "e410b9c4-6535-4a3e-8945-03955f2e8b31", - "lat": 40.43904779436164, - "lon": -79.94427530432857, - "active": false - }, - { - "key": "6cdbff15-99c6-4372-809c-cc3831392ed0", - "lat": 40.43902911631064, - "lon": -79.94430775838443, - "active": false - }, - { - "key": "fc9e4c8c-4c18-446b-8852-1c976465eb7f", - "lat": 40.43901004534296, - "lon": -79.94434055103522, - "active": false - }, - { - "key": "f9e4c0c4-a34d-4123-9222-48eafa83abb5", - "lat": 40.43899554933613, - "lon": -79.94436782012558, - "active": false - }, - { - "key": "26cbfaa5-1e77-42cd-a064-2068bbd90767", - "lat": 40.438979069994296, - "lon": -79.94440213802346, - "active": false - }, - { - "key": "5ad64f32-96e0-403a-8068-f829de0b4ef1", - "lat": 40.43896430042601, - "lon": -79.944436377861, - "active": false - }, - { - "key": "3a5ffe7c-e2a4-4cb9-b8ed-199e5ac8424b", - "lat": 40.438950459821356, - "lon": -79.94447097348215, - "active": false - }, - { - "key": "be18f178-e62f-435e-82fc-be6393d0ca55", - "lat": 40.43894012337897, - "lon": -79.94449884448866, - "active": false - }, - { - "key": "a10892a7-e08a-401a-aef7-b205dde2d734", - "lat": 40.43892868796678, - "lon": -79.94453463284829, - "active": false - }, - { - "key": "eec33a75-995a-4674-89e9-e180ff117f6d", - "lat": 40.438917671876496, - "lon": -79.94457097227851, - "active": false - }, - { - "key": "29b19ded-76c2-4abd-9954-269ee8b5ee66", - "lat": 40.438906532101115, - "lon": -79.94460643452383, - "active": false - }, - { - "key": "05d5d926-daf2-49e3-b579-e72ca69389e3", - "lat": 40.438898160343925, - "lon": -79.94463502664145, - "active": false - }, - { - "key": "8686961f-b26f-4b76-80a0-07b0ec321ccd", - "lat": 40.438890693480715, - "lon": -79.94466339523939, - "active": false - }, - { - "key": "d5e33a7d-2cbd-4dfc-81f2-cba699004194", - "lat": 40.438881997382715, - "lon": -79.9446987776632, - "active": false - }, - { - "key": "d6740c47-2180-4e85-8a05-6ac61a1899be", - "lat": 40.4388725158032, - "lon": -79.94473402652191, - "active": false - }, - { - "key": "17912952-f251-4490-b6d2-c3d02a981a8d", - "lat": 40.438863850099516, - "lon": -79.94476785834306, - "active": false - }, - { - "key": "256a02cc-50c9-46be-b920-164b0a93e8ad", - "lat": 40.43885693766954, - "lon": -79.94480158717268, - "active": false - }, - { - "key": "8a77256a-6cad-462a-ab02-b0618d482950", - "lat": 40.438850317164366, - "lon": -79.94483579937494, - "active": false - }, - { - "key": "b2662eae-1305-47c4-8955-1075f67f642a", - "lat": 40.43884550585431, - "lon": -79.9448626225068, - "active": false - }, - { - "key": "085359bc-144f-463d-97a4-cc412dec83e1", - "lat": 40.43883933337918, - "lon": -79.94489582820631, - "active": false - }, - { - "key": "ae9be218-573f-417e-9304-a951a02ca842", - "lat": 40.43883343793636, - "lon": -79.94492896395779, - "active": false - }, - { - "key": "f3398c87-0e9d-4872-9b5f-3b81a77f7e51", - "lat": 40.438827830978965, - "lon": -79.94495530578256, - "active": false - }, - { - "key": "f9f07bc5-6374-401c-adf2-a17c821d3b83", - "lat": 40.43882076470383, - "lon": -79.94498776659736, - "active": false - }, - { - "key": "1f7f243f-ae41-476f-91ed-1e13c0edfbd8", - "lat": 40.43881569708881, - "lon": -79.945013204725, - "active": false - }, - { - "key": "4ced4415-3465-4539-8015-6b7f0dc6a8c9", - "lat": 40.438809521963286, - "lon": -79.94504537593778, - "active": false - }, - { - "key": "9544aa6b-2e8c-45c2-ac7d-05818f5df092", - "lat": 40.43880321644666, - "lon": -79.94507676262911, - "active": false - }, - { - "key": "58ef0674-94c3-43c5-9497-3aefc0b2aaa5", - "lat": 40.438798022897366, - "lon": -79.945101295366, - "active": false - }, - { - "key": "5da88a28-a0d5-4aff-84aa-b801e464d114", - "lat": 40.4387910223078, - "lon": -79.94513234581417, - "active": false - }, - { - "key": "c03a1df7-adac-47ea-ab82-3bc0457868ae", - "lat": 40.43878470713023, - "lon": -79.94516295822771, - "active": false - }, - { - "key": "d61222a4-6ef5-4518-83f2-7978ba6a7bd4", - "lat": 40.43877853494159, - "lon": -79.94519306363861, - "active": false - }, - { - "key": "f77304c9-ebd0-4ab5-9af7-5437ca98121a", - "lat": 40.43877392203422, - "lon": -79.94521635644787, - "active": false - }, - { - "key": "6d04e8c8-002b-4e0c-85ca-93b74b852020", - "lat": 40.43876813955743, - "lon": -79.94524514609223, - "active": false - }, - { - "key": "c8ac141b-1dbc-4185-ba0f-129760669df6", - "lat": 40.43876274052029, - "lon": -79.94527407183345, - "active": false - }, - { - "key": "3c8b5b82-6d26-4083-b048-64e46020a7a8", - "lat": 40.438756868522354, - "lon": -79.94530265492074, - "active": false - }, - { - "key": "71599bad-91f4-49c4-ba15-74335ecd6fc3", - "lat": 40.43875200905452, - "lon": -79.94532585054417, - "active": false - }, - { - "key": "0e41e288-0fd0-444c-a020-39106a81f492", - "lat": 40.438747757643505, - "lon": -79.94535440334204, - "active": false - }, - { - "key": "2fd69dfc-a073-43bc-a935-2e34e0bd17d3", - "lat": 40.4387435595206, - "lon": -79.94537681845613, - "active": false - }, - { - "key": "875a396a-680c-4a95-9f88-c7ed4cbeb568", - "lat": 40.43873997675136, - "lon": -79.94539948299858, - "active": false - }, - { - "key": "dcdcfc78-f06f-484f-80f9-290554d0242a", - "lat": 40.438735025006984, - "lon": -79.94542773037543, - "active": false - }, - { - "key": "cb57b5af-d767-4f87-8eec-94b0f619f472", - "lat": 40.43873196901191, - "lon": -79.94545590920727, - "active": false - }, - { - "key": "661b0483-1a9a-4828-8be4-a110184b2bc0", - "lat": 40.43872865620182, - "lon": -79.94548394599818, - "active": false - }, - { - "key": "a6c38b99-e6c3-4a9f-b984-6cab3b6af39f", - "lat": 40.43872584163457, - "lon": -79.94550606298525, - "active": false - }, - { - "key": "5193c864-da21-48cd-8525-db6bd5602fa8", - "lat": 40.438722078385325, - "lon": -79.94553333950866, - "active": false - }, - { - "key": "c0698bdb-0944-4205-912f-07831b37043e", - "lat": 40.43871916541325, - "lon": -79.9455600031366, - "active": false - }, - { - "key": "300c58fc-90d1-4325-985a-daa033867f2d", - "lat": 40.438716262265295, - "lon": -79.94558641024302, - "active": false - }, - { - "key": "62bf1aa9-9011-49d5-9316-2701042a04d5", - "lat": 40.43871481143633, - "lon": -79.945607648329, - "active": false - }, - { - "key": "f81767f4-9181-471f-b763-4272b124d686", - "lat": 40.43871406365869, - "lon": -79.94563411025634, - "active": false - }, - { - "key": "96937976-a2a5-4279-a6f3-4f2633b6010e", - "lat": 40.43871355634512, - "lon": -79.94565483348431, - "active": false - }, - { - "key": "ca5f4382-a834-49f4-842f-d813e4c42e71", - "lat": 40.438712805375914, - "lon": -79.94568011618236, - "active": false - }, - { - "key": "5538ad69-4c49-42b1-b66b-aac869a8d72d", - "lat": 40.43871228540668, - "lon": -79.94570029529721, - "active": false - }, - { - "key": "82627fbc-98d9-45aa-b02b-6199244375d3", - "lat": 40.43871123075945, - "lon": -79.94572443019443, - "active": false - }, - { - "key": "05bf730e-0706-4732-99f5-17786b0e2857", - "lat": 40.438710518653764, - "lon": -79.9457487844526, - "active": false - }, - { - "key": "4ba1bf2b-0c3e-4824-b405-e48d629da93c", - "lat": 40.43871112553711, - "lon": -79.94577330326126, - "active": false - }, - { - "key": "a44e720b-0c98-45dc-81fe-8b7b2e8a522a", - "lat": 40.43871226085225, - "lon": -79.94579762814733, - "active": false - }, - { - "key": "178aaaed-e112-49ad-9850-8a8c19f48c17", - "lat": 40.4387138911969, - "lon": -79.9458159188809, - "active": false - }, - { - "key": "7fa226d7-6828-4d4c-8858-1dc6305e21f4", - "lat": 40.43871509502239, - "lon": -79.9458328346282, - "active": false - }, - { - "key": "b242b88b-d61b-4f22-a806-e144430da480", - "lat": 40.438717544646614, - "lon": -79.94585410958673, - "active": false - }, - { - "key": "4bc749da-8ef1-4dd6-8e2a-0fabbeaca95a", - "lat": 40.438719432463394, - "lon": -79.94586709577442, - "active": false - }, - { - "key": "cfe41f35-532f-42f2-a6cc-63b2701b418c", - "lat": 40.43872142983638, - "lon": -79.94588041038922, - "active": false - }, - { - "key": "ceb40a2f-f1df-4ba9-8c86-3df338f22ee3", - "lat": 40.43872346198698, - "lon": -79.94589340530288, - "active": false - }, - { - "key": "877ab5f3-1236-4a04-8c7a-cf3bc2d6aa11", - "lat": 40.43872539296819, - "lon": -79.94590625145486, - "active": false - }, - { - "key": "7b2e3c8e-17cd-4399-b73b-0804cc84fe04", - "lat": 40.43872711884515, - "lon": -79.94591459444392, - "active": false - }, - { - "key": "c57dec5a-e538-48fe-9fe0-9feeeda504e9", - "lat": 40.43872972111318, - "lon": -79.9459271013221, - "active": false - }, - { - "key": "a2d52fff-671f-425f-9e2d-c1277e5ab3f4", - "lat": 40.43873117230554, - "lon": -79.94593562550033, - "active": false - }, - { - "key": "82855618-103d-4a82-8b70-66eb2cf785c4", - "lat": 40.43873341409136, - "lon": -79.94594823693284, - "active": false - }, - { - "key": "4eb63bec-2d7f-408c-9aa6-4dde6b8faf31", - "lat": 40.43873733449343, - "lon": -79.94596466257568, - "active": false - }, - { - "key": "062e8c34-37d7-4494-8cfe-96703d4d685c", - "lat": 40.43874201946106, - "lon": -79.94598026298043, - "active": false - }, - { - "key": "41943dd0-f888-4068-bad8-a8acd64f0f1b", - "lat": 40.43874788206833, - "lon": -79.94599890117104, - "active": false - }, - { - "key": "6ff01139-c5d8-4496-9df3-297dd52abb65", - "lat": 40.43875374704486, - "lon": -79.94601683821116, - "active": false - }, - { - "key": "75fd1d26-4cfd-4b54-a1b2-4f91ca80b1ba", - "lat": 40.438758428567034, - "lon": -79.9460308213025, - "active": false - }, - { - "key": "9c6445ac-cada-44b4-9e34-928f33410b4f", - "lat": 40.4387651854828, - "lon": -79.94604766772028, - "active": false - }, - { - "key": "6ca3cc3b-58c0-4dc4-af39-ef9eb6b35c2f", - "lat": 40.43877222995209, - "lon": -79.94606337730153, - "active": false - }, - { - "key": "52cae929-ffa2-4329-8fec-0cf436a6c905", - "lat": 40.43877911460433, - "lon": -79.94607875953216, - "active": false - }, - { - "key": "c40178d2-e355-4451-bea1-d6f6b518d719", - "lat": 40.438784229457546, - "lon": -79.94609152130154, - "active": false - }, - { - "key": "daaaa6d2-ecfe-4df1-b663-1d1bb9c11fac", - "lat": 40.43879029065399, - "lon": -79.94610706638287, - "active": false - }, - { - "key": "cfa8083c-b25e-42af-8339-2027ecfb4c90", - "lat": 40.438796215738556, - "lon": -79.94612174171968, - "active": false - }, - { - "key": "4d38c76d-58ab-489d-8277-251623fff0a8", - "lat": 40.43880278573204, - "lon": -79.9461359326546, - "active": false - }, - { - "key": "07267d5f-5cf3-4c44-a055-130bf707670c", - "lat": 40.43880774745415, - "lon": -79.94614645200542, - "active": false - }, - { - "key": "c3469b37-1ef8-4829-b244-2b31638352d6", - "lat": 40.43881361221674, - "lon": -79.94615956290444, - "active": false - }, - { - "key": "fe45735f-a967-487f-b93e-1de93cd7b81b", - "lat": 40.43881918704324, - "lon": -79.94617163680488, - "active": false - }, - { - "key": "38acd721-fac9-48d3-ba1a-a6445df8d528", - "lat": 40.43882496914245, - "lon": -79.94618322260857, - "active": false - }, - { - "key": "c64fabcf-720a-42de-84cc-95a35acaafd4", - "lat": 40.438829880244825, - "lon": -79.94619276714832, - "active": false - }, - { - "key": "ee77f246-39df-4db9-bec6-f74e19abc723", - "lat": 40.43883530291987, - "lon": -79.94620338712906, - "active": false - }, - { - "key": "9f57adc9-74c4-42a6-b46f-da734c08a079", - "lat": 40.4388409302237, - "lon": -79.94621414154003, - "active": false - }, - { - "key": "a13578e2-0bc0-44f4-9c79-7e86becd9ded", - "lat": 40.4388460459541, - "lon": -79.94622449266063, - "active": false - }, - { - "key": "d6d8dce2-a94c-4a22-8598-ff32bba5438d", - "lat": 40.43885096397728, - "lon": -79.9462343693864, - "active": false - }, - { - "key": "3006043b-fcbc-472d-9c4f-da18991a0886", - "lat": 40.43886190471591, - "lon": -79.94625487387157, - "active": false - }, - { - "key": "946bc0c9-30c2-45e8-9149-0c59a400a113", - "lat": 40.43887388286284, - "lon": -79.94627885089754, - "active": false - }, - { - "key": "20e972d2-2f0f-46b7-88f6-cefb55f0ca49", - "lat": 40.438883816153044, - "lon": -79.9462967311201, - "active": false - }, - { - "key": "3c20eb0b-49fc-4569-8a89-883370ff858c", - "lat": 40.43889374944194, - "lon": -79.94631448083008, - "active": false - }, - { - "key": "f44e7812-5c48-46f4-bf23-954c68b2ff0f", - "lat": 40.43890335408435, - "lon": -79.94633023165694, - "active": false - }, - { - "key": "1b5fecf3-ced4-4ece-822e-8761459c687b", - "lat": 40.43891330874774, - "lon": -79.9463461915718, - "active": false - }, - { - "key": "b3fd5178-251e-45b4-b348-b8dd961f10e0", - "lat": 40.43892289889513, - "lon": -79.94636123613915, - "active": false - }, - { - "key": "591e57a8-ba92-4054-a8fc-be20e7331efd", - "lat": 40.438932887522164, - "lon": -79.94637367980661, - "active": false - }, - { - "key": "bcd464f8-92b7-43c6-89f6-e00f488d3843", - "lat": 40.43894356196593, - "lon": -79.94638633031813, - "active": false - }, - { - "key": "7233cf04-8600-4caa-bf71-1443bcd6b64d", - "lat": 40.43895907527774, - "lon": -79.94640543749028, - "active": false - }, - { - "key": "281cc76b-b42e-43da-8ff6-e12811469dad", - "lat": 40.438977057764234, - "lon": -79.94642456441743, - "active": false - }, - { - "key": "a6344c1c-ba92-4598-be8b-156a2f9dcb48", - "lat": 40.438996550912066, - "lon": -79.94644272664922, - "active": false - }, - { - "key": "5adf7b87-2fc1-4aa5-bc11-203079eef2eb", - "lat": 40.43901616959216, - "lon": -79.94645976664646, - "active": false - }, - { - "key": "370313c9-965f-40cb-930a-15a0c0a15cc7", - "lat": 40.439035709161324, - "lon": -79.94647528956462, - "active": false - }, - { - "key": "84b04085-80d4-42de-83c2-597e4d0f402b", - "lat": 40.43905489096071, - "lon": -79.94649064492631, - "active": false - }, - { - "key": "3b6560bf-22c8-43d0-bc4f-0fef224e4749", - "lat": 40.43907424071881, - "lon": -79.94650574080826, - "active": false - }, - { - "key": "9a355791-79f2-4a28-ad3a-ce5212701329", - "lat": 40.43909091700305, - "lon": -79.9465180214022, - "active": false - }, - { - "key": "a4d8dfd4-da35-428f-8ef8-4ae1d42bb45a", - "lat": 40.43911108039224, - "lon": -79.94653216933786, - "active": false - }, - { - "key": "08a079fa-3ece-4fc5-bc7d-6588cefd8cab", - "lat": 40.439137750132396, - "lon": -79.94654971307547, - "active": false - }, - { - "key": "a7ec8b88-ccd0-46e1-8ef2-5788487b9e6e", - "lat": 40.43915926289782, - "lon": -79.94656393832328, - "active": false - }, - { - "key": "25c8d309-3777-48f8-88a2-8210a6f84b8a", - "lat": 40.43918622860413, - "lon": -79.94658101249107, - "active": false - }, - { - "key": "5faff7da-b028-4002-bada-33faef38c39e", - "lat": 40.43920702473323, - "lon": -79.94659482816692, - "active": false - }, - { - "key": "b17f8c54-0ed9-49af-8d6f-cb67b4174a95", - "lat": 40.43923245588456, - "lon": -79.94661134930203, - "active": false - }, - { - "key": "7ce5c7b6-b9e0-49fa-8166-6a5400289768", - "lat": 40.43925783332006, - "lon": -79.94662744880569, - "active": false - }, - { - "key": "86ebd6fc-7c00-4536-87db-2ead7050ea3b", - "lat": 40.43928291178657, - "lon": -79.94664353888622, - "active": false - }, - { - "key": "b875a4df-e4b8-4a2b-a820-dd8bd1c7c3c8", - "lat": 40.439307744423886, - "lon": -79.94665944236259, - "active": false - }, - { - "key": "1ae9b874-0a42-4a72-b721-d25af01a8ddc", - "lat": 40.43933294021126, - "lon": -79.94667251562251, - "active": false - }, - { - "key": "30c238df-0bb7-4d99-ba3b-0451600dfd47", - "lat": 40.439352426639246, - "lon": -79.94668250891253, - "active": false - }, - { - "key": "5567a06e-a5ff-4211-a3a0-7aa0ed2e89c9", - "lat": 40.43937643034842, - "lon": -79.94669638509824, - "active": false - }, - { - "key": "9f20d768-c046-4680-af75-9d80b0259f08", - "lat": 40.43939971300403, - "lon": -79.94671083701833, - "active": false - }, - { - "key": "7e66378e-ed99-42b1-bc4c-4c538beffd54", - "lat": 40.43941820522697, - "lon": -79.94672211753061, - "active": false - }, - { - "key": "c3845494-e6d9-461b-8722-a682a835ddcb", - "lat": 40.439441156803476, - "lon": -79.94673642454609, - "active": false - }, - { - "key": "b8ce82dc-1882-4a8d-bd10-50e4994cf8b5", - "lat": 40.439464064072304, - "lon": -79.94675109217224, - "active": false - }, - { - "key": "ba77a37b-67d4-4251-99c3-8038cb336f5f", - "lat": 40.439487263796934, - "lon": -79.9467658136597, - "active": false - }, - { - "key": "47792717-083a-45f0-ab72-07206c6bbf95", - "lat": 40.43951040913704, - "lon": -79.94678061282721, - "active": false - }, - { - "key": "0612168e-f9aa-48e0-8cbd-0a7e9368314b", - "lat": 40.43952898448855, - "lon": -79.94679224592917, - "active": false - }, - { - "key": "f6f9f1a1-99bd-4c29-a586-8c4361e0d4fd", - "lat": 40.43955222195453, - "lon": -79.94680651520103, - "active": false - }, - { - "key": "2388b3c6-a36e-4232-bbe7-4a4f5341a3c0", - "lat": 40.43957489372849, - "lon": -79.94682205639204, - "active": false - }, - { - "key": "20a2c16e-5969-4766-9b77-d5b8ff2f64ed", - "lat": 40.43959318227675, - "lon": -79.94683558671473, - "active": false - }, - { - "key": "38a46d60-8a23-480a-8392-446662d45c57", - "lat": 40.43961594367841, - "lon": -79.9468521532125, - "active": false - }, - { - "key": "3e48246f-813f-46f5-8821-dab22f7bb146", - "lat": 40.43963809287214, - "lon": -79.94686940025345, - "active": false - }, - { - "key": "80021a9c-24d4-4f1f-aa5b-31d4951c4e3f", - "lat": 40.43965679506366, - "lon": -79.94688415533338, - "active": false - }, - { - "key": "f31b1075-72b3-425c-bba2-1335bf5e80b1", - "lat": 40.43967992970369, - "lon": -79.94690265977336, - "active": false - }, - { - "key": "96aadfa6-ebbc-4102-8844-b15188900f2f", - "lat": 40.43970305937309, - "lon": -79.94692214641911, - "active": false - }, - { - "key": "9f65fce7-ba28-4109-bb2a-322e4dff4546", - "lat": 40.43972657301413, - "lon": -79.9469410279466, - "active": false - }, - { - "key": "61c93034-b3e1-4e41-bd7b-84a8b4ce39ef", - "lat": 40.439750009200935, - "lon": -79.94696188015523, - "active": false - }, - { - "key": "0aa2e361-3f5f-4fe4-a283-fff8bf8f3b33", - "lat": 40.439768327547554, - "lon": -79.94697939323969, - "active": false - }, - { - "key": "8b182a77-bb86-4d75-91cf-6abc39e4a9fd", - "lat": 40.43979118638673, - "lon": -79.94700185163076, - "active": false - }, - { - "key": "2b8b3fca-c0de-4d7f-83b6-6a95211104ff", - "lat": 40.43981455488587, - "lon": -79.94702536225243, - "active": false - }, - { - "key": "3e52d4d6-189d-4c31-be4c-4ec23d85eea1", - "lat": 40.439833547178615, - "lon": -79.94704451057538, - "active": false - }, - { - "key": "62822213-b136-42c2-8ecf-006ddd9e6796", - "lat": 40.43985247918085, - "lon": -79.94706390023387, - "active": false - }, - { - "key": "6fb0d045-47d9-47b3-9039-664d803df734", - "lat": 40.43987534337002, - "lon": -79.94708905399682, - "active": false - }, - { - "key": "9de74d8a-1780-4c3f-8426-f19f3a95aed4", - "lat": 40.43989799447451, - "lon": -79.94711395255177, - "active": false - }, - { - "key": "1bd2c1f4-5bd1-4f59-b232-741fcdec7f37", - "lat": 40.43992137541799, - "lon": -79.94713952712266, - "active": false - }, - { - "key": "e38bb8dc-66c5-48e5-b676-a153d9ca95ea", - "lat": 40.439944769798366, - "lon": -79.94716613852795, - "active": false - }, - { - "key": "e78e154e-b0fe-4f27-b3ce-c9e9dcea942b", - "lat": 40.43996785705736, - "lon": -79.94719335282885, - "active": false - }, - { - "key": "a3b1e42e-db7e-4b1c-89a7-c9ec943834c5", - "lat": 40.43999029708601, - "lon": -79.9472221205035, - "active": false - }, - { - "key": "dfe612bb-d106-44d8-8607-dfd24a5c6f11", - "lat": 40.44001255021607, - "lon": -79.94725012641982, - "active": false - }, - { - "key": "6af03cc3-0212-4754-9c66-dd6736f36dcd", - "lat": 40.44003447137256, - "lon": -79.94727959004373, - "active": false - }, - { - "key": "edfb6c51-de06-40d9-932c-e3c8f1a1a70e", - "lat": 40.4400555493886, - "lon": -79.94731014051231, - "active": false - }, - { - "key": "fd5ac1fc-c33b-40b0-8ce2-fe834b299c88", - "lat": 40.44007706580607, - "lon": -79.94734075170038, - "active": false - }, - { - "key": "dfe1876b-4c64-466e-9ce2-ffb6118a61c2", - "lat": 40.44009996764975, - "lon": -79.94737094790095, - "active": false - }, - { - "key": "9a530f2b-1e9e-4357-99aa-9455b213330e", - "lat": 40.44012254323436, - "lon": -79.94740127939684, - "active": false - }, - { - "key": "88ad42ae-6c69-4755-8e65-e9eae9483bfe", - "lat": 40.44014497399407, - "lon": -79.94743164067337, - "active": false - }, - { - "key": "bfda0509-cbc9-461c-983d-a921e745f304", - "lat": 40.44016249938116, - "lon": -79.94745666687906, - "active": false - }, - { - "key": "cc8d7a2c-97a8-4a02-ab8f-d6b97098e40c", - "lat": 40.440175594511096, - "lon": -79.947475330537, - "active": false - }, - { - "key": "2ed32e77-251d-4c71-912c-4fc784d3229c", - "lat": 40.44018892214759, - "lon": -79.94749394940625, - "active": false - }, - { - "key": "59f7d0ca-f81c-4e28-aa82-e79f3a0b30d5", - "lat": 40.44020285896854, - "lon": -79.9475120776132, - "active": false - }, - { - "key": "ad522ed8-f2e8-4d4b-911f-f12fa4ddc1f1", - "lat": 40.44021702279605, - "lon": -79.94752993945423, - "active": false - }, - { - "key": "2658d429-0752-4c88-be09-036e6b8cc610", - "lat": 40.44023117778036, - "lon": -79.94754791893044, - "active": false - }, - { - "key": "b26b715f-9aa4-41d3-a453-5d530cdbab47", - "lat": 40.44024521380137, - "lon": -79.94756570577383, - "active": false - }, - { - "key": "ae6574b6-0011-4974-a5fd-985a08bed595", - "lat": 40.440268189895804, - "lon": -79.94759627353507, - "active": false - }, - { - "key": "5a77b266-a051-46f6-b711-fd25404871bd", - "lat": 40.44029022830608, - "lon": -79.9476272570982, - "active": false - }, - { - "key": "70672c46-2543-4278-8523-c974844ad618", - "lat": 40.44030751466816, - "lon": -79.94765246095875, - "active": false - }, - { - "key": "81d83e0e-b720-4fbe-b84f-4f3cf63bd5ca", - "lat": 40.440324510771816, - "lon": -79.94767833245707, - "active": false - }, - { - "key": "050e9139-12ef-4f6b-8fba-b903c5f9e0ca", - "lat": 40.440340993041936, - "lon": -79.94770457882342, - "active": false - }, - { - "key": "7037274d-a006-4501-b025-e12e222d389d", - "lat": 40.44035927108068, - "lon": -79.94772960082719, - "active": false - }, - { - "key": "1813e6df-3e46-4ea3-8259-ed3d86d86ee9", - "lat": 40.4403830908193, - "lon": -79.947761095013, - "active": false - }, - { - "key": "8410a744-b402-4a01-8105-f2972118aaaa", - "lat": 40.44041059699813, - "lon": -79.9477932789044, - "active": false - }, - { - "key": "a2ea02ad-265a-4451-be6b-cc1282a85464", - "lat": 40.44044011091461, - "lon": -79.94782651800529, - "active": false - }, - { - "key": "7d04f785-57cc-4f62-9cfa-ef3a93f08025", - "lat": 40.440468931504746, - "lon": -79.94785694546682, - "active": false - }, - { - "key": "f14af3be-8a57-4ac1-9774-bb4fad969de6", - "lat": 40.44049578376546, - "lon": -79.94788364316966, - "active": false - }, - { - "key": "4fcc8814-2324-4aea-8a6a-8aa4c6ddc522", - "lat": 40.44051952325101, - "lon": -79.94790497250466, - "active": false - }, - { - "key": "38588b19-4017-450d-83e3-8cccc668d0bd", - "lat": 40.44055258763956, - "lon": -79.94792683102494, - "active": false - }, - { - "key": "afc0f19a-f5e3-4df8-a10a-a2a9e84042ae", - "lat": 40.44059762589458, - "lon": -79.94794828695369, - "active": false - }, - { - "key": "5e5a3473-e627-46cb-a732-6a5afa4d4f3d", - "lat": 40.44064526754903, - "lon": -79.94796235753056, - "active": false - }, - { - "key": "c02392c9-b0ae-4593-b65e-ec8a891e4dde", - "lat": 40.44069704892641, - "lon": -79.94796911694424, - "active": false - }, - { - "key": "b467aa39-bf39-46bb-b785-405c747d0b36", - "lat": 40.440745963695875, - "lon": -79.94797266289837, - "active": false - }, - { - "key": "c1b99e37-7b16-464f-ad94-a24186207c2e", - "lat": 40.44078524207797, - "lon": -79.94797134551666, - "active": false - }, - { - "key": "df5f579e-db30-4688-853b-6dda6d666bad", - "lat": 40.4408213813644, - "lon": -79.94796791608556, - "active": false - }, - { - "key": "95ed3944-29e3-4b8b-906f-a1fa497a23a5", - "lat": 40.44085169819512, - "lon": -79.94796475045689, - "active": false - }, - { - "key": "25b8fc7d-eb4f-4e7b-95f6-0e5695611176", - "lat": 40.440884989093085, - "lon": -79.94795829939342, - "active": false - }, - { - "key": "bc9bebde-03aa-44dc-950b-cd1ee526ece9", - "lat": 40.44091343275486, - "lon": -79.94794743108343, - "active": false - }, - { - "key": "cb13fe8a-4641-4888-9de6-70a9c1180e9a", - "lat": 40.440940290295856, - "lon": -79.9479340479996, - "active": false - }, - { - "key": "12d44052-4721-45e6-b57b-547e83164264", - "lat": 40.44096099951472, - "lon": -79.94792323419333, - "active": false - }, - { - "key": "2d1eaecb-fbc4-487d-b939-fa93020fddb3", - "lat": 40.44098559340036, - "lon": -79.94791023438032, - "active": false - }, - { - "key": "8451d85a-2f52-4a60-b0fe-832246b559a5", - "lat": 40.44100701645064, - "lon": -79.94789239732201, - "active": false - }, - { - "key": "9b3a3af8-1499-48aa-a833-a14c614e1deb", - "lat": 40.441025871698784, - "lon": -79.94787385925271, - "active": false - }, - { - "key": "256b6906-4f61-447e-ac5d-4b061531503e", - "lat": 40.44104289598526, - "lon": -79.94785511055493, - "active": false - }, - { - "key": "0387b5ba-39f2-411e-b475-127a0eb591cb", - "lat": 40.441055183970036, - "lon": -79.94783973332987, - "active": false - }, - { - "key": "87065e13-9f7a-408c-9bc6-2e856068cfbf", - "lat": 40.4410694838655, - "lon": -79.94782047290215, - "active": false - }, - { - "key": "a74c7604-4e7e-42ac-a6d6-1136d0574e35", - "lat": 40.441083167282265, - "lon": -79.94780291236192, - "active": false - }, - { - "key": "32aec36b-676e-4d76-8f5b-50678dd8a077", - "lat": 40.44109369215928, - "lon": -79.94778960320723, - "active": false - }, - { - "key": "a3be57d7-fe44-4ae9-8219-e014af6d97e2", - "lat": 40.44110569610537, - "lon": -79.94777333343195, - "active": false - }, - { - "key": "db46d709-680e-4404-9de5-26c41459ae42", - "lat": 40.44111651439194, - "lon": -79.9477580348075, - "active": false - }, - { - "key": "c7c9d2a2-3392-48c7-ba0c-c57a90259e43", - "lat": 40.441124713245, - "lon": -79.94774632752255, - "active": false - }, - { - "key": "4e4ae879-60b2-4c78-a67b-00dedd801454", - "lat": 40.4411350433641, - "lon": -79.94773326834995, - "active": false - }, - { - "key": "f07b387a-982f-4fe6-9769-bef280b674f9", - "lat": 40.44114428857152, - "lon": -79.94772191058412, - "active": false - }, - { - "key": "ed332c24-42e5-46c9-b49d-1aec63227f7d", - "lat": 40.441152929108284, - "lon": -79.94771142621573, - "active": false - }, - { - "key": "8c3cc960-2c0f-4c6a-9558-b16ee4938d65", - "lat": 40.44115913945887, - "lon": -79.94770336574474, - "active": false - }, - { - "key": "27d8c3a3-17d2-4bc9-89c3-cb32d7a04aa3", - "lat": 40.441166683991995, - "lon": -79.94769442859017, - "active": false - }, - { - "key": "a53677b6-4a00-4565-8a7a-e2a68018c41b", - "lat": 40.44117280817922, - "lon": -79.94768749685659, - "active": false - }, - { - "key": "ca3fa3d0-d9ee-404f-a072-e1879c0f87b0", - "lat": 40.44117880114107, - "lon": -79.94768138128885, - "active": false - }, - { - "key": "982acf80-fa89-41e6-ab38-473f1676cb9b", - "lat": 40.44118240899137, - "lon": -79.9476768441332, - "active": false - }, - { - "key": "98e19f00-ec2e-4c98-b4bb-6543ef72010a", - "lat": 40.4411857510975, - "lon": -79.94767270885997, - "active": false - }, - { - "key": "92865f9e-b141-4402-bb14-aa966cf3be3e", - "lat": 40.44119595846277, - "lon": -79.94766012543461, - "active": false - }, - { - "key": "2f7d092a-fbb5-41bd-b3ca-637cec172fc1", - "lat": 40.44120175623969, - "lon": -79.9476527562289, - "active": false - }, - { - "key": "ea917da9-3d7f-422e-972c-e71aac2cc85c", - "lat": 40.44120738401352, - "lon": -79.94764606566137, - "active": false - }, - { - "key": "cea60299-2296-421d-8d54-89024ab50013", - "lat": 40.441216004204, - "lon": -79.94763629809903, - "active": false - }, - { - "key": "c0790b31-e0c5-4eb0-a0fd-8a2e196a28a1", - "lat": 40.44122560454712, - "lon": -79.94762559721387, - "active": false - }, - { - "key": "3c90fdaa-40e7-414c-a63e-5c831828301f", - "lat": 40.441235640251065, - "lon": -79.94761355083845, - "active": false - }, - { - "key": "20f3c49a-89f6-4e0b-af6c-3677273dc6e5", - "lat": 40.441245912542556, - "lon": -79.94760115856657, - "active": false - }, - { - "key": "2c05ef6e-c5af-4fcb-ab11-39dacc731769", - "lat": 40.441253957365355, - "lon": -79.94759132811572, - "active": false - }, - { - "key": "2dadd19e-a09c-40ed-b487-1f01937b65bb", - "lat": 40.44126469677598, - "lon": -79.94757719402216, - "active": false - }, - { - "key": "a9f9f7b1-f69b-4daa-9cfd-6b1e9f1bd875", - "lat": 40.441275028372914, - "lon": -79.94756203074004, - "active": false - }, - { - "key": "6e09d583-e2dc-42d3-b73b-64fde8a4816a", - "lat": 40.441282727705094, - "lon": -79.94755065788141, - "active": false - }, - { - "key": "0909dd4e-7de3-4299-8448-905c151148cd", - "lat": 40.44129196769031, - "lon": -79.94753696861082, - "active": false - }, - { - "key": "03522321-7750-4f3a-9780-08201a1f7667", - "lat": 40.44129909105498, - "lon": -79.947526842414, - "active": false - }, - { - "key": "b46522f8-d6f2-43fa-8495-63da520382de", - "lat": 40.44130799497114, - "lon": -79.94751300233328, - "active": false - }, - { - "key": "8229ceab-924a-41fd-aa4f-c949e9997661", - "lat": 40.44131673078607, - "lon": -79.94749901038236, - "active": false - }, - { - "key": "de73e321-e6a1-44ec-82ae-6d08764d3970", - "lat": 40.44132567604631, - "lon": -79.94748455111998, - "active": false - }, - { - "key": "7716bc02-d28c-491a-a062-54fda32a92cd", - "lat": 40.4413345523756, - "lon": -79.9474696728087, - "active": false - }, - { - "key": "56c39fab-5057-4ac6-9d08-c99be7371746", - "lat": 40.44134397520264, - "lon": -79.9474557007067, - "active": false - }, - { - "key": "f122a7eb-7ad0-4169-a225-1c4976480264", - "lat": 40.44135180627177, - "lon": -79.94744338024972, - "active": false - }, - { - "key": "c0f5f60f-617a-41e2-966d-f720020ce463", - "lat": 40.44136139611367, - "lon": -79.94742714250248, - "active": false - }, - { - "key": "08d18626-6288-4834-8f8e-d6a92451cfad", - "lat": 40.441370837227126, - "lon": -79.94741194301105, - "active": false - }, - { - "key": "af6e45c7-fdca-498f-96f8-85d62326b846", - "lat": 40.441380352710844, - "lon": -79.94739685097814, - "active": false - }, - { - "key": "7c9df29f-1953-4f24-8c7a-f3d05509a67e", - "lat": 40.44138796097726, - "lon": -79.94738456688965, - "active": false - }, - { - "key": "df8d4952-d3cc-4405-a5c6-02d84efbbc27", - "lat": 40.44139769840925, - "lon": -79.94736900518778, - "active": false - }, - { - "key": "31fe7577-fc17-4241-af91-867ec0596f20", - "lat": 40.441406891849994, - "lon": -79.94735242759411, - "active": false - }, - { - "key": "7d273352-40cd-4cf1-882c-b7c49c617f86", - "lat": 40.44141562712367, - "lon": -79.9473358966809, - "active": false - }, - { - "key": "9fb88f4e-56ac-4ae8-b6ca-41f125c832cd", - "lat": 40.44142235276205, - "lon": -79.94732196348684, - "active": false - }, - { - "key": "c2f8d6b7-c50c-450e-8e1f-ff00dfd0961c", - "lat": 40.44142875469339, - "lon": -79.94730902763044, - "active": false - }, - { - "key": "8c8d8240-931a-4469-b121-d4e6346ea2df", - "lat": 40.441436374198716, - "lon": -79.94729219312536, - "active": false - }, - { - "key": "0eefb4f3-c65c-443b-8254-5da51eabd076", - "lat": 40.4414419308956, - "lon": -79.94727896485092, - "active": false - }, - { - "key": "457bc4a5-8db6-419e-b1f5-6332f7c31792", - "lat": 40.4414445140737, - "lon": -79.94727242583264, - "active": false - }, - { - "key": "763f14ca-93fc-41cb-bef3-e3856c8db4f2", - "lat": 40.44144930449349, - "lon": -79.94725823624138, - "active": false - }, - { - "key": "84d702ed-2e4a-415a-82b3-3d5ce479b5a0", - "lat": 40.44145142977496, - "lon": -79.94725114350942, - "active": false - }, - { - "key": "191bb508-06d0-41bd-a4a0-389cb9adcd78", - "lat": 40.44145518917162, - "lon": -79.94723691656267, - "active": false - }, - { - "key": "f68ad1e2-c5c3-479d-a264-01dafc78e1c9", - "lat": 40.441457521879045, - "lon": -79.94722603222304, - "active": false - }, - { - "key": "17efa97a-7682-40d3-97f6-6f9a78f04883", - "lat": 40.44145990341546, - "lon": -79.94721151170143, - "active": false - }, - { - "key": "7a8423ed-aa82-4d6b-a63e-ff769613adba", - "lat": 40.441462058862314, - "lon": -79.94719326218295, - "active": false - }, - { - "key": "5c9dcfa9-c517-4c37-9c6f-02edd1a186b8", - "lat": 40.4414635270357, - "lon": -79.94717873550876, - "active": false - }, - { - "key": "389a9b47-d402-441f-ae49-c107aac2ee59", - "lat": 40.44146403845801, - "lon": -79.94716038046543, - "active": false - }, - { - "key": "df556374-6b6d-4b2c-bb97-759f2939393c", - "lat": 40.441464227319095, - "lon": -79.94714582164117, - "active": false - }, - { - "key": "034dd1c3-3424-4b4e-bd67-9f26cdf34086", - "lat": 40.44146364056978, - "lon": -79.94712785071289, - "active": false - }, - { - "key": "fae73703-d47b-4c00-bab8-4be9d793ffe2", - "lat": 40.44146276824855, - "lon": -79.94711026657541, - "active": false - }, - { - "key": "048286ae-39e5-42c1-93f8-c7fb8ce4b66c", - "lat": 40.44146179222235, - "lon": -79.94709268248127, - "active": false - }, - { - "key": "e367f5eb-3197-4e25-aceb-4336c0583b95", - "lat": 40.44146068733923, - "lon": -79.94707896203576, - "active": false - }, - { - "key": "216b26ff-9b4c-42ff-a52d-5841fdb3c75a", - "lat": 40.4414597138217, - "lon": -79.94706511239777, - "active": false - }, - { - "key": "d7d26401-3b8b-423f-8f43-cdb745754558", - "lat": 40.441458736365384, - "lon": -79.94704854241658, - "active": false - }, - { - "key": "77c8d35b-1cf3-4c3c-ad03-c22fb5bc58bb", - "lat": 40.441457755665645, - "lon": -79.94703260007795, - "active": false - }, - { - "key": "204aecd8-514a-4b54-97c0-d5dcbaa70c33", - "lat": 40.44145644559129, - "lon": -79.94701624587574, - "active": false - }, - { - "key": "4e5f9e71-6929-4428-b346-b2402b18ee34", - "lat": 40.44145513575654, - "lon": -79.94700324480597, - "active": false - }, - { - "key": "9416c737-5175-4bfd-ac1f-8ecc84649f10", - "lat": 40.44145311462802, - "lon": -79.94698741402641, - "active": false - }, - { - "key": "d1cadc11-5910-4636-ad0d-6a01b520c2e3", - "lat": 40.441451402142235, - "lon": -79.94697126128418, - "active": false - }, - { - "key": "795be8e2-7021-4ffd-8ea5-7bf39337686c", - "lat": 40.44145018616112, - "lon": -79.94695907148852, - "active": false - }, - { - "key": "edf7ad29-e28a-4b50-bf95-de8189e3ce39", - "lat": 40.44144856440225, - "lon": -79.94694491767267, - "active": false - }, - { - "key": "45c4044f-37e9-480e-b5f8-fda858292927", - "lat": 40.441446316462496, - "lon": -79.94693042493923, - "active": false - }, - { - "key": "981fa996-05aa-4c91-968b-fa8b480a8fce", - "lat": 40.4414443665537, - "lon": -79.94691519110701, - "active": false - }, - { - "key": "41e6b694-02cb-4988-97e1-d4eaa51976d1", - "lat": 40.44144237871191, - "lon": -79.94689964747198, - "active": false - }, - { - "key": "2f89bab3-509d-4d11-8758-4cd3b14f53e5", - "lat": 40.441441119253234, - "lon": -79.94688752948153, - "active": false - }, - { - "key": "d0c3642a-4263-4c01-a0e9-e0c46ffb3ffe", - "lat": 40.441439269383714, - "lon": -79.94687160102467, - "active": false - }, - { - "key": "b9406b62-3b85-4d02-9d6d-348c670b196c", - "lat": 40.44143771579801, - "lon": -79.94685941262406, - "active": false - }, - { - "key": "f82ab805-a848-414b-9023-be910624bcc5", - "lat": 40.44143615313271, - "lon": -79.94684340621764, - "active": false - }, - { - "key": "87bdf2d9-222d-48f3-bd95-96b0ed6bb8d3", - "lat": 40.44143403199677, - "lon": -79.946827079824, - "active": false - }, - { - "key": "87084d54-715f-457a-8ea0-5110950782c3", - "lat": 40.44143191973669, - "lon": -79.94681025497769, - "active": false - }, - { - "key": "33e0deda-01dc-4361-8f62-70c52dbc4de8", - "lat": 40.441429934032136, - "lon": -79.94679738083912, - "active": false - }, - { - "key": "ae5b8643-7f6d-4cce-b917-5d247ba40a9b", - "lat": 40.4414275413873, - "lon": -79.94678025928383, - "active": false - }, - { - "key": "fd9e6fd7-c3cc-49dd-95f7-f10b93d52d46", - "lat": 40.441423947459285, - "lon": -79.9467566482477, - "active": false - }, - { - "key": "f9f61806-fe31-42ca-960b-bc56311a7399", - "lat": 40.441417101881804, - "lon": -79.94671504785084, - "active": false - }, - { - "key": "c886c6ea-f871-4cd3-bce2-47056b07f914", - "lat": 40.44140418170665, - "lon": -79.94664727470193, - "active": false - }, - { - "key": "b61ba471-377c-458a-92af-bb0b57a86684", - "lat": 40.44138491960012, - "lon": -79.9465521216605, - "active": false - }, - { - "key": "20e1ea21-3328-4f7b-be11-79fdf35b80d7", - "lat": 40.4413538038779, - "lon": -79.94640318646539, - "active": false - }, - { - "key": "1ba8afee-cc3c-411f-91a1-0022cd566dbd", - "lat": 40.44131898388635, - "lon": -79.94624646380882, - "active": false - }, - { - "key": "898a84ac-6a08-48f5-9a26-a8cb161fcad0", - "lat": 40.44126614664166, - "lon": -79.94599040251543, - "active": false - }, - { - "key": "2f9c88cd-751f-4a49-b1e1-5173dbaa3080", - "lat": 40.44121653769946, - "lon": -79.94576022498865, - "active": false - }, - { - "key": "fcda0941-a421-4edb-bcec-9f53b1fb64a2", - "lat": 40.44116134770805, - "lon": -79.94549378940913, - "active": false - }, - { - "key": "aff35207-9f7f-420d-bb00-bd418b664c79", - "lat": 40.441108018010574, - "lon": -79.94524120522036, - "active": false - }, - { - "key": "6b14e89d-c633-40a7-9ba0-30e189cedd74", - "lat": 40.44104769339873, - "lon": -79.94496051486551, - "active": false - }, - { - "key": "e2eb376c-7205-4c34-abbc-9eb5ebbd42cf", - "lat": 40.44099028415086, - "lon": -79.9446674434803, - "active": false - }, - { - "key": "16fac774-df8c-4315-b4b7-8710af7f1bbf", - "lat": 40.44091598280372, - "lon": -79.94430564349189, - "active": false - }, - { - "key": "c5be3969-4200-4ee3-95b5-abf6848d5b83", - "lat": 40.44085983189997, - "lon": -79.94403020430866, - "active": false - }, - { - "key": "85a672a1-5e9b-4869-a436-0007eac9360c", - "lat": 40.44078246835623, - "lon": -79.9436613125456, - "active": false - }, - { - "key": "f8c06db2-c7b6-4db0-b659-636ecf6e8cf2", - "lat": 40.44070136131911, - "lon": -79.94328586270674, - "active": false - }, - { - "key": "832261d6-d76a-49cf-ad9c-4eb649e16ed2", - "lat": 40.440628988803326, - "lon": -79.94293336613299, - "active": false - }, - { - "key": "b9d75e94-8c0f-4342-b471-965a50bebd71", - "lat": 40.440566598641055, - "lon": -79.94262349705194, - "active": false - }, - { - "key": "ff465702-02ea-4573-9587-fcaba7e0ce26", - "lat": 40.440505109015916, - "lon": -79.9423156325689, - "active": false - } + { + "key": "b14080a9-e73a-4944-aa36-6d0bcc59fb30", + "lat": 40.441674206728784, + "lon": -79.94163388344283, + "active": false + }, + { + "key": "a29030e1-962f-4202-aa49-09c884a049fe", + "lat": 40.44167437513235, + "lon": -79.94163388153763, + "active": false + }, + { + "key": "bd966b18-f1b6-4c3a-b30c-b2e673334861", + "lat": 40.44167445579479, + "lon": -79.94163387914878, + "active": false + }, + { + "key": "e4d6a28e-d814-4227-b076-a673b2eceec7", + "lat": 40.44167437773192, + "lon": -79.94163382054673, + "active": false + }, + { + "key": "4fd81ec5-574f-4b13-956d-a617f555c917", + "lat": 40.44167424952401, + "lon": -79.94163374653937, + "active": false + }, + { + "key": "9a4557ff-13ee-4257-94b6-6103e541b184", + "lat": 40.44167415491765, + "lon": -79.94163369253283, + "active": false + }, + { + "key": "e74098a1-2cad-46e3-a430-8a67e3a30380", + "lat": 40.44167411918154, + "lon": -79.9416336475982, + "active": false + }, + { + "key": "20c2d883-8ee8-4b0d-a6af-ae922230bf7b", + "lat": 40.441674111916804, + "lon": -79.94163375015339, + "active": false + }, + { + "key": "c40b36b0-80d5-4d11-9a7e-495369ebff1e", + "lat": 40.441674156423375, + "lon": -79.94163377325161, + "active": false + }, + { + "key": "f3415132-e6c3-41c5-b7a5-57e8b91c3b63", + "lat": 40.441674182280366, + "lon": -79.94163371082054, + "active": false + }, + { + "key": "1d13b1fc-16b7-457e-a4cf-0edf132822eb", + "lat": 40.441674255301336, + "lon": -79.94163375428995, + "active": false + }, + { + "key": "aa754c2f-e7dd-483a-bf39-a24429dacf82", + "lat": 40.44167424146994, + "lon": -79.94163389516072, + "active": false + }, + { + "key": "ef315f3e-892b-4491-b697-93c93a0942df", + "lat": 40.44167421442566, + "lon": -79.94163376914993, + "active": false + }, + { + "key": "b3329055-ce59-4973-a4fe-82127f65ece5", + "lat": 40.441674304256665, + "lon": -79.94163375571536, + "active": false + }, + { + "key": "5341210d-5959-4be6-9226-9f13c6fd0727", + "lat": 40.441674202963405, + "lon": -79.94163368493386, + "active": false + }, + { + "key": "f7202734-97c9-4af4-be8b-37577472f235", + "lat": 40.44167421651537, + "lon": -79.94163374313617, + "active": false + }, + { + "key": "b30471f2-b2b7-4cfb-a26b-ba8671768984", + "lat": 40.44167406982346, + "lon": -79.94163363770306, + "active": false + }, + { + "key": "5b5a7316-0257-4a15-a7f6-1862dffa8648", + "lat": 40.44167391222837, + "lon": -79.94163355183143, + "active": false + }, + { + "key": "973aab34-1e15-4ce9-8a2e-f276c534636b", + "lat": 40.44167408203141, + "lon": -79.94163335702804, + "active": false + }, + { + "key": "eb3131ed-a4b1-49ae-ac69-18f176683fda", + "lat": 40.44167387460884, + "lon": -79.94163340786241, + "active": false + }, + { + "key": "c785f2b5-2293-4319-9537-af29fc9b09e2", + "lat": 40.44167378153241, + "lon": -79.94163349894248, + "active": false + }, + { + "key": "f7f2130a-57a5-4d09-90cb-fe3e9c0ca7e7", + "lat": 40.441673767841294, + "lon": -79.94163345318458, + "active": false + }, + { + "key": "696653ac-1ece-4a99-ad43-425cff89df74", + "lat": 40.44167386846082, + "lon": -79.94163361689866, + "active": false + }, + { + "key": "fbd93788-ae6b-46d7-8dbf-9ce6fe51c13b", + "lat": 40.44167390234611, + "lon": -79.94163363904237, + "active": false + }, + { + "key": "2973a923-4b1a-47b9-8908-2e959a38ddb3", + "lat": 40.44167393987221, + "lon": -79.94163393736949, + "active": false + }, + { + "key": "741bfeef-970c-4a17-8d89-d1ecfd08943f", + "lat": 40.441673963186, + "lon": -79.94163403731656, + "active": false + }, + { + "key": "406dd516-f302-4578-87f5-785ab96483e7", + "lat": 40.44167412988648, + "lon": -79.94163401905176, + "active": false + }, + { + "key": "4dbbe41a-a9fb-4955-a3f3-3b5db61482fd", + "lat": 40.441674161683764, + "lon": -79.9416339458606, + "active": false + }, + { + "key": "65bc04f1-36dc-4f39-a4fa-c88a92653a89", + "lat": 40.44167412545795, + "lon": -79.94163381610406, + "active": false + }, + { + "key": "d175dfe1-0b78-48b3-a3d9-1ecf041b30e8", + "lat": 40.441674127437636, + "lon": -79.94163401817585, + "active": false + }, + { + "key": "65cf309b-42d4-4440-9d36-3a3730e80927", + "lat": 40.4416740572156, + "lon": -79.94163389007741, + "active": false + }, + { + "key": "350567bb-477e-44f6-87fa-3ebf198457f5", + "lat": 40.441671427904694, + "lon": -79.94163375956708, + "active": false + }, + { + "key": "ff6a84e3-d770-4511-bcd7-91db32eb1869", + "lat": 40.44166483443422, + "lon": -79.94163362111621, + "active": false + }, + { + "key": "eecd4bee-454b-4a47-b649-65d809a1bced", + "lat": 40.441656077306114, + "lon": -79.9416355922333, + "active": false + }, + { + "key": "14d44e31-7212-4423-bd71-92dc4a427451", + "lat": 40.441645233088906, + "lon": -79.94164007084402, + "active": false + }, + { + "key": "ba975e94-b587-41f2-994f-30d4491b8ba3", + "lat": 40.44163631137896, + "lon": -79.94164421356977, + "active": false + }, + { + "key": "cea217d5-7cb3-40d0-bf4c-2ea1afd76d3a", + "lat": 40.441629678898195, + "lon": -79.94164737616678, + "active": false + }, + { + "key": "4a7f3a61-dc7c-456e-8efd-ab7e7c720b37", + "lat": 40.44162778812216, + "lon": -79.94164854224772, + "active": false + }, + { + "key": "f67908d5-27f2-4434-a2c5-ff274aa01f77", + "lat": 40.44162852113008, + "lon": -79.9416480518442, + "active": false + }, + { + "key": "386f0b41-2eaa-4835-8351-a1bd5f6ce301", + "lat": 40.44162863106276, + "lon": -79.94164806492292, + "active": false + }, + { + "key": "ce3c8285-e6d1-4ff8-be51-b2d49fb266b7", + "lat": 40.441628652240986, + "lon": -79.9416480194968, + "active": false + }, + { + "key": "bc2d6ce2-6f8b-4f5c-b102-201e29616d59", + "lat": 40.44162863369047, + "lon": -79.94164788436404, + "active": false + }, + { + "key": "e3de73cd-1966-4937-9f38-d3354dcb6b86", + "lat": 40.44162852064693, + "lon": -79.94164767797413, + "active": false + }, + { + "key": "8ae9d187-3790-4697-93ca-9272d6743be4", + "lat": 40.44162856369769, + "lon": -79.94164764560287, + "active": false + }, + { + "key": "07d66f69-e754-4296-bfbb-141c04b59d37", + "lat": 40.441628448960145, + "lon": -79.94164767863727, + "active": false + }, + { + "key": "aa9496a2-d97b-40ef-adbf-fb4152d93828", + "lat": 40.44162863957455, + "lon": -79.9416479977705, + "active": false + }, + { + "key": "63e359f5-490b-4804-be7d-8591192b26e0", + "lat": 40.44162868401334, + "lon": -79.94164808030669, + "active": false + }, + { + "key": "c8fde378-4de9-4244-9ee5-94f70ad66431", + "lat": 40.44162864420369, + "lon": -79.94164817136719, + "active": false + }, + { + "key": "3439b5f1-538f-4c44-9cc4-6198c619fda8", + "lat": 40.441628672418176, + "lon": -79.94164809186853, + "active": false + }, + { + "key": "5f45d94c-5c99-47c0-afee-6b133fb63032", + "lat": 40.44162867906454, + "lon": -79.94164793864816, + "active": false + }, + { + "key": "cafebd9c-02c2-4b0b-bd10-81e43eb842a6", + "lat": 40.441628779721775, + "lon": -79.94164788235227, + "active": false + }, + { + "key": "c8b03908-faf6-4469-8d32-8bedd333eb6f", + "lat": 40.44162880012459, + "lon": -79.94164781258837, + "active": false + }, + { + "key": "31bcfd33-7a65-4450-8bfd-c003633e107d", + "lat": 40.4416288144872, + "lon": -79.9416479061913, + "active": false + }, + { + "key": "eaae3910-21e2-4979-a8d6-3daad6e4474b", + "lat": 40.4416286811238, + "lon": -79.94164785866302, + "active": false + }, + { + "key": "67a13a66-b851-4806-be15-7a2585336376", + "lat": 40.44162880477365, + "lon": -79.94164789570227, + "active": false + }, + { + "key": "1721a578-bb8e-4f3c-918d-43af20c53e6c", + "lat": 40.44162889846051, + "lon": -79.94164793485845, + "active": false + }, + { + "key": "6834f83b-36a2-43b3-9813-8155aa45acd6", + "lat": 40.44162884547597, + "lon": -79.9416479656921, + "active": false + }, + { + "key": "bf94a5db-4d94-433d-bbcf-c85431726b11", + "lat": 40.44162889963017, + "lon": -79.94164815199237, + "active": false + }, + { + "key": "b5c71791-1eb7-40b9-aca3-5ad2b174b48f", + "lat": 40.441628834654175, + "lon": -79.94164820686233, + "active": false + }, + { + "key": "ff2a5cee-f626-4801-899b-4cd1a0e2471f", + "lat": 40.441628851135704, + "lon": -79.94164810513533, + "active": false + }, + { + "key": "8913a67e-1c9b-422e-a891-e9dfba2c31a3", + "lat": 40.44162889302654, + "lon": -79.94164797101821, + "active": false + }, + { + "key": "dacd82c1-0965-4a61-b527-5768fbb95002", + "lat": 40.441628878360405, + "lon": -79.94164789682236, + "active": false + }, + { + "key": "9fcf419f-9da7-41b9-8120-ab9e2158bb3e", + "lat": 40.4416288450838, + "lon": -79.94164799923863, + "active": false + }, + { + "key": "0073556c-743f-4bfc-b94b-2247dd375b20", + "lat": 40.44162881774331, + "lon": -79.94164796506864, + "active": false + }, + { + "key": "1651fef0-fbd5-4144-ad1d-b70940a16a69", + "lat": 40.44162874112901, + "lon": -79.94164803654405, + "active": false + }, + { + "key": "c696555b-ab2b-45ed-9d3c-d6f84d8c2f14", + "lat": 40.441628656965705, + "lon": -79.9416480112906, + "active": false + }, + { + "key": "c931b9c5-9442-4aa5-8ee1-0dfbab578334", + "lat": 40.44162865883151, + "lon": -79.9416479328827, + "active": false + }, + { + "key": "ec56e7ea-ed83-479c-8bcc-495a9e4dd7c5", + "lat": 40.44162870859796, + "lon": -79.9416480156985, + "active": false + }, + { + "key": "61af8d39-0c82-45c9-a490-891efd07d10e", + "lat": 40.44162885333345, + "lon": -79.94164806343875, + "active": false + }, + { + "key": "6172b1c5-27e6-4e6a-b3f8-942bc2144dff", + "lat": 40.44162600743306, + "lon": -79.94164905890896, + "active": false + }, + { + "key": "78d70d77-0465-41cf-abff-66429431d2a9", + "lat": 40.441602287893, + "lon": -79.9416588053375, + "active": false + }, + { + "key": "6be58c28-9745-4e99-80c2-d0898cf64911", + "lat": 40.44156593959516, + "lon": -79.94167677511038, + "active": false + }, + { + "key": "54646bac-f017-47bd-a30f-f5287706541b", + "lat": 40.44152276107759, + "lon": -79.94169609007437, + "active": false + }, + { + "key": "6a204882-9811-450a-9fca-9b826d9733ad", + "lat": 40.44147302381378, + "lon": -79.94171739680063, + "active": false + }, + { + "key": "c195ab0f-5aab-4d7d-b6e3-58818358e32c", + "lat": 40.44142911229496, + "lon": -79.94173757709883, + "active": false + }, + { + "key": "b9b2c91a-200c-4c1c-a2b7-6c2b0d4d7476", + "lat": 40.44137880532396, + "lon": -79.94175792370139, + "active": false + }, + { + "key": "06031079-5ef3-4136-9afd-32ee6e056db9", + "lat": 40.441323562636285, + "lon": -79.94178206277914, + "active": false + }, + { + "key": "1ea2c1b7-b60f-4103-8546-3984dd7adc36", + "lat": 40.441275933153584, + "lon": -79.94180240848272, + "active": false + }, + { + "key": "10b28025-fc4e-4496-96c1-0cf4e38160b4", + "lat": 40.44123213937382, + "lon": -79.94182260452877, + "active": false + }, + { + "key": "9613e378-d50b-4cee-94cd-a4e075ca1413", + "lat": 40.44117850978757, + "lon": -79.94184435581323, + "active": false + }, + { + "key": "db42c4cb-8318-4453-a9f7-1ab8c6d4b7d2", + "lat": 40.441129630975105, + "lon": -79.9418656256279, + "active": false + }, + { + "key": "5d4c2794-31a4-4a3e-9d9a-3774805e5aa7", + "lat": 40.44108542576557, + "lon": -79.94188380166146, + "active": false + }, + { + "key": "01da166d-9fb0-4934-89bd-757fb833f686", + "lat": 40.441033937965884, + "lon": -79.9419064105284, + "active": false + }, + { + "key": "711bbe4b-b733-435e-9840-202ed390bfde", + "lat": 40.44098521085449, + "lon": -79.94192789342941, + "active": false + }, + { + "key": "ed32c6ca-8872-4257-b2b9-651650a16149", + "lat": 40.44094226134122, + "lon": -79.94194595725057, + "active": false + }, + { + "key": "35f3013d-7734-40b0-91c3-097f1b911620", + "lat": 40.44089493473035, + "lon": -79.94196731849566, + "active": false + }, + { + "key": "d3c71c0d-baa9-4ff3-8b3b-dabc4ce44b7a", + "lat": 40.44084813229093, + "lon": -79.94198779106188, + "active": false + }, + { + "key": "b31a3e6e-504b-44f8-80d0-122d562d9814", + "lat": 40.440806877575156, + "lon": -79.94200575567163, + "active": false + }, + { + "key": "53d2a3e9-8b80-4617-8936-92ed830aefd3", + "lat": 40.4407633295324, + "lon": -79.94202409008433, + "active": false + }, + { + "key": "3f985c2b-23e5-41d7-b8bf-f2fea7786171", + "lat": 40.44071739796548, + "lon": -79.94204352221638, + "active": false + }, + { + "key": "a9917210-49ba-4abf-8a74-05e05508b8a0", + "lat": 40.44067697447462, + "lon": -79.94206044574798, + "active": false + }, + { + "key": "c1f8524b-8116-46c6-9c26-1eb92253491b", + "lat": 40.44063204261111, + "lon": -79.94207952383702, + "active": false + }, + { + "key": "629f50c3-690b-4c91-a4e3-7c907ef763a2", + "lat": 40.44058525862543, + "lon": -79.94210058977778, + "active": false + }, + { + "key": "1b1d22b3-ab43-4971-8bb5-4853b2683163", + "lat": 40.44054394451477, + "lon": -79.94212165633333, + "active": false + }, + { + "key": "8a3f9c52-d454-4211-a679-143704bdf4d9", + "lat": 40.440499404700866, + "lon": -79.94214498295094, + "active": false + }, + { + "key": "247cc1a7-beae-44d3-9c0a-aa638304eb4b", + "lat": 40.44045668479303, + "lon": -79.94216596230603, + "active": false + }, + { + "key": "1f9a6141-6b94-40c0-b369-35be21154f72", + "lat": 40.44041203576738, + "lon": -79.94219057948291, + "active": false + }, + { + "key": "3d78a10c-0ce3-4604-8b54-843907e1dac8", + "lat": 40.440366881318795, + "lon": -79.94221771573842, + "active": false + }, + { + "key": "4ba19941-cfcb-40f1-ac2a-a6caed5b0ea8", + "lat": 40.44032099648348, + "lon": -79.94225057993681, + "active": false + }, + { + "key": "5dc5096d-d274-4110-8707-072ce3ba4a4f", + "lat": 40.44027827332368, + "lon": -79.94228763946643, + "active": false + }, + { + "key": "40de024a-654c-435e-bb13-62c2ccfaaae6", + "lat": 40.44023888325223, + "lon": -79.9423468337214, + "active": false + }, + { + "key": "37da5c94-aba3-4441-acdf-7fcd16e58ce2", + "lat": 40.4402089063978, + "lon": -79.94242436346813, + "active": false + }, + { + "key": "f80d4c9d-b451-4dc5-8e19-b34e11ff8769", + "lat": 40.44018547671198, + "lon": -79.94250734962795, + "active": false + }, + { + "key": "d694228d-3315-476c-bb37-7c86c2d4e74f", + "lat": 40.4401649427623, + "lon": -79.94259692112985, + "active": false + }, + { + "key": "3079a551-1aec-438b-931b-953d3a6a7422", + "lat": 40.440145218495054, + "lon": -79.94269266097878, + "active": false + }, + { + "key": "9f5b6a6f-1055-4f66-9f21-85ef666977f0", + "lat": 40.440121967313445, + "lon": -79.94279378637734, + "active": false + }, + { + "key": "501bdd0c-6bb5-4fbe-b31e-404ba41e4d28", + "lat": 40.440091566278355, + "lon": -79.9428987926615, + "active": false + }, + { + "key": "dc065987-f3f3-4f4d-9165-3c81bc0dd5db", + "lat": 40.440053007673676, + "lon": -79.94300347823122, + "active": false + }, + { + "key": "a60bac61-5243-4d89-88c1-ca6ad8274f5d", + "lat": 40.44000193412223, + "lon": -79.94310266360117, + "active": false + }, + { + "key": "184dbfe8-70b0-4e09-aa9b-69374fdbeff9", + "lat": 40.43994284061901, + "lon": -79.94320088039164, + "active": false + }, + { + "key": "4675dcd1-d58a-4b99-bdec-37733fe7acb7", + "lat": 40.43987204053676, + "lon": -79.94329066870273, + "active": false + }, + { + "key": "94a8d39a-0137-4bd9-860a-09b9d31a2ba2", + "lat": 40.439799623381376, + "lon": -79.94337997279929, + "active": false + }, + { + "key": "6d31f5b5-a21a-44ae-b86c-313fde2dc591", + "lat": 40.439723643528474, + "lon": -79.94347066250273, + "active": false + }, + { + "key": "a7f76c38-cc7f-4440-89c7-31e7304c5da2", + "lat": 40.439649976843, + "lon": -79.94356096573466, + "active": false + }, + { + "key": "1c0dde52-8927-470f-9e46-cacc6d2033a2", + "lat": 40.43957444245867, + "lon": -79.94364654934363, + "active": false + }, + { + "key": "70252db9-e0d8-4f05-93e9-7144b80aa0f0", + "lat": 40.439500945001, + "lon": -79.94373303072615, + "active": false + }, + { + "key": "9676e067-5c7b-4d70-90f1-656f3b50f73a", + "lat": 40.43942698817514, + "lon": -79.94381510278889, + "active": false + }, + { + "key": "6f622aef-64e9-45a4-9066-005d3d006b00", + "lat": 40.439354845146646, + "lon": -79.94389674078089, + "active": false + }, + { + "key": "b5240ca6-9c21-4fa7-b5d5-d5eb7af0cc53", + "lat": 40.43928082003441, + "lon": -79.94397504401043, + "active": false + }, + { + "key": "84f66767-d4c1-4836-a749-cf175b613cfa", + "lat": 40.43920670285525, + "lon": -79.94404757469322, + "active": false + }, + { + "key": "caec01f1-c6dc-4167-8d97-3bbd8f39be00", + "lat": 40.43913478154404, + "lon": -79.94412159339632, + "active": false + }, + { + "key": "893839b0-6716-4079-abf3-9bbae16cf63d", + "lat": 40.43906652164044, + "lon": -79.94419663551255, + "active": false + }, + { + "key": "d95867b4-8cbd-4ec6-abd6-da248db36273", + "lat": 40.439009114484385, + "lon": -79.94428505260011, + "active": false + }, + { + "key": "aa9dbfca-6e80-4bf4-80e5-3639fe30d936", + "lat": 40.43896009503183, + "lon": -79.94437775792645, + "active": false + }, + { + "key": "c1ce7f48-eadd-42a5-b2eb-45327931b18e", + "lat": 40.43891737068923, + "lon": -79.94447602813663, + "active": false + }, + { + "key": "4bb4dc99-0f1b-4a64-8383-f776a1f98c25", + "lat": 40.43888542547845, + "lon": -79.94457958420297, + "active": false + }, + { + "key": "866c1bfd-2f65-4520-937a-80ce97e644d8", + "lat": 40.43886260340316, + "lon": -79.9446860610351, + "active": false + }, + { + "key": "d575b0a5-ce08-460d-aef5-f0f6eec5c8ef", + "lat": 40.43883774055108, + "lon": -79.94478943412271, + "active": false + }, + { + "key": "560b4f8b-b9bc-48eb-ac12-53d0f11fc42d", + "lat": 40.438816755988576, + "lon": -79.94489332504263, + "active": false + }, + { + "key": "4fc9c0a2-a745-445d-890e-8229fd0c74c3", + "lat": 40.438795804461215, + "lon": -79.94499621577928, + "active": false + }, + { + "key": "3506d39b-0254-4143-a758-3d5a3a1d488a", + "lat": 40.438774920389434, + "lon": -79.94509707610212, + "active": false + }, + { + "key": "215e6e1b-22db-463a-8223-7327c1e0eb6b", + "lat": 40.43875578316524, + "lon": -79.94519631384784, + "active": false + }, + { + "key": "9fac035a-2ff7-4e21-93ba-c775faa5e751", + "lat": 40.43874015518457, + "lon": -79.94529460509307, + "active": false + }, + { + "key": "b79272ea-4df0-461a-97b5-5ef54bdc2e5f", + "lat": 40.43872496914257, + "lon": -79.94539059003031, + "active": false + }, + { + "key": "edd5fdc6-80eb-46d0-a3a1-564e8e1054da", + "lat": 40.43870937646705, + "lon": -79.94548637231428, + "active": false + }, + { + "key": "ba588922-1478-4f21-aba9-524c0d55ba5f", + "lat": 40.43869797708435, + "lon": -79.94558119221303, + "active": false + }, + { + "key": "b7e5c24f-43f0-4c94-b8ee-11bd97709e53", + "lat": 40.43869532282356, + "lon": -79.94567569209818, + "active": false + }, + { + "key": "d563938c-d055-401d-b10d-68d71e728fad", + "lat": 40.43870028144677, + "lon": -79.94576751567757, + "active": false + }, + { + "key": "368bcafe-c866-4b4d-a20d-c49ca7c25377", + "lat": 40.43871178944336, + "lon": -79.94585564175438, + "active": false + }, + { + "key": "a450e646-0b2c-45b8-a484-4b6905e5b5bf", + "lat": 40.43872983566996, + "lon": -79.94594291400674, + "active": false + }, + { + "key": "9e164947-0797-4911-999d-af1ee1be4cfb", + "lat": 40.438753729434296, + "lon": -79.94602290945416, + "active": false + }, + { + "key": "9ab266b1-5fa8-4521-ab28-45a84b58c98d", + "lat": 40.43878157239455, + "lon": -79.94609844603812, + "active": false + }, + { + "key": "dcb83b5b-1cd7-46e4-8865-6356d7ee04e2", + "lat": 40.43881002331804, + "lon": -79.94617230499406, + "active": false + }, + { + "key": "c869f484-21e1-4eb3-b4e7-e46f95f72d4e", + "lat": 40.438843784759094, + "lon": -79.9462413217983, + "active": false + }, + { + "key": "42154acb-b89f-4f0a-b051-b13714545ee3", + "lat": 40.438882503945216, + "lon": -79.94630332437308, + "active": false + }, + { + "key": "40068c49-3cc0-4791-be96-97f2635ead12", + "lat": 40.43892391346011, + "lon": -79.94635991328346, + "active": false + }, + { + "key": "af7e26c2-1faa-4394-8e4f-c1ba45e9de50", + "lat": 40.4389673726988, + "lon": -79.946411645916, + "active": false + }, + { + "key": "d05d5a07-62d4-4e00-b37a-95b7ef3f5470", + "lat": 40.43901411912967, + "lon": -79.94645520102382, + "active": false + }, + { + "key": "5efd0c67-2f6a-4865-a9dc-bac9a519b5fa", + "lat": 40.43906350496209, + "lon": -79.94649499185957, + "active": false + }, + { + "key": "40e0c213-ab9f-424b-90dd-f96ba7281caa", + "lat": 40.43911343789358, + "lon": -79.94653169228599, + "active": false + }, + { + "key": "baa47098-5ec9-47fc-9919-26ac7bf59078", + "lat": 40.43916453829429, + "lon": -79.9465653973664, + "active": false + }, + { + "key": "94d4ffc9-0e3a-41db-b450-4764b78657b7", + "lat": 40.43921450588048, + "lon": -79.94659875811413, + "active": false + }, + { + "key": "4ef83256-d554-4f88-9507-8206acb7dfd4", + "lat": 40.439264797063935, + "lon": -79.94662941566446, + "active": false + }, + { + "key": "771e2e8a-ed94-456b-8cd5-e183bb471cf0", + "lat": 40.439315375246785, + "lon": -79.94665921237626, + "active": false + }, + { + "key": "bf367fd6-b763-47b7-9e8a-ae3655ead110", + "lat": 40.43936381819195, + "lon": -79.94668754423842, + "active": false + }, + { + "key": "8d9d0317-e349-42b9-bd4b-cd382ae7a2b9", + "lat": 40.4394115728521, + "lon": -79.94671706763211, + "active": false + }, + { + "key": "12dd7549-6e37-4a79-a665-5fe0262b6caa", + "lat": 40.43945996554909, + "lon": -79.94674649632273, + "active": false + }, + { + "key": "ebf6c8f4-bcb7-45a9-b1c5-81a8a46f5ae6", + "lat": 40.43950822617038, + "lon": -79.94677626407571, + "active": false + }, + { + "key": "32f8e887-5d10-4d83-8105-4ab02b7c5a38", + "lat": 40.43955531535933, + "lon": -79.94680759193098, + "active": false + }, + { + "key": "900a595f-0885-440c-bb9c-9fce037fea1e", + "lat": 40.43960333848619, + "lon": -79.94684122121843, + "active": false + }, + { + "key": "6d3f84ad-ce47-4b0c-9e88-827c84bd03da", + "lat": 40.43965152705131, + "lon": -79.94687786789186, + "active": false + }, + { + "key": "444c60b6-8a0b-439c-8460-cd8dbad1eb29", + "lat": 40.43970112408119, + "lon": -79.9469170958961, + "active": false + }, + { + "key": "9c0ca239-ded1-4da9-8b47-f84adaa9dcd4", + "lat": 40.439751789413975, + "lon": -79.94695930834823, + "active": false + }, + { + "key": "97a1650c-1a0d-4e83-aeba-7f94ee84cd68", + "lat": 40.43980339867682, + "lon": -79.9470029653453, + "active": false + }, + { + "key": "b6584618-4651-4a9f-b6cb-48b3a3f77285", + "lat": 40.439854047973505, + "lon": -79.94705107525901, + "active": false + }, + { + "key": "833c1a22-eeb7-4540-9ae3-18c77150ae1d", + "lat": 40.43990533350213, + "lon": -79.94710177688708, + "active": false + }, + { + "key": "817c2b0f-9075-4f06-8924-12f96a1a8907", + "lat": 40.43995563803151, + "lon": -79.9471564730815, + "active": false + }, + { + "key": "90eb452a-b08a-4b85-84b7-d88cf9c673f4", + "lat": 40.4400042853409, + "lon": -79.94721497649594, + "active": false + }, + { + "key": "a9e3a85d-13ac-4d31-9817-8ee7cc4b1ee2", + "lat": 40.44005188299738, + "lon": -79.94727514292956, + "active": false + }, + { + "key": "49f93fe1-e367-4e41-bc02-c69e6b8fdec8", + "lat": 40.4401000517424, + "lon": -79.94733773101571, + "active": false + }, + { + "key": "b01f6a9a-aae4-458c-a489-0ee7ab39516e", + "lat": 40.440147690706375, + "lon": -79.94740109248342, + "active": false + }, + { + "key": "bebe216b-1937-4230-873a-99c07a04b42c", + "lat": 40.44019594822378, + "lon": -79.9474638537546, + "active": false + }, + { + "key": "134a36e7-c0b3-49c7-87d2-5c8b064ca433", + "lat": 40.44024428165478, + "lon": -79.94753075951296, + "active": false + }, + { + "key": "c83870f6-f4d3-4d78-aeb1-1b36e6f4d1cb", + "lat": 40.4402913309927, + "lon": -79.94759674810138, + "active": false + }, + { + "key": "33829d47-497a-4a2c-9063-75e595fcf441", + "lat": 40.44034009279249, + "lon": -79.94766244398636, + "active": false + }, + { + "key": "03063d5c-b0f9-4b3d-a906-5194cf61257e", + "lat": 40.44038784174999, + "lon": -79.94772870166612, + "active": false + }, + { + "key": "054caa68-c107-4356-a92a-7ef522db2b3a", + "lat": 40.44043376379928, + "lon": -79.94780028873389, + "active": false + }, + { + "key": "34ce086b-430e-4f95-90ac-2d8ba0e89cc5", + "lat": 40.44048375743321, + "lon": -79.94786699233086, + "active": false + }, + { + "key": "3b5d48e8-34a5-4087-9927-839893a5d455", + "lat": 40.44053639244634, + "lon": -79.94793104384061, + "active": false + }, + { + "key": "5450253c-5806-4b53-9170-9970a68aaf16", + "lat": 40.44059855552176, + "lon": -79.94797650745885, + "active": false + }, + { + "key": "744e5275-ed4c-4b93-9dca-3f96cd9daceb", + "lat": 40.44066709163043, + "lon": -79.94799386313369, + "active": false + }, + { + "key": "15c53857-b40b-4854-a36d-4230c2f4fc47", + "lat": 40.44073553856873, + "lon": -79.9480011659618, + "active": false + }, + { + "key": "5415e2a9-b25d-48c4-bdec-8ce26905a6da", + "lat": 40.440805937350966, + "lon": -79.94799730850539, + "active": false + }, + { + "key": "a9fabe4d-5d24-4164-9441-70b2ec3c7c7e", + "lat": 40.44087502264476, + "lon": -79.94798480628383, + "active": false + }, + { + "key": "69fa1149-6f64-4f10-9a44-fa7e90fa6afd", + "lat": 40.4409392086668, + "lon": -79.9479598847673, + "active": false + }, + { + "key": "9c886113-f854-4bab-b5ff-650273f86b73", + "lat": 40.44099212314513, + "lon": -79.9479145662162, + "active": false + }, + { + "key": "47e94ecd-7aa8-414b-b857-5d6756c01957", + "lat": 40.44103901777972, + "lon": -79.94786730383575, + "active": false + }, + { + "key": "53742c9f-b2ec-4c70-99ba-4000bacebb63", + "lat": 40.44108113200553, + "lon": -79.94782072105606, + "active": false + }, + { + "key": "4c9338f3-6982-4b89-8423-ab1cdaf208e7", + "lat": 40.44111587899972, + "lon": -79.94777571170677, + "active": false + }, + { + "key": "bf36a22d-ed01-4005-8330-294388cba36b", + "lat": 40.44114957686801, + "lon": -79.94773391626225, + "active": false + }, + { + "key": "18be55b6-6138-4e54-948d-0a4cd685bb05", + "lat": 40.44117747087336, + "lon": -79.94769456423585, + "active": false + }, + { + "key": "6ed6b9e4-c573-4280-944b-e5fe57a5cc0c", + "lat": 40.441202995523156, + "lon": -79.9476591883112, + "active": false + }, + { + "key": "88616eb6-29cd-4956-a815-d019f1e20454", + "lat": 40.441227821802805, + "lon": -79.94762517338638, + "active": false + }, + { + "key": "50a81040-53d0-4b19-85f8-56faecaa0a47", + "lat": 40.44125517716834, + "lon": -79.94758766365433, + "active": false + }, + { + "key": "33db67b5-1436-46b6-8f03-1149c0ade4fd", + "lat": 40.44128203520435, + "lon": -79.94754748798717, + "active": false + }, + { + "key": "a401a4c3-0330-413e-9b81-007dc296f87f", + "lat": 40.44131443413316, + "lon": -79.94750561396782, + "active": false + }, + { + "key": "d082c8cf-a9ec-4eb5-9197-4d7b5ebded2c", + "lat": 40.441345600314065, + "lon": -79.9474623698726, + "active": false + }, + { + "key": "0309b990-6a47-48e4-8955-44a3e06c6298", + "lat": 40.441375362497865, + "lon": -79.9474133363368, + "active": false + }, + { + "key": "e44ff2f1-b4dd-4cb4-8bc4-84cdd2305958", + "lat": 40.44140398116693, + "lon": -79.94736216204065, + "active": false + }, + { + "key": "1c0b8642-1fdc-4572-9c20-26c86f3e6603", + "lat": 40.44143075511234, + "lon": -79.94730714953512, + "active": false + }, + { + "key": "91031c7e-c7c2-4607-9f46-fcbeeb6dcd2c", + "lat": 40.44145141602689, + "lon": -79.94725065794096, + "active": false + }, + { + "key": "e018962b-35a8-48a2-a43f-570e8488eaa2", + "lat": 40.44146388509335, + "lon": -79.94718892203093, + "active": false + }, + { + "key": "2c28d756-ec48-4a16-ad1a-2f2b6de64eb3", + "lat": 40.44146648332716, + "lon": -79.94713029842278, + "active": false + }, + { + "key": "18d18d3a-a97e-4cef-ab2a-79608e370a4b", + "lat": 40.441463410954604, + "lon": -79.94706886192853, + "active": false + }, + { + "key": "654fbb65-d584-4c93-9557-d69b8eb58f6f", + "lat": 40.44145883375807, + "lon": -79.94701756782125, + "active": false + }, + { + "key": "b3677674-95c1-44ce-b1f6-90c035cf8ac8", + "lat": 40.441450970034936, + "lon": -79.94696256061849, + "active": false + }, + { + "key": "1a529e66-0a6b-499e-a606-47725a563c4d", + "lat": 40.44144568435565, + "lon": -79.9469164792336, + "active": false + }, + { + "key": "a9932502-852b-401f-b7cf-2d0a91063628", + "lat": 40.44143729426943, + "lon": -79.94686400354297, + "active": false + }, + { + "key": "76f16639-f08e-4263-9cc3-f4f4b2c46a82", + "lat": 40.441429914881276, + "lon": -79.94681991869615, + "active": false + }, + { + "key": "8ec19e9a-0982-4509-a4ac-40eab76d94a1", + "lat": 40.441422658603095, + "lon": -79.9467703257848, + "active": false + }, + { + "key": "e4aa1ba0-ba1b-42dd-9435-834fedfb7826", + "lat": 40.44141439540747, + "lon": -79.94672021934468, + "active": false + }, + { + "key": "69436834-11e8-4799-803c-419ee49c387b", + "lat": 40.441407588119084, + "lon": -79.94667728548774, + "active": false + }, + { + "key": "312a0bc1-fd96-49ef-9cd8-255b2cf1d24d", + "lat": 40.44139819293787, + "lon": -79.94662726231631, + "active": false + }, + { + "key": "baef8557-c340-40ae-a507-321eaf534acf", + "lat": 40.44139015048203, + "lon": -79.94658503037623, + "active": false + }, + { + "key": "7a10f25e-ae3a-4d45-b93e-0f1ebac3ec46", + "lat": 40.44138181150902, + "lon": -79.94654144024992, + "active": false + }, + { + "key": "a35bf91a-40cc-434f-aaa9-20a5dc933e32", + "lat": 40.441372703080766, + "lon": -79.94649591193888, + "active": false + }, + { + "key": "2deee254-a250-453a-83b8-2f6ebc00a76f", + "lat": 40.44136447050732, + "lon": -79.94645794782176, + "active": false + }, + { + "key": "fcbd1cf9-2a36-4ce0-8a35-7246c6e50244", + "lat": 40.441354101903094, + "lon": -79.94641295652117, + "active": false + }, + { + "key": "d7d58b2f-0567-4870-9b5b-431f91d69b4a", + "lat": 40.44134618844617, + "lon": -79.94637440936914, + "active": false + }, + { + "key": "399e5cee-9f00-4a75-a993-2fb5f083e3be", + "lat": 40.44133684777208, + "lon": -79.94632836395667, + "active": false + }, + { + "key": "9965717b-a706-40dd-9209-94ea3ac11903", + "lat": 40.441327830069845, + "lon": -79.94628984888521, + "active": false + }, + { + "key": "8b7dbe92-a978-416e-aa38-97dec9a843bb", + "lat": 40.44131794058374, + "lon": -79.94624598518787, + "active": false + }, + { + "key": "7ce1ddbc-8dfa-4b3a-8856-23aebb13e9d0", + "lat": 40.44130912043824, + "lon": -79.94620555902411, + "active": false + }, + { + "key": "f94fc1b3-2dbe-4fb5-b9a6-26458508c42a", + "lat": 40.44130272643207, + "lon": -79.94617440870343, + "active": false + }, + { + "key": "2d2e5f57-e9ba-4ee6-94e9-00acc2a87542", + "lat": 40.441296659783134, + "lon": -79.94614608618959, + "active": false + }, + { + "key": "89b0eaa8-a611-4e19-8ad7-f01fdddcdea4", + "lat": 40.441289612181706, + "lon": -79.94610820721937, + "active": false + }, + { + "key": "46b12ef1-78be-423e-8e4f-605a89f59241", + "lat": 40.44127936899182, + "lon": -79.9460636577083, + "active": false + }, + { + "key": "53844a00-67e1-4f50-9f0f-ca0dfaffac36", + "lat": 40.44126871046795, + "lon": -79.94601004061153, + "active": false + }, + { + "key": "fcc4e49c-109f-4839-bf3e-a0f9fb0ac47b", + "lat": 40.441258189158034, + "lon": -79.9459609670652, + "active": false + }, + { + "key": "69b34483-c747-4dee-b114-02692a1b2ecb", + "lat": 40.44124709088341, + "lon": -79.94590892197947, + "active": false + }, + { + "key": "1c94bef6-bd43-40e8-b3cd-61e2f957b8b6", + "lat": 40.44123598666907, + "lon": -79.945858140893, + "active": false + }, + { + "key": "c10827d9-8bd0-4c42-8d07-4a76b8d9ef83", + "lat": 40.441224627992845, + "lon": -79.9458045514929, + "active": false + }, + { + "key": "717bb092-74d1-44c2-ab3b-cf1a63782427", + "lat": 40.44121366391192, + "lon": -79.94575336208293, + "active": false + }, + { + "key": "9a201589-e509-4cff-9e17-04093cc50886", + "lat": 40.44120400289501, + "lon": -79.94570395590128, + "active": false + }, + { + "key": "26fe499e-256a-4989-aef3-c4f3ceec13f6", + "lat": 40.441192820488745, + "lon": -79.94564703826639, + "active": false + }, + { + "key": "37cf1e7e-9b41-43ae-9935-409cc2e9193b", + "lat": 40.44118112110092, + "lon": -79.94559541527408, + "active": false + }, + { + "key": "f9b3164f-b42c-4a14-a561-9019f3cd4e57", + "lat": 40.44117108285586, + "lon": -79.94554430632898, + "active": false + }, + { + "key": "ef3ef488-94ce-4f46-8ae2-dbbcc92e71fd", + "lat": 40.44115997515626, + "lon": -79.94549092145945, + "active": false + }, + { + "key": "c3a8fcff-cb27-45c5-9273-dd10c95a0cfd", + "lat": 40.44114989157117, + "lon": -79.94544480492176, + "active": false + }, + { + "key": "65b67a03-84b4-4c9a-9522-185a2f245bd2", + "lat": 40.44114007989868, + "lon": -79.94539285010148, + "active": false + }, + { + "key": "00fd4763-6a7b-41aa-a5aa-b3e9f00e68f4", + "lat": 40.441128009211326, + "lon": -79.94533951933713, + "active": false + }, + { + "key": "3b5f93b7-93f6-4edd-aeb5-e7887355a028", + "lat": 40.44111816938716, + "lon": -79.94529330250255, + "active": false + }, + { + "key": "9acbb16d-5f21-4e23-ab8e-4b05b6169449", + "lat": 40.44110869090064, + "lon": -79.94524815691385, + "active": false + }, + { + "key": "aa723d7e-0dd9-4d58-bd58-54453cf75315", + "lat": 40.44109816146267, + "lon": -79.9452006952466, + "active": false + }, + { + "key": "21d9344d-af7a-4546-b28e-fa1f0a1d4f4e", + "lat": 40.441086966366484, + "lon": -79.94514760235727, + "active": false + }, + { + "key": "481d912e-8f73-496a-8718-1b98a3217f8c", + "lat": 40.44107630416083, + "lon": -79.94510011852277, + "active": false + }, + { + "key": "eed26038-9751-4d4d-a14b-fa1572824b4e", + "lat": 40.44106690316736, + "lon": -79.94505436925554, + "active": false + }, + { + "key": "640bb685-70c0-4b92-877e-d8781f9851a5", + "lat": 40.44105549602748, + "lon": -79.945002692254, + "active": false + }, + { + "key": "60c71097-47e6-49b1-a770-5cffecd0c777", + "lat": 40.441045376807004, + "lon": -79.94495570590253, + "active": false + }, + { + "key": "e2ca7336-3c3f-4e43-9ac1-755d626fff9f", + "lat": 40.44103635798185, + "lon": -79.94491168347696, + "active": false + }, + { + "key": "3e441899-babf-4d1d-a953-4d61f06517fb", + "lat": 40.44102515485617, + "lon": -79.94485781466616, + "active": false + }, + { + "key": "01aba8ca-af33-4ce9-98aa-ac5533117a22", + "lat": 40.441015640198586, + "lon": -79.9448071657936, + "active": false + }, + { + "key": "6b656e19-8122-4336-a7c4-5ce7a914ea79", + "lat": 40.44100589691808, + "lon": -79.94476027270957, + "active": false + }, + { + "key": "0b749fc1-72d6-4ce6-a079-8496811a5b3a", + "lat": 40.44099588039742, + "lon": -79.94471406730922, + "active": false + }, + { + "key": "c382ef1c-8099-41ad-a5cf-3b3a72ef21ec", + "lat": 40.44098665738124, + "lon": -79.94466812571375, + "active": false + }, + { + "key": "621a0d4c-b789-497d-b781-cdd8ec489e69", + "lat": 40.44097830205228, + "lon": -79.944625658136, + "active": false + }, + { + "key": "ed9a2518-22d3-4ff5-97f2-e90af06f50eb", + "lat": 40.440970118384925, + "lon": -79.94458424109587, + "active": false + }, + { + "key": "89e48c39-17bf-4c9b-b7fd-bd43ace63423", + "lat": 40.44096057712249, + "lon": -79.94454062097334, + "active": false + }, + { + "key": "6aebd847-c282-4b27-8370-2ffd5868beae", + "lat": 40.44095192195208, + "lon": -79.9444990063873, + "active": false + }, + { + "key": "24009a8e-f2db-43ff-a067-9304c064bcbc", + "lat": 40.44094392729827, + "lon": -79.94446114592337, + "active": false + }, + { + "key": "e189a807-ce5f-4fc3-9d9a-2efa8f55a706", + "lat": 40.440936374988986, + "lon": -79.94442310928265, + "active": false + }, + { + "key": "6e4e177c-40dd-4d38-80fc-5a59e8a3260d", + "lat": 40.44092519495809, + "lon": -79.9443712454942, + "active": false + }, + { + "key": "f1bde560-9313-4f0f-97ee-d4fe382bf91c", + "lat": 40.440911963333754, + "lon": -79.94431050239805, + "active": false + }, + { + "key": "bb4ef750-d41c-48a7-bf65-a5bcae98dae6", + "lat": 40.440898097366215, + "lon": -79.9442406323999, + "active": false + }, + { + "key": "052ebcb3-7ff0-4038-b134-56b9d0e1574e", + "lat": 40.440883506141674, + "lon": -79.94416786958065, + "active": false + }, + { + "key": "bd57825b-e6aa-473d-a95d-738af67d5409", + "lat": 40.440866618561294, + "lon": -79.94408052806796, + "active": false + }, + { + "key": "3f389c34-2561-4df3-9bae-15a10b4afad9", + "lat": 40.44085011880178, + "lon": -79.94399669637806, + "active": false + }, + { + "key": "eef89c42-0e31-4fc7-b9eb-451167ad9670", + "lat": 40.440834088987934, + "lon": -79.94391561527341, + "active": false + }, + { + "key": "8e3c9b0a-25fc-4182-a260-5d0eead34ed6", + "lat": 40.44081884356305, + "lon": -79.94383777994786, + "active": false + }, + { + "key": "5f1abf74-eddc-4752-adda-7484125a90b0", + "lat": 40.440800072440304, + "lon": -79.94374761886937, + "active": false + }, + { + "key": "7ae21a97-a890-4921-b3f5-f7ba68fe1464", + "lat": 40.4407819558829, + "lon": -79.9436622743007, + "active": false + }, + { + "key": "3763be53-69f8-4ea8-9906-57f04009a5a1", + "lat": 40.440764454834124, + "lon": -79.94358075318209, + "active": false + }, + { + "key": "2fdcbaa6-0e86-4942-9157-f80c88d395f5", + "lat": 40.44074807647404, + "lon": -79.94350258470634, + "active": false + }, + { + "key": "8675fe5d-8b8e-4ed0-b993-3f3eac93f72c", + "lat": 40.44073132470898, + "lon": -79.94343063193428, + "active": false + }, + { + "key": "a249e593-4ce9-4241-be38-e2b1b00e09a1", + "lat": 40.44071690231774, + "lon": -79.94336117410303, + "active": false + }, + { + "key": "6f4b0e0d-8fe9-4f62-ae15-100547f8287b", + "lat": 40.44070116442049, + "lon": -79.943282932858, + "active": false + }, + { + "key": "165bf525-ee37-4067-919c-88366a4c4716", + "lat": 40.44068414323882, + "lon": -79.94320532529241, + "active": false + }, + { + "key": "764450f4-6a0c-4290-bf8c-c81708cccdf6", + "lat": 40.44066908096477, + "lon": -79.94313265855665, + "active": false + }, + { + "key": "c3381d07-0c0a-4e98-af45-619905fb15f8", + "lat": 40.44065423520972, + "lon": -79.94306355081117, + "active": false + }, + { + "key": "da76a74f-9831-4134-9b77-76c725868f26", + "lat": 40.44064097759341, + "lon": -79.94299650475062, + "active": false + }, + { + "key": "c5083cca-7ab3-4ab2-8e2f-39234cf936f9", + "lat": 40.440628090867676, + "lon": -79.94292771403265, + "active": false + }, + { + "key": "4d3222dd-c7cc-49cc-9c31-f23d0b04fc2f", + "lat": 40.44061428630566, + "lon": -79.94286177160306, + "active": false + }, + { + "key": "2ffa1d0b-22a7-4f2b-87e6-7c22b0d93afc", + "lat": 40.440599912122806, + "lon": -79.94279612519809, + "active": false + }, + { + "key": "728a5332-4db0-420c-824f-81acdebed4c4", + "lat": 40.440588048453556, + "lon": -79.9427323774912, + "active": false + }, + { + "key": "c29e33a9-3bf4-45d4-bf23-05de82001243", + "lat": 40.44057430931777, + "lon": -79.94267020557264, + "active": false + }, + { + "key": "4747fe7b-c1e2-45d9-96f2-3980ad4ff319", + "lat": 40.44056119847559, + "lon": -79.94260920437344, + "active": false + }, + { + "key": "0e3c4416-c020-4bf2-87b4-c354b7095c16", + "lat": 40.440548862689255, + "lon": -79.94255093480372, + "active": false + }, + { + "key": "41ad75af-71b0-46f7-a9ec-be5d4de8f36a", + "lat": 40.44053836168875, + "lon": -79.94249749446008, + "active": false + }, + { + "key": "d7efed0e-9729-4913-93e4-a3560ff9ef80", + "lat": 40.44052795874271, + "lon": -79.94245215022174, + "active": false + }, + { + "key": "bea593cb-bdeb-4c97-857f-dbf39bd978e4", + "lat": 40.44051867416263, + "lon": -79.94241321933349, + "active": false + }, + { + "key": "e8feb874-e9c1-4085-a8d6-e26a52fffb88", + "lat": 40.4405129191283, + "lon": -79.94238207926358, + "active": false + }, + { + "key": "b8d7b947-dc95-4880-9fc0-2b0d64324c19", + "lat": 40.440508357797725, + "lon": -79.94235958627605, + "active": false + }, + { + "key": "b8e78d1d-a963-4fd1-8202-9f2f97fa61ec", + "lat": 40.44050503870836, + "lon": -79.94234382382729, + "active": false + }, + { + "key": "6fab7fcd-23e1-40ec-8778-0448a4607082", + "lat": 40.44050288553176, + "lon": -79.94233798308369, + "active": false + } ] \ No newline at end of file diff --git a/rb_ws/src/buggy/scripts/2d_sim/engine.py b/rb_ws/src/buggy/scripts/2d_sim/engine.py index cf3f518..945fa01 100755 --- a/rb_ws/src/buggy/scripts/2d_sim/engine.py +++ b/rb_ws/src/buggy/scripts/2d_sim/engine.py @@ -68,6 +68,7 @@ def __init__(self, start_pos: str, velocity: float, buggy_name: str): "PASS_PT": (589491, 4477003, -160), "FREW_ST": (589646, 4477359, -20), "FREW_ST_PASS": (589644, 4477368, -20), + "RACELINE_PASS": (589468.02, 4476993.07, -160), } # Start position for End of Hill 2 From 641194de0cfb9beeaafdccafe6b559373319d35a Mon Sep 17 00:00:00 2001 From: Mehul Goel Date: Tue, 17 Sep 2024 16:42:54 -0400 Subject: [PATCH 4/8] Update README.md (#106) --- README.md | 2 -- 1 file changed, 2 deletions(-) diff --git a/README.md b/README.md index 67387a9..bd9440b 100755 --- a/README.md +++ b/README.md @@ -34,7 +34,6 @@ A complete re-write of the old RoboBuggy. catkin_make source /rb_ws/devel/setup.bash # sets variables so that our package is visible to ROS commands -- To learn ROS on your own, follow the guide on https://wiki.ros.org/ROS/Tutorials. Start from the first and install Ros using a Virtual Machine. ## Installation (for MacOS - M2) ### Install Softwares: Docker, Foxglove @@ -58,7 +57,6 @@ A complete re-write of the old RoboBuggy. catkin_make source /rb_ws/devel/setup.bash # sets variables so that our package is visible to ROS commands -- To learn ROS on your own, follow the guide on https://wiki.ros.org/ROS/Tutorials. Start from the first and install Ros using a Virtual Machine. --- ## Open Docker From 9c6ce4caf0c2c32ae1925b1196816b00a54e3ebb Mon Sep 17 00:00:00 2001 From: Mehul Goel Date: Wed, 18 Sep 2024 09:43:00 -0400 Subject: [PATCH 5/8] Breh (#107) --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index bd9440b..ca8d478 100755 --- a/README.md +++ b/README.md @@ -46,7 +46,7 @@ A complete re-write of the old RoboBuggy. - In the website above, see these two pages: [Generating a new SSH key and adding it to the ssh-agent](https://docs.github.com/en/authentication/connecting-to-github-with-ssh/generating-a-new-ssh-key-and-adding-it-to-the-ssh-agent) and ["Adding a new SSH key to your GitHub account"](https://docs.github.com/en/authentication/connecting-to-github-with-ssh/adding-a-new-ssh-key-to-your-github-account). ### Clone -- In your terminal type: `$ git clone git@github.com:CMU-Robotics-Club/RoboBuggy.git`. +- In your terminal type: `$ git clone git@github.com:CMU-Robotics-Club/RoboBuggy2.git`. - The clone link above is find in github: code -> local -> Clone SSH. - ![image](https://github.com/CMU-Robotics-Club/RoboBuggy2/assets/116482510/8ea809f7-35f9-4517-b98d-42e2e869d233) From 43192656ea21dd1a7699f14f94b6d00d94f8e6ac Mon Sep 17 00:00:00 2001 From: Jack He <45720415+Jackack@users.noreply.github.com> Date: Wed, 18 Sep 2024 10:05:56 -0400 Subject: [PATCH 6/8] Added Rossetta instructions (#109) --- README.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index ca8d478..88e4341 100755 --- a/README.md +++ b/README.md @@ -35,11 +35,14 @@ A complete re-write of the old RoboBuggy. catkin_make source /rb_ws/devel/setup.bash # sets variables so that our package is visible to ROS commands -## Installation (for MacOS - M2) +## Installation (for MacOS) ### Install Softwares: Docker, Foxglove - Go install Foxglove https://foxglove.dev/. - You will need [Docker](https://docs.docker.com/get-docker/) installed. +### Apple Silicon Mac Only: +- In Docker Desktop App: go to settings -> general and turn on "Use Rosetta for x86/amd64 emulation on Apple Silicon" + ### Set up repository - To set up ssh key, follow this link: [Connecting to GitHub with SSH](https://docs.github.com/en/authentication/connecting-to-github-with-ssh). - Note: Ensure that the SSH keys are generated while in the WSL terminal From 1029d893fae8ce3a9921689d53ff9836bdec4628 Mon Sep 17 00:00:00 2001 From: Jack He <45720415+Jackack@users.noreply.github.com> Date: Wed, 18 Sep 2024 10:06:24 -0400 Subject: [PATCH 7/8] Removed mention of WSL from macos section in README.md (#108) --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 88e4341..b0fd54b 100755 --- a/README.md +++ b/README.md @@ -45,7 +45,7 @@ A complete re-write of the old RoboBuggy. ### Set up repository - To set up ssh key, follow this link: [Connecting to GitHub with SSH](https://docs.github.com/en/authentication/connecting-to-github-with-ssh). -- Note: Ensure that the SSH keys are generated while in the WSL terminal +- Note: Ensure that the SSH keys are generated while in the terminal - In the website above, see these two pages: [Generating a new SSH key and adding it to the ssh-agent](https://docs.github.com/en/authentication/connecting-to-github-with-ssh/generating-a-new-ssh-key-and-adding-it-to-the-ssh-agent) and ["Adding a new SSH key to your GitHub account"](https://docs.github.com/en/authentication/connecting-to-github-with-ssh/adding-a-new-ssh-key-to-your-github-account). ### Clone From f6a47b2acb260a773606ab7b8e8f57fff3136b43 Mon Sep 17 00:00:00 2001 From: Mehul Goel Date: Mon, 23 Sep 2024 21:44:54 -0400 Subject: [PATCH 8/8] Mockrolls 19 09 24 (#110) * Mock rolls 09 - 19 * new INS config * changing topic remappings * Mock Rolls Sept 19 * pylint :( --------- Co-authored-by: Buggy Co-authored-by: Jackack --- camera.py | 70 +++ docker_auton/Dockerfile | 9 +- .../Dockerfile | 0 python-requirements.txt | 1 + rb_ws/src/buggy/INS_params_v2.yml | 587 ++++++++++++++++++ rb_ws/src/buggy/launch/debug_filter.launch | 2 +- rb_ws/src/buggy/launch/ghost_auton.launch | 2 +- rb_ws/src/buggy/launch/sc-main.launch | 8 +- rb_ws/src/buggy/launch/sc-system.launch | 2 +- rb_ws/src/buggy/scripts/auton/autonsystem.py | 12 + rb_ws/src/buggy/scripts/auton/buggystate.py | 2 + .../buggy/scripts/auton/publish_rtk_err.py | 2 + .../scripts/auton/rolling_sanity_check.py | 8 +- .../buggy/scripts/util/rosbag_to_pose_csv.py | 1 + .../scripts/util/rosbag_to_waypoints_json.py | 2 + .../buggy/scripts/visualization/telematics.py | 10 +- telematics_layout.json | 8 +- 17 files changed, 703 insertions(+), 23 deletions(-) create mode 100644 camera.py rename {docker_tester => docker_tester_outofdate}/Dockerfile (100%) create mode 100644 rb_ws/src/buggy/INS_params_v2.yml diff --git a/camera.py b/camera.py new file mode 100644 index 0000000..6281080 --- /dev/null +++ b/camera.py @@ -0,0 +1,70 @@ +######################################################################## +# +# Copyright (c) 2022, STEREOLABS. +# +# All rights reserved. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +# A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +# OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +# SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +# LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +# DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +# THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +# +######################################################################## + +import sys +from signal import signal, SIGINT +import argparse + + +import pyzed.sl as sl + +cam = sl.Camera() + +#Handler to deal with CTRL+C properly +def handler(signal_received, frame): + cam.disable_recording() + cam.close() + sys.exit(0) + +signal(SIGINT, handler) + +def main(): + + init = sl.InitParameters() + init.depth_mode = sl.DEPTH_MODE.NONE # Set configuration parameters for the ZED + + status = cam.open(init) + if status != sl.ERROR_CODE.SUCCESS: + print("Camera Open", status, "Exit program.") + exit(1) + + recording_param = sl.RecordingParameters(opt.output_svo_file, sl.SVO_COMPRESSION_MODE.H264) # Enable recording with the filename specified in argument + err = cam.enable_recording(recording_param) + if err != sl.ERROR_CODE.SUCCESS: + print("Recording ZED : ", err) + exit(1) + + runtime = sl.RuntimeParameters() + print("SVO is Recording, use Ctrl-C to stop.") # Start recording SVO, stop with Ctrl-C command + frames_recorded = 0 + + while True: + if cam.grab(runtime) == sl.ERROR_CODE.SUCCESS : # Check that a new image is successfully acquired + frames_recorded += 1 + print("Frame count: " + str(frames_recorded), end="\r") + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument('--output_svo_file', type=str, help='Path to the SVO file that will be written', required= True) + opt = parser.parse_args() + if not opt.output_svo_file.endswith(".svo") and not opt.output_svo_file.endswith(".svo2"): + print("--output_svo_file parameter should be a .svo file but is not : ",opt.output_svo_file,"Exit program.") + exit() + main() \ No newline at end of file diff --git a/docker_auton/Dockerfile b/docker_auton/Dockerfile index 2804440..a05558e 100755 --- a/docker_auton/Dockerfile +++ b/docker_auton/Dockerfile @@ -1,8 +1,8 @@ -FROM nvidia/cuda:11.6.2-base-ubuntu20.04 as CUDA +# FROM nvidia/cuda:11.6.2-base-ubuntu20.04 as CUDA FROM osrf/ros:noetic-desktop-full-focal -COPY --from=CUDA /usr/local/cuda /usr/local/ +# COPY --from=CUDA /usr/local/cuda /usr/local/ RUN apt update @@ -16,10 +16,11 @@ RUN apt-get install -y -qq \ ros-noetic-foxglove-bridge \ ros-noetic-microstrain-inertial-driver \ ros-noetic-realsense2-camera \ - ros-noetic-realsense2-description + ros-noetic-realsense2-description \ + ros-${ROS_DISTRO}-mavros ros-${ROS_DISTRO}-mavros-extras ros-${ROS_DISTRO}-mavros-msgs # Run this now to cache it separately from other requirements -COPY cuda-requirements_TEMP_DO_NOT_EDIT.txt cuda-requirements.txt +# COPY cuda-requirements_TEMP_DO_NOT_EDIT.txt cuda-requirements.txt # RUN pip3 install -r cuda-requirements.txt diff --git a/docker_tester/Dockerfile b/docker_tester_outofdate/Dockerfile similarity index 100% rename from docker_tester/Dockerfile rename to docker_tester_outofdate/Dockerfile diff --git a/python-requirements.txt b/python-requirements.txt index 254c5da..a7b9fe2 100755 --- a/python-requirements.txt +++ b/python-requirements.txt @@ -1,4 +1,5 @@ matplotlib==3.1.2 +NavPy==1.0 numba==0.58.0 numpy<1.21.0 osqp==0.6.3 diff --git a/rb_ws/src/buggy/INS_params_v2.yml b/rb_ws/src/buggy/INS_params_v2.yml new file mode 100644 index 0000000..d0f0fe9 --- /dev/null +++ b/rb_ws/src/buggy/INS_params_v2.yml @@ -0,0 +1,587 @@ +# Standalone example params file for GX3, GX4, GX/CX5, RQ1 and GQ7 series devices +# Note: Feature support is device-dependent and some of the following settings may have no affect on your device. +# Please consult your device's documentation for supported features + +# ****************************************************************** +# NOTE: This file is formatted to work with ROS and will not work if specified as the params_file argument in ROS2. +# If you want to override parameters for ROS2, start with https://github.com/LORD-MicroStrain/microstrain_inertial/blob/ros2/microstrain_inertial_driver/config/empty.yml +# ****************************************************************** + +# ****************************************************************** +# General Settings +# ****************************************************************** + +# port is the main port that the device will communicate over. For all devices except the GQ7, this is the only available port. +# aux_port is only available for the GQ7 and is only needed when streaming RTCM corrections to the device from ROS, or if you want to publish NMEA sentences from this node +port : "/dev/ttyACM0" +baudrate : 115200 +aux_port : "/dev/null" +aux_baudrate : 115200 +debug : True + +# If set to true, this will configure the requested baudrate on the device for the main port and aux port if possible. +# Note that this will be set on both USB and serial, but will only actually affect the baudrate of a serial connection. +set_baud : False + +# Waits for a configurable amount of time until the device exists +# If poll_max_tries is set to -1 we will poll forever until the device exists +poll_port : False +poll_rate_hz : 1.0 +poll_max_tries : 60 + +# Number of times to attempt to reconnect to the device if it disconnects while running +# If configure_after_reconnect is true, we will also reconfigure the device after we reconnect +# +# Note: It is strongly recommended to configure after reconnect unless device_setup is set to false +# as the device will likely initialize in a different state otherwise +reconnect_attempts : 127 +configure_after_reconnect : True + +# Controls if the driver-defined setup is sent to the device +# false - The driver will ignore the settings below and use the device's current settings +# true - Overwrite the current device settings with those listed below +device_setup : True + +# Controls if the driver-defined settings are saved +# false - Do not save the settings +# true - Save the settings in the device's non-volatile memory +save_settings : False + +# Controls if the driver creates a raw binary file +# false - Do not create the file +# true - Create the file +# +# Note: The filename will have the following format - +# model_number "_" serial_number "_" datetime (year_month_day_hour_minute_sec) ".bin" +# example: "3DM-GX5-45_6251.00001_20_12_01_01_01_01.bin" +# Note: This file is useful for getting support from the manufacturer +raw_file_enable : False + +# (GQ7/CV7 only) Controls if the driver requests additional factory support data to be included in the raw data file +# false - Do not request the additional data +# true - Request the additional channels (please see notes below!) +# +# Note: We recommend only enabling this feature when specifically requested by Microstrain. +# Including this feature increases communication bandwidth requirements significantly... +# for serial data connections please ensure the baudrate is sufficient for the added data channels. +raw_file_include_support_data : True + +# The directory to store the raw data file +raw_file_directory : "/home/your_name" + + +# ****************************************************************** +# Frame ID Settings +# ****************************************************************** + +# The mode in which we will publish transforms to the below frame IDs +# 0 - No transforms will be published between any of the non static frame ids. (if publish_mount_to_frame_id_transform is true, it will still be published, and so will the antenna and odometer transforms) +# 1 - Global mode: +# Transform will be published from earth_frame_id to target_frame_id containing global position +# 2 - Relative mode: +# Note: In order to use relative mode, you must configure filter_relative_position +# Transform will be published from earth_frame_id to map_frame_id using relative position configuration +# Transform between map_frame_id and target_frame_id will be published using position information reported by the device +# for more information, see: https://wiki.ros.org/microstrain_inertial_driver/transforms +tf_mode : 0 + +# Frame ID that most header.frame_id fields will be populated with. +frame_id: "imu_link" + +# Frame IDs determining the transforms published by this node to aid in navigation. See https://www.ros.org/reps/rep-0105.html +# Note: If use_enu_frame is false, these frames (with the exception of earth_frame_id) will automatically have "_ned" appended to them. +mount_frame_id : "base_link" # Frame ID that the device is mounted on. +map_frame_id : "map" +earth_frame_id : "earth" +gnss1_frame_id : "gnss_1_antenna_link" +gnss2_frame_id : "gnss_2_antenna_link" +odometer_frame_id : "odometer_link" + +# Target frame ID to publish transform to. Note that there needs to be some path of transforms between this and frame_id +# If tf_mode is set to 1, a transform between earth_frame_id and target_frame_id will be published +# If tf_mode is set to 2, a transform between map_frame_id and target_frame_id will be published +target_frame_id : "base_link" + +# Static transform between mount_frame_id and frame_id. +# Note: It is recommended to define this in a urdf file if you are building a robot, or are able to modify the robot's description. +publish_mount_to_frame_id_transform : True +mount_to_frame_id_transform : [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0] # [ x, y, z, qi, qj, qk, qw ] + +# Controls if the driver outputs data with-respect-to ENU frame +# false - position, velocity, and orientation are WRT the NED frame (native device frame) +# true - position, velocity, and orientation are WRT the ENU frame +# +# Note: It is strongly recommended to leave this as True if you plan to integrate with other ROS tools +# Note: If this is set to false, all "*_frame_id" variables will have "_ned" appended to them by the driver. +# For more information, see: https://wiki.ros.org/microstrain_inertial_driver/use_enu_frame +use_enu_frame : True + + +# ****************************************************************** +# GNSS Settings (only applicable for devices with GNSS) +# ****************************************************************** + +# Antenna #1 lever arm offset source +# 0 - Disabled: We will not configure the antenna offset, or publish it as a transform +# 1 - Manual: We will use the provided vector to configure the device, and publish it as the transform between frame_id and gnss1_frame_id +# 2 - Transform: We will lookup the transform between frame_id and gnss1_frame_id and use it to configure the device. We will ignore gns1_antenna_offset +# Antenna #1 lever arm offset vector +# For GQ7 - in the vehicle frame wrt IMU origin (meters) +# For all other models - in the IMU frame wrt IMU origin (meters) +# Note: Make this as accurate as possible for good performance +gnss1_antenna_offset_source : 1 +gnss1_antenna_offset : [-0.6007, 0.0, -0.2225] + + +# ****************************************************************** +# GNSS2 Settings (only applicable for multi-GNSS systems (e.g. GQ7) ) +# ****************************************************************** + +# Antenna #2 lever arm offset source +# 0 - Disabled: We will not configure the antenna offset, or publish it as a transform +# 1 - Manual: We will use the provided vector to configure the device, and publish it as the transform between frame_id and gnss2_frame_id +# 2 - Transform: We will lookup the transform between frame_id and gnss2_frame_id and use it to configure the device. We will ignore gns2_antenna_offset +# Antenna #2 lever arm offset vector +# For GQ7 - in the vehicle frame wrt IMU origin (meters) +# For all other models - in the IMU frame wrt IMU origin (meters) +# Note: Make this as accurate as possible for good performance +gnss2_antenna_offset_source : 1 +gnss2_antenna_offset : [0.4968, 0.0, -0.3268] + +# GNSS signal configuration +gnss_glonass_enable : False +gnss_galileo_enable : True +gnss_beidou_enable : False + + +# ****************************************************************** +# RTK Settings (only applicable for devices with RTK support (e.g. GQ7) ) +# ****************************************************************** + +# (GQ7 Only) Enable RTK dongle interface. This is required when using a 3DM-RTK +# Note: Enabling this will cause the node to publish mip/gnss_corrections/rtk_corrections_status +rtk_dongle_enable : False + +# (GQ7 Only) Allow the node to receive RTCM messages on the /rtcm topic and publish NMEA sentences from the aux port on /nmea. +# It is suggested to use https://github.com/LORD-MicroStrain/ntrip_client with this interface +# Note: This will require the aux_port configuration to be valid and pointing to a valid aux port +ntrip_interface_enable : False + +# ****************************************************************** +# Kalman Filter Settings (only applicable for devices with a Kalman Filter) +# ****************************************************************** + +# (GQ7/CV7 only) Aiding measurement control +filter_enable_gnss_pos_vel_aiding : True +filter_enable_gnss_heading_aiding : True +filter_enable_altimeter_aiding : False +filter_enable_odometer_aiding : False +filter_enable_magnetometer_aiding : False +filter_enable_external_heading_aiding : False + +# (GQ7 only) Filter Initialization control +# Init Condition source = +# 0 - auto pos, vel, attitude (default) +# 1 - auto pos, vel, roll, pitch, manual heading +# 2 - auto pos, vel, manual attitude +# 3 - manual pos, vel, attitude +# +# Auto-Heading alignment selector (note this is a bitfield, you can use more than 1 source) = +# Bit 0 - Dual-antenna GNSS +# Bit 1 - GNSS kinematic (requires motion, e.g. a GNSS velocity) +# Bit 2 - Magnetometer +# Bit 3 - External Heading (first valid external heading will be used to initialize the filter) +# +# Reference frame = +# 1 - WGS84 Earth-fixed, earth centered (ECEF) position, velocity, attitude +# 2 - WGS84 Latitude, Longitude, height above ellipsoid position, NED velocity and attitude +filter_init_condition_src : 0 +filter_auto_heading_alignment_selector : 3 +filter_init_reference_frame : 2 +filter_init_position : [0.0, 0.0, 0.0] +filter_init_velocity : [0.0, 0.0, 0.0] +filter_init_attitude : [0.0, 0.0, 0.0] + +# (GQ7 only) Relative Position Configuration +# Reference frame = +# 1 - Relative ECEF position +# 2 - Relative LLH position +# +# Source = +# 0 - Position will be reported relative to the base station. filter_relative_position_ref will be ignored +# 1 - Position will be reported relative to filter_relative_position_ref +# 2 - Position will be reported relative to the first position reported by the device after it enters full nav. filter_relative_position_ref will be ignored +# 3 - We will wait for a transform to be made available between earth_frame_id and map_frame_id and use that as the relative position reference. filter_relative_position_ref will be ignored +# +# Reference position - Units provided by reference frame (ECEF - meters, LLH - deg, deg, meters) +# Note: The source selected here will determine the transform published between earth_frame_id and map_frame_id when running in relative transform mode +# For more information, see: https://wiki.ros.org/microstrain_inertial_driver/relative_position_configuration +filter_relative_position_config : False +filter_relative_position_frame : 2 +filter_relative_position_source : 2 +filter_relative_position_ref : [0.0, 0.0, 0.01] + +# (GQ7 Only) Reference point lever arm offset control. +# Note: This offset will affect the position and velocity measurements in the following topics: nav/odometry, nav/relative_pos/odometry +# Note: This offset is in the vehicle reference frame. +# Note: This can cause strange behavior when also using the ROS transform tree. +# It is recommended to not use this if you want to use the ROS transform tree unless you really know what you are doing +filter_lever_arm_offset: [-0.3835, 0.0, -0.0671] + +# (GQ7 only) Wheeled Vehicle Constraint Control +# Note: When enabled, the filter uses the assumption that velocity is constrained to the primary vehicle axis. +# By convention, the primary vehicle axis is the vehicle X-axis +filter_enable_wheeled_vehicle_constraint : True + +# (GQ7 only) Vertical Gyro Constraint Control +# Note: When enabled and no valid GNSS measurements are available, the filter uses the accelerometers to track +# pitch and roll under the assumption that the sensor platform is not undergoing linear acceleration. +# This constraint is useful to maintain accurate pitch and roll during GNSS signal outages. +filter_enable_vertical_gyro_constraint : False + +# (GQ7 only) GNSS Antenna Calibration Control +# When enabled, the filter will enable lever arm error tracking, up to the maximum offset specified in meters. +# This allows the filter to compensate for antenna offsets when they are incorrect. +filter_enable_gnss_antenna_cal : True +filter_gnss_antenna_cal_max_offset : 0.1 + +# (GQ7/CV7 only) PPS Source +# PPS Source = +# 0 - Disabled +# 1 - Reciever 1 (default) +# 2 - Reciever 2 +# 3 - GPIO (provided by external source if supported). Use the GPIO config above to further configure +# 4 - Generated from system oscillator +filter_pps_source : 1 + +# Sensor2vehicle frame transformation selector +# 0 = None +# 1 = Euler Angles +# 2 = matrix +# 3 = quaternion +# Note: These are different ways of setting the same parameter in the device. +# The different options are provided as a convenience. +# Support for matrix and quaternion options is firmware version dependent (GQ7 supports Quaternion as of firmware 1.0.07) +# Quaternion order is [i, j, k, w] +# Note: This can cause strange behavior when also using the ROS transform tree. +# It is recommended to not use this if you want to use the ROS transform tree unless you really know what you are doing +filter_sensor2vehicle_frame_selector : 1 +filter_sensor2vehicle_frame_transformation_euler : [0.0, 0.0, 0.0] +filter_sensor2vehicle_frame_transformation_matrix : [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] +filter_sensor2vehicle_frame_transformation_quaternion : [0.0, 0.0, 0.0, 1.0] + +# Controls if the Kalman filter will auto-init or requires manual initialization +filter_auto_init : True + +# Controls if the Kalman filter is reset after the settings are configured +filter_reset_after_config : True + +# (All, except -10, and -15 products) Declination Source 1 = None, 2 = magnetic model, 3 = manual +# Note: When using a CV7, this MUST be changed to either 1, or 3 or the node will not start +filter_declination_source : 2 +filter_declination : 0.23 + +# Controls what kind of linear acceleration data is used in the Filter IMU message. +# If this is set to true, the acceleration will not factor out gravity, if set to false gravity will be filtered out of the linear acceleration. +filter_use_compensated_accel : True + +# (GQ7/CV7 full support, GX5-45 limited support) Adaptive filter settings +# Adaptive level: 0 - off, 1 - Conservative, 2 = Moderate (default), 3 = agressive +# Time limit: Max duration of measurement rejection prior to recovery, in milliseconds - default = 15000 +filter_adaptive_level : 2 +filter_adaptive_time_limit_ms : 15000 + +# External GPS Time Update Control +# Note: filter_external_gps_time_topic should publish at no more than 1 Hz. +# Note: gps_leap_seconds should be updated to reflect the current number of leap seconds. +filter_enable_external_gps_time_update : False +filter_external_gps_time_topic : "/external_gps_time" +gps_leap_seconds : 18.0 + +# (GQ7 only) Speed Lever Arm Configuration +# Lever Arm - In vehicle reference frame (meters) +filter_speed_lever_arm : [0.0, 0.5, -1.0] + +# (All, except GQ7, CV7, -10, and -15 products) Heading Source 0 = None, 1 = magnetic, 2 = GNSS velocity (note: see manual for limitations) +# Note: For the GQ7, this setting has no effect. See filter_auto_heading_alignment_selector +# Note: When using a -10/-AR product. This MUST be set to 0 or the node will not start +filter_heading_source : 1 + +# (GX5 and previous,-45 models only) Dynamics Mode 1 = Portable (default), 2 = Automotive, 3 = Airborne (<2Gs), 4 = Airborne High G (<4Gs) +filter_dynamics_mode : 1 + +# (GQ7 only) GNSS Aiding Source Control +# 1 = All internal receivers +# 2 = External GNSS messages provided by user +# 3 = Internal GNSS Receiver 1 only +# 4 = Internal GNSS Receiver 2 only +filter_gnss_aiding_source_control: 1 + +# ****************************************************************** +# IMU Settings +# ****************************************************************** + +# Static IMU message covariance values (the device does not generate these) +imu_orientation_cov : [0.01, 0, 0, 0, 0.01, 0, 0, 0, 0.01] +imu_linear_cov : [0.01, 0, 0, 0, 0.01, 0, 0, 0, 0.01] +imu_angular_cov : [0.01, 0, 0, 0, 0.01, 0, 0, 0, 0.01] +imu_mag_cov : [0.01, 0, 0, 0, 0.01, 0, 0, 0, 0.01] +imu_pressure_variance : 0.01 + +# ****************************************************************** +# Other Device Settings +# ****************************************************************** + +# (GQ7 Only) Hardware Odometer Control +enable_hardware_odometer : False +odometer_scaling : 0.0 +odometer_uncertainty : 0.0 + +# (GQ7/CV7 only) GPIO Configuration +# +# For information on possible configurations and specific pin options refer to the MSCL MipNodeFeatures command, supportedGpioConfigurations. +# +# GQ7 GPIO Pins = +# 1 - GPIO1 (primary port pin 7) - Features = 0 - Unused, 1 - GPIO, 2 - PPS, 3 - Encoder +# 2 - GPIO2 (primary port pin 9) - Features = 0 - Unused, 1 - GPIO, 2 - PPS, 3 - Encoder +# 3 - GPIO3 (aux port pin 7) - Features = 0 - Unused, 1 - GPIO, 2 - PPS, 3 - Encoder +# 4 - GPIO4 (aux port pin 9) - Features = 0 - Unused, 1 - GPIO, 2 - PPS, 3 - Encoder +# +# CV7 GPIO Pins = +# 1 - GPIO1 (pin 7) - Features = 0 - Unused, 1 - GPIO, 2 - PPS, 5 - UART +# 2 - GPIO2 (pin 9) - Features = 0 - Unused, 1 - GPIO, 2 - PPS, 5 - UART +# 3 - GPIO3 (pin 6) - Features = 0 - Unused, 1 - GPIO, 2 - PPS, 5 - UART +# 4 - GPIO4 (pin 10) - Features = 0 - Unused, 1 - GPIO, 2 - PPS, 5 - UART +# +# GPIO Behavior = +# 0 - Unused +# 1 - Input +# 2 - Output Low +# 3 - Output High +# +# PPS Behavior = +# 0 - Unused +# 1 - Input +# 2 - Output +# +# Encoder Behavior = +# 0 - Unused +# 1 - Encoder A +# 2 - Encoder B +# +# UART Behavior = +# 0x21 - UART port 2 transmit (only valid for GPIO 1 and 2) +# 0x22 - UART port 2 receive (only valid for GPIO 1 and 2) +# 0x31 - UART port 3 transmit (only valid for GPIO 3 and 4) +# 0x32 - UART port 3 receive (only valid for GPIO 3 and 4) +# +# Pin Mode Bitfield = +# 1 - open drain +# 2 - pulldown +# 4 - pullup +gpio_config : False + +gpio1_feature : 0 +gpio1_behavior : 0 +gpio1_pin_mode : 0 + +gpio2_feature : 0 +gpio2_behavior : 0 +gpio2_pin_mode : 0 + +gpio3_feature : 0 +gpio3_behavior : 0 +gpio3_pin_mode : 0 + +gpio4_feature : 0 +gpio4_behavior : 0 +gpio4_pin_mode : 0 + +# (GQ7 only) SBAS options +sbas_enable: True +sbas_enable_ranging: False +sbas_enable_corrections: True +sbas_apply_integrity: False + +# (GQ7 only) SBAS included PRNs +# Note: ROS2 can't handle empty arrays in a yml file, so uncomment this line and fill it in if you want to specify PRNs +#sbas_included_prns: [] + +# Low pass filter configuration. +# Note: The device may fail if one of these is enabled, and the device does not support the relevant measurement +# accel_* will affect data in /imu/data_raw if enabled +# gyro_* will affect data in /imu/data_raw if enabled +# mag_* will affect data in /imu/mag if enabled +# pressure_* will affect data in /imu/pressure if enabled +low_pass_filter_config : True + +accel_low_pass_filter_enable : False +accel_low_pass_filter_auto : False +accel_low_pass_filter_frequency : 0 + +gyro_low_pass_filter_enable : False +gyro_low_pass_filter_auto : False +gyro_low_pass_filter_frequency : 0 + +mag_low_pass_filter_enable : False +mag_low_pass_filter_auto : False +mag_low_pass_filter_frequency : 0 + +pressure_low_pass_filter_enable : False +pressure_low_pass_filter_auto : False +pressure_low_pass_filter_frequency : 0 + +# ****************************************************************** +# Publisher Settings +# ****************************************************************** +# +# Note: If set to 0, the data will not be stremaed from the device, and the publisher will not be created + +# The speed at which the individual IMU publishers will publish at. +imu_data_raw_rate : 1 # Rate of imu/data_raw topic +imu_data_rate : 100 # Rate of imu/data topic +imu_mag_data_rate : 0 # Rate of imu/mag topic +imu_pressure_data_rate : 0 # Rate of imu/pressure topic +imu_wheel_speed_data_rate : 0 # Rate of imu/wheel_Speed topic + +# The speed at which the individual GNSS1 publishers will publish at. +gnss1_llh_position_data_rate : 10 # Rate of gnss_1/llh_position topic +gnss1_velocity_data_rate : 10 # Rate of gnss_1/velocity topic +gnss1_velocity_ecef_data_rate : 10 # Rate of gnss_1/velocity_ecef topic + # Note: gnss1_odometry_earth_data_rate depends on the contents of this message. + # If it is set to a higher value, this message will be published at that rate. +gnss1_odometry_earth_data_rate : 10 # Rate of gnss_1/odometry_earth topic +gnss1_time_data_rate : 0 # Rate of gnss_1/time topic + +# The speed at which the individual GNSS2 publishers will publish at. +gnss2_llh_position_data_rate : 10 # Rate of gnss_2/llh_position topic +gnss2_velocity_data_rate : 2 # Rate of gnss_2/velocity topic +gnss2_velocity_ecef_data_rate : 0 # Rate of gnss_2/velocity_ecef topic + # Note: gnss2_odometry_earth_data_rate depends on the contents of this message. + # If it is set to a higher value, this message will be published at that rate. +gnss2_odometry_earth_data_rate : 10 # Rate of gnss_2/odometry_earth topic +gnss2_time_data_rate : 0 # Rate of gnss_2/time topic + +# The speed at which the individual Filter publishers will publish at. +filter_human_readable_status_data_rate : 100 # Rate of ekf/status +filter_imu_data_rate : 0 # Rate of ekf/imu/data topic + # Note: Both filter_odometry_earth_data_rate and filter_odometry_map_data_rate depend on the contents of this message. + # If either are set to a higher value, this message will be published at that rate. +filter_llh_position_data_rate : 100 # Rate of ekf/llh_position topic +filter_velocity_data_rate : 0 # Rate of ekf/velocity topic + # Note: filter_odometry_map_data_rate depends on the contents of this message. + # If either are set to a higher value, this message will be published at that rate. +filter_velocity_ecef_data_rate : 0 # Rate of ekf/velocity_ecef topic + # Note: filter_odometry_earth_data_rate depends on the contents of this message. + # If either are set to a higher value, this message will be published at that rate. +filter_odometry_earth_data_rate : 100 # Rate of ekf/odometry_earth topic +filter_odometry_map_data_rate : 100 # Rate of ekf/odometry_map topic +filter_dual_antenna_heading_data_rate : 10 # Rate of ekf/dual_antenna_heading topic + # Note: mip_filter_gnss_position_aiding_status_data_rate depends on the contents of this message. + # If either are set to a higher value, this message will be published at that rate. + +# The speed at which the individual MIP publishers will publish at. +mip_sensor_overrange_status_data_rate : 0 # Rate of mip/sensor/overrange_status topic +mip_sensor_temperature_statistics_data_rate : 0 # Rate of mip/sensor/temperature_statistics topic + +mip_gnss1_fix_info_data_rate : 10 # Rate of mip/gnss_1/fix_info topic +mip_gnss1_sbas_info_data_rate : 0 # Rate of mip/gnss_1/sbas_info topic +mip_gnss1_rf_error_detection_data_rate : 0 # Rate of mip/gnss_1/rf_error_detection + +mip_gnss2_fix_info_data_rate : 10 # Rate of mip/gnss_1/fix_info topic +mip_gnss2_sbas_info_data_rate : 0 # Rate of mip/gnss_2/sbas_info topic +mip_gnss2_rf_error_detection_data_rate : 0 # Rate of mip/gnss_2/rf_error_detection + +mip_filter_status_data_rate : 10 # Rate of mip/filter/status topic +mip_filter_gnss_position_aiding_status_data_rate : 10 # Rate of mip/filter/gnss_aiding_status + # Note: filter_llh_position_data_rate depends on the contents of this message. + # If it is set to a higher value, this message will be published at that rate. +mip_filter_multi_antenna_offset_correction_data_rate : 0 # Rate of mip/filter/multi_antenna_offset_correction + # Note: This message will also affect the frequency that the transform between frame_id and gnss_1/2_frame_id are published +mip_filter_gnss_dual_antenna_status_data_rate : 0 # Rate of mip/filter/gnss_dual_antenna_status + # Note: filter_dual_antenna_heading_data_rate depends on the contents of this message. + # If either are set to a higher value, this message will be published at that rate. +mip_filter_aiding_measurement_summary_data_rate : 0 # Rate of mip/filter/aiding_measurement_summary topic + + +# ****************************************************************** +# NMEA streaming settings +# ****************************************************************** + +# (GQ7 only) NMEA message format. If set to false, all NMEA message configuration will not have any affect +nmea_message_config: False + +# Allow NMEA messages with the same talker IDs on different data sources (descriptor sets) +# In most cases, this should be set to False, as multiple messages of the same type with the same talker ID from a different descriptor set could cause confusion when parsing. +nmea_message_allow_duplicate_talker_ids: False + +# NMEA messages in the sensor (IMU) descriptor set +# In order to enable a message, set nmea_message_config to true, and then change the 'data_rate' of the sentences you want to the desired rate in hertz +imu_nmea_prkr_data_rate: 0 + +# NMEA messages in the GNSS1 descriptor set +# In order to enable a message, set nmea_message_config to true, and then change the 'data_rate' of the sentences you want to the desired rate in hertz +# +# Note: gnss1_nmea_talker_id can be any of the follwing numeric values: +# 1 - Sentences will start with GN +# 2 - Sentences will start with GP +# 3 - Sentences will start with GA +# 4 - Sentences will start with GL +# The purpose of the talker ID is to differentiate when the same message_id comes from different data sources (descriptor sets) +# The gnss1_nmea_talker_id will be applied to all NMEA messages from the GNSS1 descriptor set +gnss1_nmea_talker_id: 1 +gnss1_nmea_gga_data_rate: 0 +gnss1_nmea_gll_data_rate: 0 +gnss1_nmea_gsv_data_rate: 0 # Note that this message_id will not use the gnss1_talker_id since the talker ID will come from the actual constellation the message originates from +gnss1_nmea_rmc_data_rate: 0 +gnss1_nmea_vtg_data_rate: 0 +gnss1_nmea_hdt_data_rate: 0 +gnss1_nmea_zda_data_rate: 0 + +# NMEA messages in the GNSS2 descriptor set +# In order to enable a message, set nmea_message_config to true, and then change the 'data_rate' of the sentences you want to the desired rate in hertz +# +# Note: gnss2_nmea_talker_id can be any of the follwing numeric values: +# 1 - Sentences will start with GN +# 2 - Sentences will start with GP +# 3 - Sentences will start with GA +# 4 - Sentences will start with GL +# The purpose of the talker ID is to differentiate when the same message_id comes from different data sources (descriptor sets) +# The gnss2_nmea_talker_id will be applied to all NMEA messages from the GNSS2 descriptor set +gnss2_nmea_talker_id: 2 +gnss2_nmea_gga_data_rate: 0 +gnss2_nmea_gll_data_rate: 0 +gnss2_nmea_gsv_data_rate: 0 # Note that this message_id will not use the gnss1_talker_id since the talker ID will come from the actual constellation the message originates from +gnss2_nmea_rmc_data_rate: 0 +gnss2_nmea_vtg_data_rate: 0 +gnss2_nmea_hdt_data_rate: 0 +gnss2_nmea_zda_data_rate: 0 + +# NMEA messages in the filter descriptor set +# In order to enable a message, set nmea_message_config to true, and then change the 'data_rate' of the sentences you want to the desired rate in hertz +# +# Note: filter_nmea_talker_id can be any of the follwing numeric values: +# 1 - Sentences will start with GN +# 2 - Sentences will start with GP +# 3 - Sentences will start with GA +# 4 - Sentences will start with GL +# The purpose of the talker ID is to differentiate when the same message_id comes from different data sources (descriptor sets) +# The filter_nmea_talker_id will be applied to all NMEA messages from the filter descriptor set +filter_nmea_talker_id: 3 +filter_nmea_gga_data_rate: 0 +filter_nmea_gll_data_rate: 0 +filter_nmea_rmc_data_rate: 0 +filter_nmea_hdt_data_rate: 0 +filter_nmea_prka_data_rate: 0 # Note that this message_id will not have any talker ID on it since it is proprietary and can only come from the filter descriptor set + +# (CV7-INS only) External aiding measurement configuration +subscribe_ext_time : False +subscribe_ext_fix : False +subscribe_ext_vel_ned : False +subscribe_ext_vel_enu : False +subscribe_ext_vel_ecef : False +subscribe_ext_vel_body : False +subscribe_ext_heading_ned : False +subscribe_ext_heading_enu : False +subscribe_ext_mag : False +subscribe_ext_pressure : False \ No newline at end of file diff --git a/rb_ws/src/buggy/launch/debug_filter.launch b/rb_ws/src/buggy/launch/debug_filter.launch index 48094ea..98a36b2 100644 --- a/rb_ws/src/buggy/launch/debug_filter.launch +++ b/rb_ws/src/buggy/launch/debug_filter.launch @@ -9,7 +9,7 @@ - + diff --git a/rb_ws/src/buggy/launch/ghost_auton.launch b/rb_ws/src/buggy/launch/ghost_auton.launch index 76ce13c..4810f02 100644 --- a/rb_ws/src/buggy/launch/ghost_auton.launch +++ b/rb_ws/src/buggy/launch/ghost_auton.launch @@ -14,7 +14,7 @@ args="$(arg starting_pose) $(arg velocity) $(arg buggy_name)"/> - + diff --git a/rb_ws/src/buggy/launch/sc-main.launch b/rb_ws/src/buggy/launch/sc-main.launch index e76c68d..5b3316a 100755 --- a/rb_ws/src/buggy/launch/sc-main.launch +++ b/rb_ws/src/buggy/launch/sc-main.launch @@ -3,9 +3,9 @@ - + - + @@ -14,11 +14,11 @@ - + - + \ No newline at end of file diff --git a/rb_ws/src/buggy/launch/sc-system.launch b/rb_ws/src/buggy/launch/sc-system.launch index de560f1..219c44b 100644 --- a/rb_ws/src/buggy/launch/sc-system.launch +++ b/rb_ws/src/buggy/launch/sc-system.launch @@ -2,7 +2,7 @@ - + diff --git a/rb_ws/src/buggy/scripts/auton/autonsystem.py b/rb_ws/src/buggy/scripts/auton/autonsystem.py index 14a3c6c..e4fd0e3 100755 --- a/rb_ws/src/buggy/scripts/auton/autonsystem.py +++ b/rb_ws/src/buggy/scripts/auton/autonsystem.py @@ -21,6 +21,8 @@ from path_planner import PathPlanner from pose import Pose +import navpy + class AutonSystem: """ Top-level class for the RoboBuggy autonomous system @@ -68,6 +70,10 @@ def __init__(self, self.other_odom_msg = None self.use_gps_pos = False + #TODO: DOUBLE CONVERTING HERE, NOT A GOOD IDEA + rospy.Subscriber("/ekf/odometry_earth", Odometry, self.change_utm_latlon) + self.latlonodom = rospy.Publisher(self_name + "/nav/odom", Odometry, queue_size=1) + rospy.Subscriber(self_name + "/nav/odom", Odometry, self.update_self_odom) rospy.Subscriber(self_name + "/gnss1/odom", Odometry, self.update_self_odom_backup) rospy.Subscriber(self_name + "/nav/traj", TrajectoryMsg, self.update_traj) @@ -103,6 +109,12 @@ def __init__(self, self.profile = profile self.tick_caller() + def change_utm_latlon(self, msg): + new_msg = msg + lat, lon, _ = navpy.ecef2lla([msg.pose.pose.position.x, msg.pose.pose.position.y, msg.pose.pose.position.z]) + new_msg.pose.pose.position.x, new_msg.pose.pose.position.y = lon, lat + self.latlonodom.publish(new_msg) + # functions to read data from ROS nodes def update_use_gps(self, msg): diff --git a/rb_ws/src/buggy/scripts/auton/buggystate.py b/rb_ws/src/buggy/scripts/auton/buggystate.py index f806476..5444886 100644 --- a/rb_ws/src/buggy/scripts/auton/buggystate.py +++ b/rb_ws/src/buggy/scripts/auton/buggystate.py @@ -13,6 +13,8 @@ import rospy +#BROKEN TOPIC PATHS, INCREDIBLY BROKEN + class BuggyState: """ Basically a translator from ROSOdom to ensure everything is in the correct units. diff --git a/rb_ws/src/buggy/scripts/auton/publish_rtk_err.py b/rb_ws/src/buggy/scripts/auton/publish_rtk_err.py index 0760088..1e85d7b 100755 --- a/rb_ws/src/buggy/scripts/auton/publish_rtk_err.py +++ b/rb_ws/src/buggy/scripts/auton/publish_rtk_err.py @@ -10,6 +10,8 @@ from pose import Pose from world import World + +#BROKEN BROKEN BROKEN BROKEN class RTKErrPublisher(): """ diff --git a/rb_ws/src/buggy/scripts/auton/rolling_sanity_check.py b/rb_ws/src/buggy/scripts/auton/rolling_sanity_check.py index eca106a..ef540fb 100644 --- a/rb_ws/src/buggy/scripts/auton/rolling_sanity_check.py +++ b/rb_ws/src/buggy/scripts/auton/rolling_sanity_check.py @@ -6,12 +6,14 @@ from nav_msgs.msg import Odometry from std_msgs.msg import Bool, String, Int8MultiArray, Int8 -from microstrain_inertial_msgs.msg import FilterStatus, ImuOverrangeStatus +from microstrain_inertial_msgs.msg import MipFilterStatus, ImuOverrangeStatus from geometry_msgs.msg import PoseStamped from world import World from pose import Pose +#BROKEN BROKEN BROKEN + class SanityCheck: """ Wrapper to publish a lot of error and debug data regarding the estimated position of the specified buggy and INS output @@ -47,7 +49,7 @@ def __init__(self, rospy.Subscriber(self_name + "/imu/overrange_status", ImuOverrangeStatus, self.update_overrange_status) - rospy.Subscriber(self_name + "/nav/status.status_flags", FilterStatus, self.update_status_flags) + rospy.Subscriber(self_name + "/nav/status.status_flags", MipFilterStatus, self.update_status_flags) rospy.Subscriber(self_name + "/gnss1/fix_Pose/", PoseStamped, self.update_gps_location) rospy.Subscriber(self_name + "/nav/odom", Odometry, self.update_filter_location) @@ -81,7 +83,7 @@ def __init__(self, def update_overrange_status(self, msg : ImuOverrangeStatus): self.imu_overrange_status = msg.status - def update_status_flags(self, msg : FilterStatus): + def update_status_flags(self, msg : MipFilterStatus): self.status_flag_val = msg.gq7_status_flags def update_gps_location(self, msg : PoseStamped): diff --git a/rb_ws/src/buggy/scripts/util/rosbag_to_pose_csv.py b/rb_ws/src/buggy/scripts/util/rosbag_to_pose_csv.py index 9ae9bf2..60d4520 100644 --- a/rb_ws/src/buggy/scripts/util/rosbag_to_pose_csv.py +++ b/rb_ws/src/buggy/scripts/util/rosbag_to_pose_csv.py @@ -4,6 +4,7 @@ import rosbag from tf.transformations import euler_from_quaternion +#BROKEN BROKEN BROKEN BROKEN def main(): """ diff --git a/rb_ws/src/buggy/scripts/util/rosbag_to_waypoints_json.py b/rb_ws/src/buggy/scripts/util/rosbag_to_waypoints_json.py index 6c50f38..2dc110a 100755 --- a/rb_ws/src/buggy/scripts/util/rosbag_to_waypoints_json.py +++ b/rb_ws/src/buggy/scripts/util/rosbag_to_waypoints_json.py @@ -5,6 +5,8 @@ import rosbag +#BROKEN BROKEN BROKEN + def main(): # Read in bag path from command line parser = argparse.ArgumentParser() diff --git a/rb_ws/src/buggy/scripts/visualization/telematics.py b/rb_ws/src/buggy/scripts/visualization/telematics.py index 182b274..a3e4893 100755 --- a/rb_ws/src/buggy/scripts/visualization/telematics.py +++ b/rb_ws/src/buggy/scripts/visualization/telematics.py @@ -8,7 +8,7 @@ from std_msgs.msg import String from std_msgs.msg import Int8 -from microstrain_inertial_msgs.msg import GNSSFixInfo +from microstrain_inertial_msgs.msg import MipGnssFixInfo class Telematics: """ @@ -24,19 +24,19 @@ def __init__(self): self.gnss1_pose_publisher = rospy.Publisher("/gnss1/fix_Pose", PoseStamped, queue_size=10) self.gnss1_covariance_publisher = rospy.Publisher("/gnss1/fix_FloatArray_Covariance", Float64MultiArray, queue_size=10) - self.gnss1_subscriber = rospy.Subscriber("/gnss1/fix", NavSatFix, self.convert_navsatfix_to_pose_covariance, (self.gnss1_pose_publisher, self.gnss1_covariance_publisher)) + self.gnss1_subscriber = rospy.Subscriber("/gnss1/llh_position", NavSatFix, self.convert_navsatfix_to_pose_covariance, (self.gnss1_pose_publisher, self.gnss1_covariance_publisher)) self.gnss2_pose_publisher = rospy.Publisher("/gnss2/fix_Pose", PoseStamped, queue_size=10) self.gnss2_covariance_publisher = rospy.Publisher("/gnss2/fix_FloatArray_Covariance", Float64MultiArray, queue_size=10) - self.gnss2_subscriber = rospy.Subscriber("/gnss2/fix", NavSatFix, self.convert_navsatfix_to_pose_covariance, (self.gnss2_pose_publisher, self.gnss2_covariance_publisher)) + self.gnss2_subscriber = rospy.Subscriber("/gnss2/llh_position", NavSatFix, self.convert_navsatfix_to_pose_covariance, (self.gnss2_pose_publisher, self.gnss2_covariance_publisher)) self.gnss1_fixinfo_publisher = rospy.Publisher("/gnss1/fix_info_republished", String, queue_size=10) self.gnss1_fixinfo_int_publisher = rospy.Publisher("/gnss1/fix_info_republished_int", Int8, queue_size=10) - self.gnss1_fixinfo_subscriber = rospy.Subscriber("/gnss1/fix_info", GNSSFixInfo, self.republish_fixinfo, (self.gnss1_fixinfo_publisher, self.gnss1_fixinfo_int_publisher)) + self.gnss1_fixinfo_subscriber = rospy.Subscriber("/mip/gnss1/fix_info", MipGnssFixInfo, self.republish_fixinfo, (self.gnss1_fixinfo_publisher, self.gnss1_fixinfo_int_publisher)) self.gnss2_fixinfo_publisher = rospy.Publisher("/gnss2/fix_info_republished", String, queue_size=10) self.gnss2_fixinfo_int_publisher = rospy.Publisher("/gnss2/fix_info_republished_int", Int8, queue_size=10) - self.gnss2_fixinfo_subscriber = rospy.Subscriber("/gnss2/fix_info", GNSSFixInfo, self.republish_fixinfo, (self.gnss2_fixinfo_publisher, self.gnss2_fixinfo_int_publisher)) + self.gnss2_fixinfo_subscriber = rospy.Subscriber("/mip/gnss2/fix_info", MipGnssFixInfo, self.republish_fixinfo, (self.gnss2_fixinfo_publisher, self.gnss2_fixinfo_int_publisher)) def convert_odometry_to_navsatfix(self, msg): """Convert Odometry-type to NavSatFix-type for plotting on Foxglove diff --git a/telematics_layout.json b/telematics_layout.json index 9cfab8f..51b7202 100644 --- a/telematics_layout.json +++ b/telematics_layout.json @@ -5,7 +5,7 @@ "diffMethod": "custom", "diffTopicPath": "", "showFullMessageForDiff": false, - "topicPath": "/nav/dual_antenna_status" + "topicPath": "/mip/ekf/gnss_dual_antenna_status" }, "RawMessages!3xary91": { "diffEnabled": false, @@ -94,8 +94,8 @@ "followTopic": "", "layer": "map", "topicColors": { - "/gnss1/fix": "#e34f4f", - "/gnss2/fix": "#4fd5e3" + "/gnss1/llh_position": "#e34f4f", + "/gnss2/llh_position": "#4fd5e3" }, "zoomLevel": 16, "maxNativeZoom": 20 @@ -152,7 +152,7 @@ "diffMethod": "custom", "diffTopicPath": "", "showFullMessageForDiff": false, - "topicPath": "/gnss2/fix_info", + "topicPath": "/mip/gnss2/fix_info", "expansion": "none" } },