11email: h_moaiyeri@sbu.ac.ir
11email: {e.amouzadkhalili, k.ghasemzadeh, ho.gohari, mohammadr.jafari, mat.jamshidi, m.khaxar, a.akramifard, m.hatamzadeh, sab.sadeghi}@mail.sbu.ac.ir
https://sbu-team.github.io/
Technical Report of Mobile Manipulator Robot for Industrial Environments
Abstract
This paper describes Auriga’s @Work team and their robot, developed at Shahid Beheshti University Department of Electrical Engineering’s Robotics and Intelligent Automation Lab for RoboCup 2024 competitions. The robot is designed for industrial tasks, optimizing efficiency in repetitive or hazardous environments. It features a 4-wheel Mecanum system for omnidirectional movement and a 5-degree-of-freedom manipulator arm with a 3D-printed gripper for object handling and navigation. The electronics include custom boards with ESP32 microcontrollers and an Nvidia Jetson Nano for real-time control. Key software components include Hector SLAM for mapping, A* path planning, and YOLO for object detection, supported by integrated sensors for enhanced navigation and collision avoidance.
Keywords:
Robocup@Work Robotics Robots Grasping Computer Vision1 Introduction
Nowadays in many industries, robots are a suitable option for optimizing tasks and increasing efficiency. @Work robots can meticulously do tasks deemed repetitive, exhausting, impossible or dangerous for humans. On the other hand, robots can help people in the work environment, A combination of workers and robots can multiply efficiency. @Work robots are useful in a wide variety of industries. Contributing to a faster production line, assisting humans, limited environment transportation, doing tasks considered difficult for humans and many other desired tasks we can define for the robot are but a few of @Work robots’ applications.
2 Hardware Description
2.1 Mechanical Design
2.1.1 Body
This part includes 4 Mecanum wheels and each wheel has a separate motor. Previously mentioned motors are DC motors, each one connected to the corresponding wheel by a solar gearbox. Because of using Mecanum wheels and separate motors each one of the wheels can move left, right, forward or backward independently so it increases maneuverability. Robot’s chassis is built using Aluminum profiles.
2.1.2 Arm
Robot’s arm has four sections
-
1.
Rotary section
The rotary section consists of a set of ball bearings and surfaces that the arm is mounted on and turning this surface by a DC motor with gearboxes makes the arm rotate around the Z axis. -
2.
Elevator section
The elevator section consists of a set of 2 by 2 profiles, ball bearings, strap, pulley and etc. which moves the gripper back and forth by two DC Motors with gearboxes. (linear movement in X axis) -
3.
Telescopic section
The telescopic section of the assembly consists of a set of guide shafts, linear bearings, belts, pulleys, etc. These components enable the gripper to move forward and backward in the direction of the X-axis using two DC geared motors, providing linear motion. -
4.
Gripper
The mechanical structure of the gripper, depicted in Fig. 2, was entirely designed in Solid-Works and printed by a 3D printer to be able to grab different objects with different orientations. The gripper contains four Servo motors, two of which are used to grab objects and the other two are sued to change location and orientation of the head of the gripper.
The body structre of robot is as shown as Fig. 1.All mechanical sections are designed, built and assembled entirely by the mechanics team and no pre-built parts have been used.
2.2 Electrical Design
Auriga’s @Work consists of two electronic boards, one board used in the top section of the robot to control the movement of robot’s arm and one board in the bottom section of the robot to control general movement of the robot which are connected by UART protocol. These boards are powered by a four cell 16000 mAH lithium polymer battery. Voltage regulators have been used in order to supply the required voltage of different circuits.
-
1.
Arm’s board
In this board two XL4016 switching regulators supply servo motors, encoders and one AMS1117 supplies 3.3V for ESP32 microcontroller and ICs. This board contains one ESP32 microcontroller, two triple 2:1 MUX/DeMUX ICs and two L298N drivers to control the movement of DC motors in the arm section of the robot. Also, The arm section contains four servo motors which are controlled by this board. -
2.
Board located in the body
In this board two XL4016 switching regulators supply encoders and Nvidia Jetson Nano board(5V) and one linear regulator AMS1117 supply 3.3V for two microcontrollers, ICs, range measurement sensors and gyroscopes. Gyroscopes and range measurement sensors send data to the desired microcontroller by I2C protocol. Also, microcontrollers and Jetson Nano’s connection and data exchange is done by Serial connection using UART protocol. Similar to the top section board, designed circuit for controlling DC motors contains L298N driver and a 2:1 MUX/DeMUX IC. Since we have 5 motors in this section, we have used three drivers. It is possible to turn off the motors and turn them back on by switching the emergency switch key available in both boards. Designed board for this case contains one or multiple MUX ICs and relays. All parts of designing the robot’s boards, designing PCBs using Altium Designer Application and assembling the parts have been done by the Electronics team.
2.3 Sensors
-
1.
Intel RealSense D435i Depth Camera
This sensor is a camera with the ability to detect depth and send RGB-D data to the main processor of the robot[1]. -
2.
RpLidar A1
This time-of-flight range measurement sensor uses lasers to scan 360 degrees around itself and detect obstacles around the robot. This sensor is located in front of the robot and is used in implementing mapping and navigation algorithms. -
3.
Rotary encoder
We have used E38S6G5-100B-G24N rotary encoder. This sensor calculates movement of the desired section of the arm or linear velocity of wheels using the amount of motor’s shafts’ rotation. This sensor has been used both in movement section of the body and in the arm. These sensors have been used to estimate arm position, wheel velocity and generally for estimating states of different sections. -
4.
Range Sensor
These sensors are used in order to understand distance of obstacles with respect to the robot for LiDAR’s blind spots. Said sensor is a time-of-flight range sensor VL53L1X which prevents collision when moving left, right or back. The reason for using this sensor is its high speed and accuracy characteristics. -
5.
Gyroscope
To perform angle measurements of the robot, CMPS14 and MPU6050 sensors have been used. After combining incoming data of the two sensors, one final result will be used as the estimated angle. This sensor is also used for increasing the accuracy of robot’s localization.
3 Algorithm and software full description
3.1 Localization and Mapping
@Work robot needs an accurate map of the environment for searching the environment. In this regard, the robot obtains its estimated location with respect to a global coordinate system by combining system’s motion model equations[2], encoders and gyroscopes’ data. On the other hand, the robot obtains obstacles’ location in the surrounding environment in its local coordinate system by constantly knowing the location of itself and receiving LiDAR and auxiliary range measurement sensors’ data then locates obstacles present in the environment in the global coordinates using a transform function. Finally, constructed map of the environment is saved in the processor’s memory as a two-dimensional array and will be used in the navigation algorithm.
We utilize the Hector SLAM algorithm for mapping and navigation within the workspace. In Figure 7, you can see an example output of the Hector SLAM mapping [4]. The purple color represents the navigated path, the blue area represents the walls, the white area represents the free space, and the gray area represents the unmapped space.
3.2 Decision making and navigation
In this robot, we divide the decision-making process for doing the desired tasks into two parts:
-
1.
Mission Planning In the mission planning phase, the robot optimizes time and resources by selecting actions based on the current and desired state of the service area. As shown in the flowchart in Figure 8, the robot first assesses if the area is in the desired state. If not, it determines whether to fetch a new item or deliver a previously fetched one, based on a cost evaluation of both options. The goal is to minimize resource use, ensuring efficient task execution. Once a decision is made, the result is passed to the path planning phase, where the robot navigates to perform the chosen task.
Figure 8: Flowchart of mission planning algorithms. -
2.
Path Planning
Path planning is designed to make the robot move from the current location to the desired destination which is specified as the result of mission planning algorithm, in path planning we have used A* [5] [6] algorithm to find the shortest route for the robot to go without colliding with the obstacles based on the map we have of the environment. The implementation of this algorithm utilizes a MinHeap data structure, which significantly affects the algorithm’s execution time. It is important to note that the greater the distance from the start to the destination, the more pronounced this time difference becomes. This is because the order of searching among the open nodes changes from to . The cost function in the implementation of the A* algorithm is defined as the sum of G-cost, H-cost, and Safety-cost. The reason for adding the last term to the cost function is to increase the cost of cells that are closer to the walls if the robot needs to pass between two walls, This encourages the robot to move through the middle of the path, reducing the likelihood of colliding with the walls. It is also important to note that the Euclidean distance from the target cell to the destination cell is chosen as the criterion for H-cost.After the path robot has to go is decided, that path is given to the control system as a reference, and the robot uses PID controller [7] to remain in its path until reaching the destination. While moving towards the destination, LiDAR and range measurement sensors’ data is also checked in real-time and if there’s a possibility of collision in the path the robot stops (because of possible error in calculating the optimized path) and runs navigation process again. For the implementation of said algorithms C++ programming language is used and these algorithms are processed real-time on the main processor, Nvidia Jetson Nano.
3.3 Computer Vision
Our computer vision system leverages the Intel RealSense D435i camera to achieve precise and efficient environmental perception, which is crucial for tasks such as object recognition, spatial mapping, and virtual boundary detection. The section is organized into three critical components that contribute to the system’s robust performance:
-
1.
Object Segmentation:
Objects located within each workstation are identified and segmented in real-time using the YOLO (You Only Look Once) neural network, a state-of-the-art object detection algorithm known for its high speed and accuracy in detecting multiple classes of objects in a single forward pass [8] [10]. The YOLO model allows the system to recognize diverse objects, such as tools, products, or obstacles, facilitating efficient task automation and enhanced decision-making processes. Once detected, the objects are segmented from the background, enabling further processing and manipulation. Example of object detection is shown in Figure 9. -
2.
Locating Objects:
Once objects are segmented and classified by the YOLO neural network, the system utilizes the depth data provided by the Intel RealSense D435i camera to compute the precise spatial location of each object. The camera’s depth sensing capabilities allow for accurate extraction of x, y, and z coordinates, providing a 3D understanding of the environment. For angle detection we use the PCA algorithm [11]. This spatial information is essential for applications such as robotic grasping, navigation, or further object interaction, as it enables the system to determine the object’s distance, orientation, and position relative to the camera and other surrounding objects.(a) Example of Object Detection using YOLO (b) Detection of Multiple Objects in an Industrial Setting Figure 9: Examples of Object Detection and Segmentation in Various Stations -
3.
Virtual Walls Detection:
Virtual walls or barriers are detected through the analysis of point clouds generated by the depth camera. The point cloud data, consisting of a dense collection of 3D points, is used to model the surrounding environment, enabling the system to identify and locate virtual walls or restricted zones. These virtual walls can be critical for defining boundaries for robotic movement or ensuring safety by preventing collision with off-limits areas. Example of virtual walls is mentioned in Figure 10.Figure 10: Virtual walls annotations.
3.4 Pick and Place Objects
The manipulator is a 5-degree-of-freedom arm, with each motor in a closed-loop system using sensors to ensure accurate real-time state estimation. A finite-state machine has been used for grasping objects. To pick up an object, the arm first uses feedback from the camera data to align its y-axis position with the target object. Then, it adjusts the telescopic part of the arm along the x-axis to align with the object. Finally, it matches its angle and height with the object and closes the gripper to grab it. The equations for the position of the arm’s end-effector based on the status of each motor is mentioned in Figure 11.
3.5 Robot Operating System
This section is divided into two important parts. First part is receiving instructions from AC [3] and sending these instructions to the relevant sections in the robot and in the second part AI and computer vision, receiving data from the camera and LiDAR, mapping, navigation and control algorithms are placed next to in each other in the ROS platform. At times when a process is useless, that process is shut down to use the resources in the best way and in an optimal way[12].
3.6 Embedded System Design
In order to control, drive body and arm’s motors, receive data from encoders, gyroscopes, range measurement sensors and communication between processors an embedded system has been implemented which contains three ESP32 microcontrollers, sensors and appropriate drivers. Required processes are done in Nvidia Jetson Nano board and the final command is sent to the microcontroller that must execute that command and the destination microcontroller sets the speed and location of the motor internally. We are using incremental PID controller [13] to precisely adjust mecanum wheels speed based on encoders feedback and standard PID controller to control the position, ensuring smooth and accurate movement across all components. Connection between ESP32s is built by an SPI protocol with a common Bus and Jetson Nano and main ESP32’s connection is through UART protocol. Hardware system’s general schematic is shown in Figure 12.
Attrbiute | Value |
---|---|
System Weight | 25Kg |
Overall Length | 60cm |
Overall Width | 42cm |
Overall Height | 94cm |
Max Velocity | 20cm/s |
Payload | 0.5kg |
Structure Material | Aluminum cast |
Communication | SPI-UART-I2C-Ethernet |
Voltage connection | 16.8 Vdc |
Arm Link Speed | 45 Degree/s |
References
- [1] Keselman, L., Woodfill, J., Grunnet-Jepsen, A. & Bhowmik, A. Intel RealSense Stereoscopic Depth Cameras. (2017)
- [2] Hamid Taheri & Ghaeminezhad, N. Kinematic Model of a Four Mecanum Wheeled Mobile Robot. International Journal Of Computer Applications. Volume 113, 6-9 (2015)
- [3] Kraetzschmar, G., Hochgeschwender, N., Nowak, W., Hegger, F., Schneider, S., Dwiputra, R., Berghofer, J. & Bischoff, R. RoboCup@Work: Competing for the Factory of the Future. RoboCup 2014: Robot World Cup XVIII. 8992 pp. 171-182 (2015)
- [4] Kohlbrecher, S., Meyer, J., Stryk, O. & Klingauf, U. A Flexible and Scalable SLAM System with Full 3D Motion Estimation. Proc. IEEE International Symposium On Safety, Security And Rescue Robotics (SSRR). (2011,11)
- [5] Hart, P., Nilsson, N. & Raphael, B. A Formal Basis for the Heuristic Determination of Minimum Cost Paths. IEEE Transactions On Systems Science And Cybernetics. 4, 100-107 (1968), https://doi.org/10.1109/tssc.1968.300136
- [6] Goyal, J. & Nagla, K. A new approach of path planning for mobile robots. 2014 International Conference On Advances In Computing, Communications And Informatics (ICACCI). pp. 863-867 (2014)
- [7] Ang, K., Chong, G. & Li, Y. PID control system analysis, design, and technology. IEEE Transactions On Control Systems Technology. 13, 559-576 (2005)
- [8] Jocher, G., Chaurasia, A. & Qiu, J. Ultralytics YOLO. (2023,1), https://github.com/ultralytics/ultralytics
- [9] Redmon, J., Divvala, S., Girshick, R. & Farhadi, A. You Only Look Once: Unified, Real-Time Object Detection. 2016 IEEE Conference On Computer Vision And Pattern Recognition (CVPR). pp. 779-788 (2016)
- [10] Redmon, J., Divvala, S., Girshick, R. & Farhadi, A. You Only Look Once: Unified, Real-Time Object Detection. 2016 IEEE Conference On Computer Vision And Pattern Recognition (CVPR). pp. 779-788 (2016)
- [11] Karl Pearson F.R.S. LIII. On lines and planes of closest fit to systems of points in space. The London, Edinburgh, And Dublin Philosophical Magazine And Journal Of Science. 2, 559-572 (1901)
- [12] Stanford Artificial Intelligence Laboratory et al. Robotic Operating System. (2018,5,23), https://www.ros.org
- [13] Li, Z. Review of PID control design and tuning methods. Journal Of Physics: Conference Series. 2649, 012009 (2023,11), https://dx.doi.org/10.1088/1742-6596/2649/1/012009