Skip to content

Commit

Permalink
Do world to utm conversion without world.py
Browse files Browse the repository at this point in the history
Rather than dealing with the two different Pose classes (from pose.py and rospy), just do the conversion directly in engine.oy
  • Loading branch information
PatXue committed Feb 18, 2024
1 parent 0f3faa1 commit 619d327
Showing 1 changed file with 7 additions and 7 deletions.
14 changes: 7 additions & 7 deletions rb_ws/src/buggy/scripts/2d_sim/engine.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,7 @@
from nav_msgs.msg import Odometry
import numpy as np
import utm
from buggy import Trajectory
from buggy.scripts.auton.world import World
from trajectory import Trajectory


class Simulator:
Expand Down Expand Up @@ -74,12 +73,11 @@ def __init__(self, starting_dist, velocity, buggy_name):

trajectory = Trajectory("/rb_ws/src/buggy/paths/buggycourse_safe_1.json")
init_x, init_y = trajectory.get_position_by_distance(starting_dist)
init_heading = np.rad2deg(trajectory.get_heading_by_distance(starting_dist))
init_pose = World.world_to_utm_pose(Pose(init_x, init_y, init_heading))
init_heading = np.rad2deg(trajectory.get_heading_by_distance(starting_dist))[0]

self.e_utm = init_pose.x
self.n_utm = init_pose.y
self.heading = init_pose.theta
self.e_utm = init_x + Simulator.UTM_EAST_ZERO
self.n_utm = init_y + Simulator.UTM_NORTH_ZERO
self.heading = init_heading
self.velocity = velocity # m/s

self.steering_angle = 0 # degrees
Expand All @@ -106,6 +104,7 @@ def update_velocity(self, data: Float64):
"""
with self.lock:
self.velocity = data.data

def get_steering_arc(self):
# Adapted from simulator.py (Joseph Li)
# calculate the radius of the steering arc
Expand All @@ -119,6 +118,7 @@ def get_steering_arc(self):
return np.inf

return Simulator.WHEELBASE / np.tan(np.deg2rad(steering_angle))

def dynamics(self, state, v):
""" Calculates continuous time bicycle dynamics as a function of state and velocity
Expand Down

0 comments on commit 619d327

Please sign in to comment.