Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Ukf #82

Merged
merged 5 commits into from
Apr 6, 2024
Merged

Ukf #82

Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 6 additions & 1 deletion rb_ws/src/buggy/scripts/auton/pose.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

from geometry_msgs.msg import Pose as ROSPose
from tf.transformations import euler_from_quaternion
from tf.transformations import quaternion_from_euler


class Pose:
Expand Down Expand Up @@ -38,6 +39,10 @@ def rospose_to_pose(rospose: ROSPose):
p = Pose(rospose.position.x, rospose.position.y, yaw)
return p

def heading_to_quaternion(heading):
q = quaternion_from_euler(0, 0, heading)
return q

def __init__(self, x, y, theta):
self.x = x
self.y = y
Expand Down Expand Up @@ -94,7 +99,7 @@ def from_mat(mat):
Creates a pose from a 3x3 homogeneous transformation matrix
"""
return Pose(mat[0, 2], mat[1, 2], np.arctan2(mat[1, 0], mat[0, 0]))

def invert(self):
"""
Inverts the pose
Expand Down
13 changes: 13 additions & 0 deletions rb_ws/src/buggy/scripts/serial/host_comm.py
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@ def update(self, b):
MSG_TYPE_STEERING = b'ST'
MSG_TYPE_BRAKE = b'BR'
MSG_TYPE_ALARM = b'AL'
MSG_TYPE_BNYATEL = b'BT'

@dataclass
class Odometry:
Expand All @@ -71,6 +72,15 @@ class Odometry:
radio_seqnum: int
gps_seqnum: int

@dataclass
class BnyaTelemetry:
x: float
y: float
velocity: float # In METERS / SECOND
steering: float # In DEGREES
heading: float # In RADIANS
heading_rate: float # In RADIANS / SECOND

class IncompletePacket(Exception):
pass

Expand Down Expand Up @@ -183,6 +193,9 @@ def read_packet(self):
debug = struct.unpack('<fff??B?BBxx', payload)
# print(debug)
return debug
elif msg_type == MSG_TYPE_BNYATEL:
x, y, vel, steering, heading, heading_rate = struct.unpack('<ffffff', payload)
return BnyaTelemetry(x, y, vel, steering, heading, heading_rate)
else:
return None
# print(f'Unknown packet type {msg_type}')
Expand Down
20 changes: 19 additions & 1 deletion rb_ws/src/buggy/scripts/serial/ros_to_bnyahaj.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,16 @@
import argparse
import rospy


#Ros Message Imports
from std_msgs.msg import Float64, Bool, Int8, UInt8
from nav_msgs.msg import Odometry as ROSOdom

from host_comm import *

from world import World
from pose import Pose
import numpy as np

class Translator:
def __init__(self, self_name, other_name, teensy_name):
Expand Down Expand Up @@ -78,7 +81,7 @@ def reader_thread(self):
while True:
packet = self.comms.read_packet()
# print("trying to read odom")
if isinstance(packet, Odometry):
if isinstance(packet, Odometry) and self_name == "SC":
rospy.logdebug("packet", packet)
#Publish to odom topic x and y coord
odom = ROSOdom()
Expand All @@ -91,6 +94,21 @@ def reader_thread(self):
except Exception as e:
rospy.logwarn("Unable to convert other buggy position to lon lat" + e)

elif isinstance(packet, BnyaTelemetry) and self_name == "NAND":
rospy.logdebug("packet", packet)
odom = ROSOdom()
try:
lat, long = World.utm_to_gps(packet.y, packet.x)
odom.pose.pose.position.x = long
odom.pose.pose.position.y = lat
odom.twist.twist.angular.z = packet.heading_rate
odom.pose.pose.orientation = Pose.heading_to_quaternion(packet.heading + np.pi/2)

self.odom_publisher.publish(odom)
except Exception as e:
rospy.logwarn("Unable to convert other buggy position to lon lat" + e)


elif isinstance(packet, tuple): #Are there any other packet that is a tuple
# print(packet)
self.rc_steering_angle_publisher.publish(Float64(packet[0]))
Expand Down
Loading