Skip to content

Commit

Permalink
pylint fixes
Browse files Browse the repository at this point in the history
more pylint fixes

pylint fixes for 2d sim and other existing modules

pylint fixes yet again

pylint fixes yet again #2
  • Loading branch information
Jackack committed Feb 3, 2024
1 parent 87acd66 commit af61d0c
Show file tree
Hide file tree
Showing 15 changed files with 112 additions and 118 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
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
75 changes: 37 additions & 38 deletions rb_ws/src/buggy/scripts/auton/autonsystem.py
Original file line number Diff line number Diff line change
@@ -1,14 +1,16 @@
#!/usr/bin/env python3

import argparse
import cProfile
from threading import Lock

import rospy
import sys

# ROS Message Imports
from std_msgs.msg import Float32, Float64, Bool
from nav_msgs.msg import Odometry

import numpy as np
from threading import Lock

from trajectory import Trajectory
from world import World
Expand All @@ -21,9 +23,6 @@
from path_planner import PathPlanner
from pose import Pose

import argparse
import cProfile

class AutonSystem:
"""
Top-level class for the RoboBuggy autonomous system
Expand All @@ -45,13 +44,13 @@ class AutonSystem:
ticks = 0

def __init__(self,
global_trajectory,
global_trajectory,
local_controller,
brake_controller,
self_name,
brake_controller,
self_name,
other_name,
profile) -> None:


self.global_trajectory = global_trajectory

Expand All @@ -70,7 +69,7 @@ def __init__(self,
self.ticks = 0
self.self_odom_msg = None
self.other_odom_msg = None

rospy.Subscriber(self_name + "/nav/odom", Odometry, self.update_self_odom)
if self.has_other_buggy:
rospy.Subscriber(other_name + "/nav/odom", Odometry, self.update_other_odom)
Expand Down Expand Up @@ -112,17 +111,17 @@ def update_self_odom(self, msg):
def update_other_odom(self, msg):
with self.lock:
self.other_odom_msg = msg

def update_other_steering_angle(self, msg):
with self.lock:
self.other_steering = msg.data

def tick_caller(self):
while ((not rospy.is_shutdown()) and
(self.self_odom_msg == None or
(self.self_odom_msg == None or
(self.has_other_buggy and self.other_odom_msg == None))): # with no message, we wait
rospy.sleep(0.001)

# wait for covariance matrix to be better
while ((not rospy.is_shutdown()) and
(self.self_odom_msg.pose.covariance[0] ** 2 + self.self_odom_msg.pose.covariance[7] ** 2 > 1**2)):
Expand All @@ -141,7 +140,7 @@ def tick_caller(self):
# run the planner every 10 ticks
# thr main cycle runs at 100hz, the planner runs at 10hz, but looks 1 second ahead

if not self.other_odom_msg is None and self.ticks % 10 == 0:
if not self.other_odom_msg is None and self.ticks % 10 == 0:

# for debugging, publish distance to other buggy
with self.lock:
Expand All @@ -156,12 +155,12 @@ def tick_caller(self):
cProfile.runctx('self.planner_tick()', globals(), locals(), sort="cumtime")
else:
self.planner_tick()

self.local_controller_tick()
self.ticks += 1
self.rosrate.sleep()
self.rosrate.sleep()



def get_world_pose_and_speed(self, msg):
current_rospose = msg.pose.pose
# Check if the pose covariance is a sane value. Publish a warning if insane
Expand All @@ -177,7 +176,7 @@ def get_world_pose_and_speed(self, msg):
# Get data from message
pose_gps = Pose.rospose_to_pose(current_rospose)
return World.gps_to_world_pose(pose_gps), current_speed

def local_controller_tick(self):
with self.lock:
self_pose, self_speed = self.get_world_pose_and_speed(self.self_odom_msg)
Expand All @@ -198,40 +197,40 @@ def planner_tick(self):
if __name__ == "__main__":
rospy.init_node("auton_system")
parser = argparse.ArgumentParser()
parser.add_argument("--controller",
parser.add_argument("--controller",
type=str,
help="set controller type",
required=True)

parser.add_argument(
"--dist",
"--dist",
type=float,
help="start buggy at meters distance along the path",
required=True)

parser.add_argument(
"--traj",
type=str,
help="path to the trajectory file, relative to /rb_ws/src/buggy/paths/",
"--traj",
type=str,
help="path to the trajectory file, relative to /rb_ws/src/buggy/paths/",
required=True)

parser.add_argument(
"--self_name",
type=str,
help="name of ego-buggy",
help="name of ego-buggy",
required=True)

parser.add_argument(
"--other_name",
"--other_name",
type=str,
help="name of other buggy, if left unspecified, the autonsystem assumes it is the only buggy on the course",
help="name of other buggy, if left unspecified, the autonsystem assumes it is the only buggy on the course",
required=False)

parser.add_argument(
"--profile",
action='store_true',
help="turn on profiling for the path planner")

args, _ = parser.parse_known_args()
ctrl = args.controller
start_dist = args.dist
Expand All @@ -253,22 +252,22 @@ def planner_tick(self):
local_ctrller = None
if (ctrl == "stanley"):
local_ctrller = StanleyController(
self_name,
self_name,
start_index=start_index)

elif (ctrl == "pure_pursuit"):
local_ctrller = PurePursuitController(
self_name,
self_name,
start_index=start_index)

elif (ctrl == "mpc"):
local_ctrller = ModelPredictiveController(
self_name,
self_name,
start_index=start_index)

if (local_ctrller == None):
raise Exception("Invalid Controller Argument")

auton_system = AutonSystem(
trajectory,
local_ctrller,
Expand Down
4 changes: 1 addition & 3 deletions rb_ws/src/buggy/scripts/auton/controller.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,7 @@
from abc import ABC, abstractmethod

import numpy as np
from trajectory import Trajectory
from pose import Pose
import rospy
from sensor_msgs.msg import NavSatFix
from world import World

Expand Down Expand Up @@ -59,7 +57,7 @@ def compute_control(
float (desired steering angle)
"""
raise NotImplementedError

