diff --git a/docker_auton/Dockerfile b/docker_auton/Dockerfile
index b162e452..ff8c4ea7 100755
--- a/docker_auton/Dockerfile
+++ b/docker_auton/Dockerfile
@@ -9,7 +9,8 @@ RUN apt update
RUN apt-get install -y -qq \
python3-pip \
python3-tk \
- vim git tmux tree sl htop x11-apps
+ vim git tmux tree sl htop x11-apps \
+ python-is-python3
RUN apt-get install -y -qq \
ros-noetic-rosserial \
diff --git a/rb_ws/src/buggy/launch/ekf.launch b/rb_ws/src/buggy/launch/ekf.launch
index 0ec1f943..894bbdcc 100644
--- a/rb_ws/src/buggy/launch/ekf.launch
+++ b/rb_ws/src/buggy/launch/ekf.launch
@@ -10,21 +10,23 @@
+
+
+
-
-
+
-
-
+
+
+
-
-
+
\ No newline at end of file
diff --git a/rb_ws/src/buggy/scripts/auton/buggystate.py b/rb_ws/src/buggy/scripts/auton/buggystate.py
index f8064768..f618963d 100644
--- a/rb_ws/src/buggy/scripts/auton/buggystate.py
+++ b/rb_ws/src/buggy/scripts/auton/buggystate.py
@@ -6,7 +6,7 @@
from std_msgs.msg import Bool
-from microstrain_inertial_msgs.msg import GNSSFixInfo
+# from microstrain_inertial_msgs.msg import GNSSFixInfo
@@ -50,21 +50,6 @@ def update_gnss2(self, msg):
def update_gnss1_fix(self, msg):
self.gps_fix = msg.fix_type
- def odom_to_navsatfix(self, odom):
- """Convert Odometry-type to NavSatFix-type for plotting on Foxglove
- Args:
- odom (Odometry): odometry object to convert
- """
- lat = odom.pose.pose.position.y
- long = odom.pose.pose.position.x
- down = odom.pose.pose.position.z
- new_odom = NavSatFix()
- new_odom.header = odom.header
- new_odom.latitude = lat
- new_odom.longitude = long
- new_odom.altitude = down
- return new_odom
-
def get_gps_fix(self):
fix_string = "fix type: "
if (self.gps_fix == 0):
@@ -111,3 +96,18 @@ def get_velocity(self):
return None
return self.filter_odom.twist.twist.linear
+
+ def odom_to_navsatfix(odom):
+ """Convert Odometry-type to NavSatFix-type for plotting on Foxglove
+ Args:
+ odom (Odometry): odometry object to convert
+ """
+ lat = odom.pose.pose.position.y
+ long = odom.pose.pose.position.x
+ down = odom.pose.pose.position.z
+ new_odom = NavSatFix()
+ new_odom.header = odom.header
+ new_odom.latitude = lat
+ new_odom.longitude = long
+ new_odom.altitude = down
+ return new_odom
diff --git a/rb_ws/src/buggy/scripts/util/ekf.py b/rb_ws/src/buggy/scripts/util/ekf.py
old mode 100644
new mode 100755
index e69de29b..bce0af74
--- a/rb_ws/src/buggy/scripts/util/ekf.py
+++ b/rb_ws/src/buggy/scripts/util/ekf.py
@@ -0,0 +1,56 @@
+#!/usr/bin/env python3
+
+import sys
+
+# Allows import of world and pose from auton directory
+# sys.path.append("/rb_ws/src/buggy/scripts/auton")
+
+# from buggystate import BuggyState
+from threading import Lock
+import rospy
+
+# Ros Message Imports
+from geometry_msgs.msg import PoseWithCovarianceStamped as ROSOdom
+from sensor_msgs.msg import NavSatFix
+
+
+class ekfTranslator:
+ def __init__(self):
+ """
+ self_name: Buggy namespace
+ other_name: Only requried by SC for passing buggy namespace
+ teensy_name: required for communication, different for SC and NAND
+
+ Initializes the subscribers, rates, and ros topics (including debug topics)
+ """
+ self.odomMsg = None
+
+ rospy.Subscriber(
+ "/robot_pose_ekf/odom_combined", ROSOdom, self.set_odom
+ )
+
+ self.lock = Lock()
+
+ self.publisher = rospy.Publisher("/robot_pose_ekf/navsatfix", NavSatFix, queue_size=1)
+
+ def set_odom(self, msg):
+ with self.lock:
+ lat = msg.pose.pose.position.y
+ long = msg.pose.pose.position.x
+ down = msg.pose.pose.position.z
+ new_odom = NavSatFix()
+ new_odom.header = msg.header
+ new_odom.latitude = lat
+ new_odom.longitude = long
+ new_odom.altitude = down
+ self.publisher.publish(new_odom)
+ print("ekf Translated")
+
+
+if __name__ == "__main__":
+ rospy.init_node("ekf_translator")
+ translate = ekfTranslator()
+ print("Initialized EKF Translator")
+ x = 1
+ while True:
+ x+=1
\ No newline at end of file