Skip to content

Commit 440751c

Browse files
committed
updated stanley controller
1 parent 33d3403 commit 440751c

File tree

2 files changed

+29
-1
lines changed

2 files changed

+29
-1
lines changed

rb_ws/src/buggy/scripts/auton/stanley_controller.py

Lines changed: 13 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
import numpy as np
22

33
import rospy
4+
from std_msgs.msg import Float64
45
from sensor_msgs.msg import NavSatFix
56
from geometry_msgs.msg import Pose as ROSPose
67
from nav_msgs.msg import Odometry
@@ -34,6 +35,9 @@ def __init__(self, buggy_name, start_index=0) -> None:
3435
self.debug_error_publisher = rospy.Publisher(
3536
buggy_name + "/auton/debug/error", ROSPose, queue_size=1
3637
)
38+
self.debug_yaw_rate_publisher = rospy.Publisher(
39+
buggy_name + "/auton/debug/yaw_rate", Float64, queue_size=1
40+
)
3741

3842
def compute_control(
3943
self, state_msg: Odometry, trajectory: Trajectory
@@ -89,7 +93,7 @@ def compute_control(
8993
trajectory.get_index_from_distance(traj_dist))
9094

9195
error_heading = ref_heading - current_pose.theta
92-
error_heading = np.arctan2(np.sin(error_heading), np.cos(error_heading))
96+
error_heading = np.arctan2(np.sin(error_heading), np.cos(error_heading)) #bounding erro_heading
9397

9498
# Calculate cross track error by finding the distance from the buggy to the tangent line of
9599
# the reference trajectory
@@ -110,11 +114,19 @@ def compute_control(
110114
StanleyController.CROSS_TRACK_GAIN * error_dist, speed + StanleyController.K_SOFT
111115
)
112116

117+
ddxdt, ddydt = trajectory.get_dheading_by_index(trajectory.get_index_from_distance(traj_dist))
118+
dxdt, dydt = np.cos(ref_heading), np.sin(ref_heading)
119+
120+
r_traj_2 = speed * (1/(1 + (dydt/dxdt)**2)) * (ddydt/dxdt - (dydt * ddxdt)/(dxdt ** 2))
121+
113122
# Calculate yaw rate error
114123
r_meas = yaw_rate
115124
r_traj = speed * (trajectory.get_heading_by_index(trajectory.get_index_from_distance(traj_dist) + 0.05)
116125
- trajectory.get_heading_by_index(trajectory.get_index_from_distance(traj_dist))) / 0.05
117126

127+
if (abs(StanleyController.K_D_YAW * (r_meas - r_traj)) > 6.0):
128+
rospy.logwarn(f"spiked yaw_rate: actual: {r_meas}, expected_basic: {r_traj}, expected_analytic: {r_traj_2}")
129+
self.debug_yaw_rate_publisher.publish(StanleyController.K_D_YAW * (r_traj_2 - r_meas))
118130

119131
steering_cmd = error_heading + cross_track_component + StanleyController.K_D_YAW * (r_traj - r_meas)
120132
steering_cmd = np.clip(steering_cmd, -np.pi / 9, np.pi / 9)

rb_ws/src/buggy/scripts/auton/trajectory.py

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -120,6 +120,22 @@ def get_heading_by_index(self, index):
120120
theta = np.arctan2(dydt, dxdt)
121121

122122
return theta
123+
124+
def get_dheading_by_index(self, index):
125+
"""Gets the derivative of the heading at given index along trajectory,
126+
interpolating if necessary
127+
128+
Args:
129+
index (float): index along the trajectory
130+
131+
Returns:
132+
float: (theta) in rads
133+
"""
134+
# theta = np.interp(index, self.indices, self.positions[:, 2])
135+
ddxdt, ddydt = self.interpolation(index, nu=2).reshape((-1, 2)).T
136+
137+
return ddxdt, ddydt
138+
123139

124140
def get_heading_by_distance(self, distance):
125141
"""Gets the heading at given distance along trajectory,

0 commit comments

Comments
 (0)