Skip to content

Commit

Permalink
Fixed pylint warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
Jackack committed Mar 5, 2024
1 parent 5acac83 commit afe6172
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 22 deletions.
22 changes: 11 additions & 11 deletions rb_ws/src/buggy/scripts/auton/model_predictive_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -515,19 +515,19 @@ def compute_trajectory(self, current_pose: Pose, trajectory: Trajectory, current
# p is the position of NAND in x-y space

n = np.array([100, 100])
p = np.array([0, 1])
# p = np.array([0, 1])
c = np.concatenate((n, np.zeros((2, )))).reshape(1, self.N_STATES)

C2 = sparse.kron(
np.eye(self.MPC_HORIZON),
np.hstack(
(
np.zeros((1, self.N_CONTROLS)),
c
)
),
format="csc",
)
# C2 = sparse.kron(
# np.eye(self.MPC_HORIZON),
# np.hstack(
# (
# np.zeros((1, self.N_CONTROLS)),
# c
# )
# ),
# format="csc",
# )

D = sparse.vstack([self.C + C1, self.X, self.U])
# D = sparse.vstack([self.C + C1, self.X, self.U, C2])
Expand Down
6 changes: 0 additions & 6 deletions rb_ws/src/buggy/scripts/auton/publish_rtk_err.py
Original file line number Diff line number Diff line change
@@ -1,16 +1,10 @@
#!/usr/bin/env python3


from abc import ABC, abstractmethod

from threading import Lock
import sys

import numpy as np

import rospy
from nav_msgs.msg import Odometry
from sensor_msgs.msg import NavSatFix
from geometry_msgs.msg import PoseStamped
from std_msgs.msg import Float64
from pose import Pose
Expand Down
8 changes: 3 additions & 5 deletions rb_ws/src/buggy/scripts/debug/debug_steer.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,5 @@
#!/usr/bin/env python3

from abc import ABC, abstractmethod

import rospy
from std_msgs.msg import Float64

Expand All @@ -28,8 +26,8 @@ def loop(self):
if (add):
steer_cmd += 18 / 100
else:
steer_cmd -= 18 / 100
steer_cmd -= 18 / 100

self.steer_publisher.publish(Float64(steer_cmd))

tick_count += 1
Expand All @@ -38,7 +36,7 @@ def loop(self):

if (steer_cmd >= 18):
add = False

if (steer_cmd <= -18):
add = True
rate.sleep()
Expand Down

0 comments on commit afe6172

Please sign in to comment.