12. Điều Khiển Robot Bằng Cử Chỉ Tay

12. Điều Khiển Robot Bằng Cử Chỉ Tay

Trong chương cuối cùng của sê-ri ROS Cơ Bản này, chúng ta sẽ kết hợp mọi thứ đã học được cho đến nay để hoàn thành một nhiệm vụ cuối cùng: di chuyển robot bằng cử chỉ tay.

Ý tưởng

Ý tưởng để làm phần này thật ra rất đơn giản và cũng không có gì mới. Trong chương trước, chúng ta đã sử dụng rqt_robot_steering, một GUI đơn giản mà ROS cung cấp để điều khiển robot di động. Về cơ bản, nó cho phép bạn thay đổi vận tốc tuyến tính (thanh trượt dọc) để tiến/lùi và vận tốc góc (thanh trượt ngang) để rẽ trái/phải. Các giá trị vận tốc này sau đó được đóng gói vào một Twist message và publish ra topic /robot_diff_drive_controller/cmd_vel.

rqt_robot_steering

Bây giờ thay vì sử dụng GUI này, bạn có thể sử dụng webcam để nhận biết các dấu tay (như ở chương 9) và chuyển đổi chúng để có các chức năng tương tự. Ngón trỏ trỏ lên/xuống (Forward/Backward) là để tiến/lùi, ngón cái (Turn Left/Turn Right) là để rẽ trái/phải và tất cả các ngón duỗi ra có nghĩa là dừng (Stop). Tất cả những gì chúng ta cần làm là viết một tập lệnh để chuyển đổi các cử chỉ này thành vận tốc và publish ra topic /robot_diff_drive_controller/cmd_vel.

hand-sign-robot-steering

Nếu bạn muốn thay đổi, thêm hoặc xóa các cử chỉ tay, hãy làm theo hướng dẫn ở phần này trong chương 9.

Hệ thống

Biểu đồ bên dưới mô tả cách toàn bộ hệ thống hoạt động. Các phần màu xanh lục là những gì chúng tôi đã làm từ các chương trước: node /my_camera đọc hình ảnh từ webcam và publish chúng lên topic /image_raw (từ các chương 78); một Node khác là /hand_sign_recognition subscribe /image_raw, xử lý hình ảnh và publish kết quả ra topic /gesture/hand_sign (từ chương 9). Chúng ta cần triển khai phần màu xanh lam, thực chất là một Node và hãy gọi nó là /hand_sign_control. Node này subscribe topic /gesture/hand_sign, chuyển đổi các ký hiệu tay thành các giá trị điều khiển và publish ra topic /robot_diff_drive_controller/ cmd_vel. Từ topic này, node /gazebo (từ chương 1011) sẽ nhận các giá trị vận tốc và điều khiển rô-bốt tương ứng.

hand-sign-mobile-robot-control-workflow

Triển khai

Sau khi có ý tưởng và hiểu cách hệ thống hoạt động, mình tin rằng việc triển khai sẽ khá đơn giản. Có nhiều cách khác nhau để làm và mình sẽ chỉ bạn một trong số đó. Hãy tạo một tập lệnh mới có tên sign_to_controller.py trong thư mục ros_hand_gesture_recognition/src. Về cơ bản, tập lệnh này sẽ xử lý các hoạt động trong phần màu xanh lá ở bên trên. Code được đặt tại đây và bên dưới là giải thích cho những phần code chính.

Đầu tiên, lớp GestureController được tạo. Trong __init__ của nó, các node hand_sign_control, gesture_subscribervel_publisher được khởi tạo. gesture_subscriber thực hiện hàm callback bất cứ khi nào nó nhận được mesage từ topic /gesture/hand_sign (tên topic này được định nghĩa trong tệp launch và được gọi bằng hàm rospy.get_param). vel_publisher publishTwist mesage tới topic /robot_diff_drive_controller/cmd_vel.

class GestureController:

    def __init__(self):
        rospy.init_node('hand_sign_control', anonymous=True)
        # Subscriber for subscribing the hand signs
        self.gesture_subcriber = rospy.Subscriber(rospy.get_param("hand_sign_recognition/publish_gesture_topic"), String, self.callback)
        # Publisher for publishing velocities 
        self.vel_publisher = rospy.Publisher("/robot_diff_drive_controller/cmd_vel", Twist, queue_size=10)
        # Velocity message
        self.vel_msg = Twist()
        # Velocity in/decrements
        self.linear_vel = 0.01 #[m/s]
        self.angular_vel = 0.1 #[rad/s]

Twist, một loại ROS mesage, biểu thị vận tốc trong không gian trống. Twist được chia thành 2 phần: tuyến tínhgóc. Mỗi phần là một vector có 3 thành phần con x, y, z. Trong trường hợp của chúng ta, rô-bốt được điều khiển bởi hai giá trị: vận tốc tuyến tính dọc theo trục X để tịnh tiến và vận tốc góc dọc theo trục Z để quay, do đó, chỉ có phần tử x trong tuyến tính và phần tử z trong angular là các tín hiệu điều khiển. Chúng được cập nhật trong hàm callback.

