QR Code Vision Tracking: Machine Vision Intergeration Into ROS

In this article, I will share the process of bringing a Python-based robotic arm QR code tracking system into ROS and running this project in a simulation environment.

video (6)

Youtube:

Environment Setup

For this project, it is recommended to use the following development environment and dependency versions:

Operating System : Ubuntu 20.04 LTS

ROS Version : Noetic

Python Version : Python 3.8 or higher

Library Version Requirement : pymycobot 3.6 or higher

Installing Key Dependencies

Run the following commands in the terminal to install the necessary Python libraries:

pip install stag-python opencv-python scipy numpy pymycobot

Creating a Workspace and Package in ROS

Creating a ROS Workspace

  1. Open the terminal and create a new ROS workspace called catkin_ws:
mkdir -p ~/catkin_ws/src
  1. Enter the workspace directory and initialize it:
cd ~/catkin_wscatkin_make
  1. Set up the environment variables to ensure ROS can locate the workspace:
echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrcsource ~/.bashrc

Tip : This configuration will load the workspace settings automatically each time a new terminal is opened.

Creating a ROS Package

  1. In the src directory, create a new ROS package called qr_tracking with required dependencies (such as rospy and std_msgs):
cd ~/catkin_ws/srccatkin_create_pkg qr_tracking rospy std_msgs

2.Verify the package creation. The qr_tracking directory should contain a standard ROS package structure, including CMakeLists.txt and package.xml files.

  1. Update dependencies: Open the package.xml file and ensure the following dependencies are included:
<?xml version="1.0"?>
<package format="2">
  <name>mycobot_280</name>
  <version>0.3.0</version>
  <description>The mycobot 280 package</description>

  <author email="lijun.zhang@elephantrobotics.com">ZhangLijun</author>
  <maintainer email="lijun.zhang@elephantrobotics.com">ZhangLijun</maintainer>

  <license>BSD</license>

  <url type="website">https://github.com/elephantrobotics/mycobot_ros</url>

  <buildtool_depend>catkin</buildtool_depend>

  <build_depend>roscpp</build_depend>
  <build_depend>rospy</build_depend>
  <build_depend>std_msgs</build_depend>
  <build_depend>actionlib</build_depend>
  <build_depend>mycobot_description</build_depend>
  <build_depend>mycobot_communication</build_depend>

  <build_export_depend>mycobot_communication</build_export_depend>
  <build_export_depend>mycobot_description</build_export_depend>

  <exec_depend>roscpp</exec_depend>
  <exec_depend>rospy</exec_depend>
  <exec_depend>std_msgs</exec_depend>
  <exec_depend>actionlib</exec_depend>
  <exec_depend>joint_state_publisher</exec_depend>
  <exec_depend>joint_state_publisher_gui</exec_depend>
  <exec_depend>robot_state_publisher</exec_depend>
  <exec_depend>xacro</exec_depend>
  <exec_depend>joy</exec_depend>
  <exec_depend>rviz</exec_depend>
  <exec_depend>controller_manager</exec_depend>
  <exec_depend>python-tk</exec_depend>
  <exec_depend>mycobot_description</exec_depend>
  <exec_depend>mycobot_communication</exec_depend>

  <export>
    <!-- Additional information for other tools can be added here -->
  </export>
</package>
  1. Rebuild the workspace to apply the ROS package configuration updates:
cd ~/catkin_wscatkin_make

Ensure that the URDF file for the robotic arm is correctly configured within the ROS package to display the model accurately.

Importing Python Files into the ROS Package

Setting Up the Scripts Directory

In your ROS package qr_tracking, create a folder named scripts to store the Python scripts. Use the following commands:

cd ~/catkin_ws/src/qr_tracking
mkdir scripts

Move your Python files (such as camera_detect.py, uvc_camera.py, marker_utils.py, etc.) to this scripts directory:

mv /path/to/camera_detect.py ~/catkin_ws/src/qr_tracking/scripts/
mv /path/to/uvc_camera.py ~/catkin_ws/src/qr_tracking/scripts/
mv /path/to/marker_utils.py ~/catkin_ws/src/qr_tracking/scripts/

Modifying Python Files for ROS Compatibility

To ensure the Python scripts work with ROS, you need to make some adjustments, such as importing ROS libraries, initializing ROS nodes, and defining message publishers/subscribers. Using camera_detect.py as an example, here are the primary modifications needed:

  1. Import ROS Libraries

At the top of your Python file, add imports for rospy and any necessary ROS message types:

import rospy   from std_msgs.msg import String
  1. Initialize the ROS Node

Initialize a ROS node at the beginning of your code:

rospy.init_node('camera_detection_node', anonymous=True)
  1. Define Topic Publisher/Subscriber

Based on the requirements, define a publisher or subscriber. For example, to publish QR code detection results:

pub = rospy.Publisher('qr_detection', String, queue_size=10)   rate = rospy.Rate(10)  # 10 Hz

Then, you can set up a function to detect QR codes and publish the results. For example:

# Assuming there is a function to detect QR codes
   def detect_qr_code():
       while not rospy.is_shutdown():
           # Detection logic here
           detection_result = "QR code detected"  # This is the detection result
           rospy.loginfo(detection_result)
           pub.publish(detection_result)
           rate.sleep()

Code Example

Below is a simplified code snippet showing how to publish QR code detection results in camera_detect.py:

