2323from rclpy .node import Node
2424
2525
26- CONTROL_COEFFICIENT = 0.002
26+ CONTROL_COEFFICIENT = 0.0005
2727
2828
2929class LaneFollower (Node ):
@@ -41,22 +41,26 @@ def __on_camera_image(self, message):
4141
4242 # Segment the image by color in HSV color space
4343 img = cv2 .cvtColor (img , cv2 .COLOR_RGB2HSV )
44- mask = cv2 .inRange (img , np .array ([70 , 120 , 170 ]), np .array ([120 , 160 , 210 ]))
44+ mask = cv2 .inRange (img , np .array ([50 , 110 , 150 ]), np .array ([120 , 255 , 255 ]))
4545
4646 # Find the largest segmented contour
4747 contours , _ = cv2 .findContours (mask , cv2 .RETR_EXTERNAL , cv2 .CHAIN_APPROX_NONE )
48+
49+ command_message = AckermannDrive ()
50+ command_message .speed = 50.0
51+ command_message .steering_angle = 0.0
52+
4853 if contours :
4954 largest_contour = max (contours , key = cv2 .contourArea )
5055 largest_contour_center = cv2 .moments (largest_contour )
51- center_x = int (largest_contour_center ['m10' ] / largest_contour_center ['m00' ])
5256
53- # Find error (the lane distance from the target distance)
54- error = center_x - 120
57+ if largest_contour_center ['m00' ] != 0 :
58+ center_x = int (largest_contour_center ['m10' ] / largest_contour_center ['m00' ])
59+ # Find error (the lane distance from the target distance)
60+ error = center_x - 190
61+ command_message .steering_angle = error * CONTROL_COEFFICIENT
5562
56- command_message = AckermannDrive ()
57- command_message .speed = 10.0
58- command_message .steering_angle = error * CONTROL_COEFFICIENT
59- self .__ackermann_publisher .publish (command_message )
63+ self .__ackermann_publisher .publish (command_message )
6064
6165
6266def main (args = None ):
0 commit comments