ros-twist-mobile-robot

Hàm callback là nơi diễn ra quá trình chuyển đổi và publish. Đầu tiên, nó kiểm tra cử chỉ đầu vào là gì. Nếu cử chỉ là Forward hoặc Backward (Tiến/Lùi) thì vận tốc tuyến tính được biểu thị bằng thành phần x của vel_msg.linear được tăng hoặc giảm tương ứng bởi linear_vel được đặt thành 0,01 m/s trong __init__. Nếu cử chỉ là Turn Right hoặc Turn Left (Rẽ Trái/Phải), vận tốc góc được biểu thị bằng thành phần z của vel_msg.angular sẽ được tăng hoặc giảm tương ứng bởi angular_vel được đặt thành 0,1 rad/s trong __init__ . Trong các trường hợp Tiến/Lùi, vận tốc góc này được đặt bằng 0 để rô-bốt đi thẳng mà không bị quay cùng lúc. Nếu cử chỉ là Stop hoặc NONE (NONE có nghĩa là không dấu tay nào được phát hiện), thì tốc độ tuyến tính và tốc độ góc được đặt thành 0 tức là rô-bốt sẽ dừng lại. Cuối cùng, vel_msg được publish bởi vel_publisher.

    def callback(self, gesture):
        if gesture.data ==  "Forward":
            self.vel_msg.linear.x += self.linear_vel
            self.vel_msg.angular.z = 0.
        elif gesture.data ==  "Backward":
            self.vel_msg.linear.x -= self.linear_vel
            self.vel_msg.angular.z = 0.
        elif gesture.data == "Turn Right":
            self.vel_msg.angular.z -= self.angular_vel
        elif gesture.data == "Turn Left":
            self.vel_msg.angular.z += self.angular_vel
        elif gesture.data == "Stop" or gesture.data == "NONE" :
            self.vel_msg.linear.x = 0
            self.vel_msg.angular.z = 0
        self.vel_publisher.publish(self.vel_msg)

Let's launch them all!

Để chạy chương trình cần có 4 tệp: sign_to_controller.py, my_cam.launch từ gói my_cam, hand_sign.launch từ gói ros_hand\ gesturerecognitiondrive_robot.launch từ gói ros_mobile_robot. Để tiết kiệm thời gian, bạn có thể nhóm 3 tệp launch đầu tiên vào một để chạy một thể bằng cách sử dụng thẻ include. Hãy gọi tệp này là sign_control.launch và đặt nó vào thư mục launch của package ros_hand_gesture_recognition . Sau đây là nội dung của nó.

<launch>
    <include file="$(find my_cam)/launch/my_cam.launch" />
    <include file="$(find ros_hand_gesture_recognition)/launch/hand_sign.launch" />

    <arg name="publish_gesture_topic" default="/gesture/hand_sign"/>
    <arg name="control_topic" default="/robot_diff_drive_controller/cmd_vel"/>

    <node name="sign_to_controller" pkg="ros_hand_gesture_recognition" type="sign_to_controller.py" output="screen">
        <param name="publish_gesture_topic" type="string" value="$(arg publish_gesture_topic)" />
        <param name="control_topic" type="string" value="$(arg control_topic)" />
    </node>
</launch>

Mở 2 terminal, trong cái đầu tiên chạy:

roslaunch ros_hand_gesture_recognition sign_control.launch

Trong cái thứ hai, chạy:

roslaunch ros_mobile_robot drive_robot.launch

Sau đó, bạn có thể điều khiển robot bằng tay của mình. Để cho thú vị hơn, bạn có thể thêm một số chướng ngại vật như là khối hộp, trụ và cầu trong Gazebo như tôi đã làm ở đây:

add-box-gazebo

Video này là một ví dụ:

Tiếp theo?

Thực sự tuyệt vời khi bạn đã hoàn thành loạt bài này. Bây giờ bạn đã biết gần hết những khái niệm cơ bản về ROS và thậm chí đã tạo ứng dụng ROS đầu tiên của mình. Từ thời điểm này, tùy theo mục đích của mình, bạn có thể bắt đầu khám phá các khía cạnh khác và vô vàn các package tuyệt vời trong ROS. Mình sẽ đặt một số link bên dưới để tham khảo nhưng chắc chắn vẫn còn nhiều cái khác mà mình không biết tới. Hãy để lại bình luận nếu bạn tìm thấy bất kỳ điều thú v gì. Sẽ có thêm nhiều post về chế tạo robot thật, ROS2, AI, v.v. tại Robodev, vì vậy bạn hãy nhớ đăng ký để được cập nhật. Cuối cùng, mình chúc bạn tiếp tục có nhiều niềm vui trong việc tìm tòi và chế tạo robot!

Nguồn tham khảo:

Did you find this article valuable?

Support Robodev Blog by becoming a sponsor. Any amount is appreciated!