#!/usr/bin/env python
import rospy
from std_msgs.msg import String

def detect_qr_code():
    pub = rospy.Publisher('qr_detection', String, queue_size=10)
    rospy.init_node('camera_detection_node', anonymous=True)
    rate = rospy.Rate(10)  # 10 Hz

    while not rospy.is_shutdown():
        # Replace with actual detection logic
        detection_result = "QR code detected"  # Simulated detection result
        rospy.loginfo(detection_result)
        pub.publish(detection_result)
        rate.sleep()

if __name__ == '__main__':
    try:
        detect_qr_code()
    except rospy.ROSInterruptException:
        pass

Note : Ensure the Python files are executable by running chmod +x ~/catkin_ws/src/qr_tracking/scripts/*.py.

Configuring the CMakeLists.txt File

Overview of CMake Configuration

In ROS, the CMakeLists.txt file is a core configuration file for each package, specifying how to compile and install files within the package. It includes configuration details like compiler options, library dependencies, and installation paths. For Python scripts to function as ROS nodes, we need to make a few necessary adjustments to this file.

Modifying CMakeLists.txt

To make the Python scripts executable within ROS, follow these steps:

  1. Add Catkin Build Dependencies

Ensure CMakeLists.txt includes a find_package statement to locate catkin and the necessary ROS dependencies, such as rospy and std_msgs. Here’s an example:

cmake_minimum_required(VERSION 2.8.3)
   project(mycobot_280)
   add_compile_options(-std=c++11)

   ## Find catkin and any catkin packages
   find_package(catkin REQUIRED COMPONENTS
     roscpp
     rospy
     std_msgs
     actionlib
     image_transport
     cv_bridge
   )
  1. Install Python Scripts

Use catkin_install_python to specify the installation path for Python scripts and to ensure they have executable permissions. Assuming your Python scripts are located in the scripts directory, add the following section to CMakeLists.txt:

catkin_install_python(PROGRAMS
     scripts/follow_display.py
     scripts/slider_control.py
     scripts/teleop_keyboard.py
     scripts/listen_real.py
     scripts/listen_real_of_topic.py
     scripts/simple_gui.py
     scripts/follow_display_gripper.py
     scripts/slider_control_gripper.py
     scripts/listen_real_gripper.py
     scripts/detect_stag.py
     DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
   )

This command installs the Python scripts to the ROS package’s binary directory and ensures they have executable permissions after compilation.

  1. Add Dependencies

Before calling catkin_package(), declare the dependencies to ensure ROS correctly resolves them. For example:

catkin_package(     CATKIN_DEPENDS std_msgs actionlib   )
  1. Complete Example

Here is a sample configuration for the CMakeLists.txt file:

cmake_minimum_required(VERSION 2.8.3)
   project(mycobot_280)
   add_compile_options(-std=c++11)

   ## Find catkin and any catkin packages
   find_package(catkin REQUIRED COMPONENTS
     roscpp
     rospy
     std_msgs
     actionlib
     image_transport
     cv_bridge
   )

   ## Declare a catkin package
   catkin_package(
     CATKIN_DEPENDS std_msgs actionlib
   )

   ## Include directories
   include_directories(include ${catkin_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS})

   ## Install Python scripts
   catkin_install_python(PROGRAMS
     scripts/follow_display.py
     scripts/slider_control.py
     scripts/teleop_keyboard.py
     scripts/listen_real.py
     scripts/listen_real_of_topic.py
     scripts/simple_gui.py
     scripts/follow_display_gripper.py
     scripts/slider_control_gripper.py
     scripts/listen_real_gripper.py
     scripts/detect_stag.py
     DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
   )

   ## Install launch and config directories
   install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
     PATTERN "setup_assistant.launch" EXCLUDE)
   install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

   ## OpenCV requirements
   find_package(OpenCV REQUIRED)
   add_executable(opencv_camera src/opencv_camera)
   target_link_libraries(opencv_camera ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})
   add_executable(camera_display src/camera_display)
   target_link_libraries(camera_display ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})

With these modifications, the Python scripts will be part of the ROS package, given executable permissions, and runnable using ROS tools such as rosrun.

This section is crucial for guiding users on how to compile, start, and verify the project’s functionality in ROS.

6. Compiling and Running

Compiling the Workspace

After configuring all aspects of your ROS package, you need to compile the workspace to generate and configure the necessary resources.

  1. Ensure you are in the root directory of the workspace:
cd ~/catkin_ws
  1. Run catkin_make to compile the workspace:
catkin_make

If the compilation succeeds, you should see output similar to:

[100%] Built target qr_tracking

Launching the Node

Once compilation is complete, you can use rosrun to start the QR code tracking node.

  1. Ensure that the workspace environment variables are loaded, and launch the simulation model:
cd ~/catkin_ws   source devel/setup.bash   roslaunch mycobot_280 detect_marker_with_topic.launch port:=/dev/ttyUSB0 baud:=115200

  1. Use rosrun to start the camera_detect.py script:
rosrun qr_tracking camera_detect.py

You should see output indicating that the ROS node has been initialized, and it will begin publishing QR code detection results.

GitHub:

https://docs.elephantrobotics.com/docs/mycobot_280_m5_en/3-FunctionsAndApplications/6.developmentGuide/ROS/12.1-ROS1/12.1.4-rivzIntroductionAndUse/

1 Like