1
1
import numpy as np
2
2
3
3
import rospy
4
+ from std_msgs .msg import Float64
4
5
from sensor_msgs .msg import NavSatFix
5
6
from geometry_msgs .msg import Pose as ROSPose
6
7
from nav_msgs .msg import Odometry
@@ -34,6 +35,9 @@ def __init__(self, buggy_name, start_index=0) -> None:
34
35
self .debug_error_publisher = rospy .Publisher (
35
36
buggy_name + "/auton/debug/error" , ROSPose , queue_size = 1
36
37
)
38
+ self .debug_yaw_rate_publisher = rospy .Publisher (
39
+ buggy_name + "/auton/debug/yaw_rate" , Float64 , queue_size = 1
40
+ )
37
41
38
42
def compute_control (
39
43
self , state_msg : Odometry , trajectory : Trajectory
@@ -89,7 +93,7 @@ def compute_control(
89
93
trajectory .get_index_from_distance (traj_dist ))
90
94
91
95
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
93
97
94
98
# Calculate cross track error by finding the distance from the buggy to the tangent line of
95
99
# the reference trajectory
@@ -110,11 +114,19 @@ def compute_control(
110
114
StanleyController .CROSS_TRACK_GAIN * error_dist , speed + StanleyController .K_SOFT
111
115
)
112
116
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
+
113
122
# Calculate yaw rate error
114
123
r_meas = yaw_rate
115
124
r_traj = speed * (trajectory .get_heading_by_index (trajectory .get_index_from_distance (traj_dist ) + 0.05 )
116
125
- trajectory .get_heading_by_index (trajectory .get_index_from_distance (traj_dist ))) / 0.05
117
126
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 ))
118
130
119
131
steering_cmd = error_heading + cross_track_component + StanleyController .K_D_YAW * (r_traj - r_meas )
120
132
steering_cmd = np .clip (steering_cmd , - np .pi / 9 , np .pi / 9 )
0 commit comments