Skip to content

Commit

Permalink
pylint fixes for 2d sim and other existing modules
Browse files Browse the repository at this point in the history
  • Loading branch information
Jackack committed Feb 3, 2024
1 parent ba8305f commit e687393
Show file tree
Hide file tree
Showing 4 changed files with 13 additions and 11 deletions.
12 changes: 7 additions & 5 deletions rb_ws/src/buggy/scripts/2d_sim/engine.py
Original file line number Diff line number Diff line change
@@ -1,14 +1,16 @@
#! /usr/bin/env python3

import sys
import threading

import rospy
from geometry_msgs.msg import Pose, Twist, PoseWithCovariance, TwistWithCovariance
from std_msgs.msg import Float64
from sensor_msgs.msg import NavSatFix
from nav_msgs.msg import Odometry
import threading
import numpy as np
import utm
import time
import sys



class Simulator:
Expand Down Expand Up @@ -70,7 +72,7 @@ def __init__(self, starting_pose, velocity, buggy_name):
# self.e_utm = utm_coords[0]
# self.n_utm = utm_coords[1]

self.e_utm, self.n_utm, self.heading = self.starting_poses[starting_pose]
self.e_utm, self.n_utm, self.heading = self.starting_poses[starting_pose]
self.velocity = velocity # m/s

self.steering_angle = 0 # degrees
Expand Down Expand Up @@ -122,7 +124,7 @@ def dynamics(self, state, v):
dstate (np.Array): time derivative of state from dynamics
"""
l = Simulator.WHEELBASE
x, y, theta, delta = state
_, _, theta, delta = state

return np.array([v * np.cos(theta),
v * np.sin(theta),
Expand Down
2 changes: 1 addition & 1 deletion rb_ws/src/buggy/scripts/auton/path_projection.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
import time
# import time
import numpy as np
from pose import Pose

Expand Down
2 changes: 1 addition & 1 deletion rb_ws/src/buggy/scripts/auton/trajectory.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
import json
import matplotlib.pyplot as plt
import uuid
import matplotlib.pyplot as plt
import numpy as np

from scipy.interpolate import Akima1DInterpolator, CubicSpline
Expand Down
8 changes: 4 additions & 4 deletions rb_ws/src/buggy/scripts/auton/world.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ def gps_to_world(lat, lon):
y = utm_coords[1] - World.WORLD_NORTH_ZERO

return x, y

@staticmethod
def utm_to_world_pose(pose: Pose) -> Pose:
"""Converts UTM coordinates to world coordinates
Expand Down Expand Up @@ -80,7 +80,7 @@ def world_to_utm_pose(pose: Pose) -> Pose:
utm_e = pose.x + World.WORLD_EAST_ZERO
utm_n = pose.y + World.WORLD_NORTH_ZERO
return Pose(utm_e, utm_n, pose.theta)

@staticmethod
def world_to_utm_numpy(coords):
"""Converts world coordinates to utm coordinates
Expand All @@ -98,7 +98,7 @@ def world_to_utm_numpy(coords):
utm_offset = np.stack((utm_offset_e, utm_offset_n), axis=1)

return coords + utm_offset

@staticmethod
def utm_to_world_numpy(coords):
"""Converts utm coordinates to world coordinates
Expand Down Expand Up @@ -136,7 +136,7 @@ def world_to_gps(x, y):
lon = utm_coords[1]

return lat, lon

@staticmethod
def utm_to_gps(x, y):
"""Converts utm coordinates to GPS coordinates
Expand Down

0 comments on commit e687393

Please sign in to comment.