Skip to content

Part 6 Line Following (Setup)

Use this code as a starting point for Part A of the Line Following exercise.

line_follower.py
#!/usr/bin/env python3

import rospy
import cv2
from cv_bridge import CvBridge, CvBridgeError
from sensor_msgs.msg import Image

from tb3 import Tb3Move

class LineFollower():
    def __init__(self):
        node_name = "line_follower"
        rospy.init_node(node_name, anonymous=True)
        self.rate = rospy.Rate(5)

        self.cvbridge_interface = CvBridge()
        self.img_sub = rospy.Subscriber(
            "/camera/rgb/image_raw", Image, self.camera_cb)
        self.robot_controller = Tb3Move()

        self.ctrl_c = False
        rospy.on_shutdown(self.shutdown_ops)

    def shutdown_ops(self):
        self.robot_controller.stop()
        cv2.destroyAllWindows()
        self.ctrl_c = True

    def camera_cb(self, img_data):
        try:
            cv_img = self.cvbridge_interface.imgmsg_to_cv2(
                img_data, desired_encoding="bgr8")
        except CvBridgeError as e:
            print(e)

        cv2.imshow("camera image", cv_img)

        height, width, _ = cv_img.shape
        ## TODO 1 (1)

        ## TODO 2 (2)

        ## TODO 3 (3)

        cv2.waitKey(1)

    def main(self):
        while not self.ctrl_c:
            self.rate.sleep()

if __name__ == '__main__':
    node = LineFollower()
    try:
        node.main()
    except rospy.ROSInterruptException:
        pass
  1. Image Cropping

    Apply some cropping to the raw camera image (cv_img).

    Crop it to around 1/5 of its original height, and to a width so that the pink line is just visible at the edge of the image.

    Call your new cropped image something like cropped_img. You could then use the cv2.imshow() method to display this in an additional pop-up window when the node is run:

    cv2.imshow("cropped_image", cropped_img)
    

  2. Colour Detection

    Filter the cropped image by selecting appropriate HSV values so that the pink line can be isolated from the rest of the image.

    You may need to use the tuos_examples\image_colours.py node again to help you identify the correct Hue and Saturation value range.

    Use cv2.cvtColor() to convert your cropped_img into an HSV colour representation:

    hsv_img = cv2.cvtColor(cropped_img, cv2.COLOR_BGR2HSV)
    

    Use cv2.inRange() to create a mask with the HSV value range that you have determined:

    line_mask = cv2.inRange(
        hsv_img, {lower_hsv_values}, {upper_hsv_values}
    )
    

    And then use cv2.bitwise_and() to create a new image with the mask applied, so that the coloured line is isolated:

    line_isolated = cv2.bitwise_and(
        cropped_img, cropped_img, mask = line_mask
    )
    

  3. Locating the line

    Finally, find the horizontal position of the line in the robot's viewpoint.

    Calculate the image moments of the pink colour blob that represents the line (line_mask) using the cv2.moments() method. Remember that it's the \(c_{y}\) component that we're interested in here:

    \[ c_{y}=\dfrac{M_{10}}{M_{00}} \]

    Ultimately, this will provide us with the feedback signal that we can use for a proportional controller that we will implement in the next part of the exercise.

    Once you've obtained the image moments (and cy), use cv2.circle() to mark the centroid of the line on the filtered image (line_isolated) with a circle. For this, you'll also need to calculate the \(c_{z}\) component of the centroid:

    \[ c_{z}=\dfrac{M_{01}}{M_{00}} \]

    Remember that once you've done all this you can display the filtered image of the isolated line (with the circle to denote the centroid location) using cv2.imshow() again:

    cv2.imshow("filtered line", line_isolated)
    

← Back to Part 6 - Exercise 4 (Part A)