Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions src/controller/launch/controller.launch
Original file line number Diff line number Diff line change
@@ -1,5 +1,11 @@
<?xml version="1.0"?>
<launch>
<node pkg="controller" type="controller.py" name="controller" output="screen">
</node>
<node pkg="traffic_detection" type="traffic_detection.py" name="traffic_detection">
</node>
<node pkg="obj_distance_estimator" type="obj_distance_estimator.py" name="obj_distance_estimator">
</node>
<node pkg="pedestrian_detection" type="pedestrian_detection.py" name="pedestrian_detection">
</node>
</launch>
17 changes: 9 additions & 8 deletions src/controller/scripts/controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@ def __init__(self):
self.stop_duration = rospy.Duration(3.0)
self.min_speed = 0.2
self.max_speed = 0.4
self.min_ang_speed = 0.6
self.max_ang_speed = 1.2
self.speed_limit = self.max_speed

self.object_detected = False
Expand Down Expand Up @@ -70,13 +72,13 @@ def sign_callback(self, msg):
rospy.loginfo("Stop sign detected")
self.stop_detected = True
self.stop_block_end_timer = rospy.Time.now() + self.stop_duration
cmd = Twist()
self.cmd_vel_pub.publish(cmd)
# cmd = Twist()
# self.cmd_vel_pub.publish(cmd)
elif sign == "red_light":
rospy.loginfo("Red light detected")
self.traffic_light_state = "red"
cmd = Twist()
self.cmd_vel_pub.publish(cmd)
# cmd = Twist()
# self.cmd_vel_pub.publish(cmd)
elif sign == "yellow_light":
rospy.loginfo("Yellow light detected")
self.traffic_light_state = "yellow"
Expand Down Expand Up @@ -131,7 +133,7 @@ def cmd_callback(self, msg):
rospy.loginfo("Stopped at a stop sign")
return

cmd = self.apply_traffic_rules(msg)
cmd = self.apply_traffic_sign_rules(msg)

if self.pedestrian_detected:
self.cmd_vel_pub.publish(cmd)
Expand All @@ -151,9 +153,9 @@ def apply_traffic_sign_rules(self, msg):
if self.traffic_light_state == "red" and cmd.linear.x > 0:
cmd.linear.x = 0.0
elif self.traffic_light_state == "yellow" and cmd.linear.x > 0:
cmd.linear.x *= 0.5 # Reduce speed by half for yellow light
cmd.linear.x = self.speed_limit / 2 # Reduce speed by half for yellow light

# Apply turn restrictions
# # Apply turn restrictions
if not self.turn_restrictions["left_allowed"] and cmd.angular.z > 0:
cmd.angular.z = 0.0 # Block left turns

Expand All @@ -165,7 +167,6 @@ def apply_traffic_sign_rules(self, msg):
cmd.angular.z = -0.2 # Force slight right turn
if cmd.linear.x > 0.3:
cmd.linear.x = 0.3 # Reduce speed for right turn

return cmd

def run(self):
Expand Down
4 changes: 2 additions & 2 deletions src/obj_distance_estimator/scripts/obj_distance_estimator.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@
from sensor_msgs.msg import PointCloud2
from std_msgs.msg import Bool

LASER_DIST_THRESHOLD = 0.40
DEPTH_DIST_THRESHOLD = 0.50
LASER_DIST_THRESHOLD = 0.30
DEPTH_DIST_THRESHOLD = 0.30

class obj_dist_est():

Expand Down
10 changes: 5 additions & 5 deletions src/pedestrian_detection/scripts/pedestrian_detection.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,10 +59,10 @@ def detect_pedestrian_lane(self, image):
height, width, _ = image.shape

# Define region of interest
roi_top = int(height * 0.25)
roi_bottom = int(height)
roi_width = int(width)
roi_left = int(0)
roi_top = int(height * 0.6)
roi_bottom = int(height * 0.8)
roi_width = int(width * 0.5)
roi_left = int(width * 0.25)
roi_right = int(roi_left + roi_width)

# Extract ROI
Expand All @@ -81,7 +81,7 @@ def detect_pedestrian_lane(self, image):
white_pixel_count = np.sum(white_mask > 0)
cv2.putText(debug_image, f"White pixels: {white_pixel_count}",
(10, 30), cv2.FONT_HERSHEY_SIMPLEX, 0.7, (255, 255, 255), 2)
if white_pixel_count < 10000:
if white_pixel_count < 4000:
return False, debug_image

# Apply morphological operations to clean up the mask
Expand Down
9 changes: 7 additions & 2 deletions src/sign_detection/scripts/sign_detection.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,11 +54,16 @@ def callback(self, data):

final_label = None

score = -1
for result in results:
for box in result.boxes:
confidence = float(box.conf[0].item()) # Extract confidence score
if confidence >= 0.80: # Confidence threshold check
label = self.model.names[int(box.cls[0].item())] # Get label
label = self.model.names[int(box.cls[0].item())]
if label == "red_light" or label == "green_light" or label == "yellow_light":
if score < confidence:
score = confidence
final_label = label
elif confidence >= 0.80:

x1, y1, x2, y2 = box.xyxy[0]
x1, y1, x2, y2 = float(x1), float(y1), float(x2), float(y2)
Expand Down