def plot_trajectory(
self, current_pose: Pose, trajectory: Trajectory, current_speed: float
):
Expand Down
18 changes: 7 additions & 11 deletions rb_ws/src/buggy/scripts/auton/model_predictive_controller.py
Original file line number Diff line number Diff line change
@@ -1,29 +1,25 @@
#!/usr/bin/env python3
from abc import ABC, abstractmethod

import time
from threading import Lock

from numba import njit

import numpy as np
import osqp
import scipy
from scipy import sparse

import rospy
from std_msgs.msg import Float32, Float64, Float64MultiArray, MultiArrayDimension, Bool
from nav_msgs.msg import Odometry
from std_msgs.msg import Float64, Float64MultiArray, MultiArrayDimension, Bool
from sensor_msgs.msg import NavSatFix
from geometry_msgs.msg import Pose as ROSPose
from geometry_msgs.msg import Pose2D
from rospy.numpy_msg import numpy_msg

from pose import Pose
from trajectory import Trajectory
from controller import Controller
from world import World

from threading import Lock

import matplotlib.pyplot as plt

Expand Down Expand Up @@ -437,7 +433,7 @@ def compute_trajectory(self, current_pose: Pose, trajectory: Trajectory, current
# 0 0 0 A2 B2 ... 0 0 0
# 0 0 0 0 0 ... 0 0 0
# 0 0 0 0 0 ... AN-1 BN-1 -I]
#
#
# D = [C; X; U]
# X selects all the states from z
# U selects all the controls from z
Expand Down Expand Up @@ -601,17 +597,17 @@ def compute_trajectory(self, current_pose: Pose, trajectory: Trajectory, current
if self.TIME:
t = time.time()
results = self.solver.solve()

steer_angle = results.x[self.N_CONTROLS + self.N_STATES - 1]
solution_trajectory = np.reshape(results.x, (self.MPC_HORIZON, self.N_STATES + self.N_CONTROLS))
state_trajectory = solution_trajectory[:, self.N_CONTROLS:(self.N_CONTROLS + self.N_STATES)]

print("status", results.info.status, results.info.status_val)
if not (results.info.status == "solved" or results.info.status == "solved inaccurate"):
return reference_trajectory

state_trajectory += reference_trajectory
steer_rate_trajectory = solution_trajectory[:, :self.N_CONTROLS]
# steer_rate_trajectory = solution_trajectory[:, :self.N_CONTROLS]

if self.TIME:
solve_time = 1000 * (time.time() - t)
Expand All @@ -627,7 +623,7 @@ def compute_trajectory(self, current_pose: Pose, trajectory: Trajectory, current

if self.PLOT:
# Plot the results
fig, [[ax1, ax2], [ax3, ax4]] = plt.subplots(2, 2)
_, [[ax1, ax2], [ax3, ax4]] = plt.subplots(2, 2)

# Extract the states
states = np.zeros((self.MPC_HORIZON, self.N_STATES))
Expand Down
Loading

0 comments on commit af61d0c

Please sign in to comment.