1 Introduction

Scientific robot competitions provide a common framework for the rigorous comparison of intelligent and autonomous systems in real world conditions [1]. Such competitions play the role of scientific experiments while being appealing to both researchers and to the general public. Currently several major grand challenges exist in robotics around the world e.g., the Mohamed Bin Zayed International Robotics Challenge (MBZIRC), DARPA Grand Challenge, CYBATHLON or EuRoC challenges, where the aim is to push the state of the art toward the solution of open problems [2]. Robot competitions such as RoboCup or the European Robotics League encourage different sub-disciplines of AI and robotics to be integrated into complete robot systems to solve complex tasks in realistic environments, benchmarking the solutions against a common problem [1, 3]. This paper describes our efforts towards the development of an autonomous mobile manipulator for the second challenge of the MBZIRC 2020 robot competition.Footnote 1

A mobile manipulator is composed of a robotic manipulator mounted on a mobile base, offering both mobility and dexterity. Many different professional and consumer service applications have been envisioned for mobile manipulators, mainly to perform manufacturing assistance in industrial environments [4, 5], to execute domestic service tasks [3, 6] and human assistance [7, 8], to transport goods inside warehouses and stores [9, 10] and to manipulate and transport objects in hazardous environments such as in search and rescue missions [11, 12] or in areas with radioactive or toxic debris [13]. There has been a growing interest in the research community in developing autonomous mobile manipulators, ranging from wheeled-mobile robots [14, 15] to humanoids [16], legged robots [17] and even aerial robots [18]. To encourage research and developments on mobile manipulators for challenging real-world problems, multiple grand robotic challenges such as DARPA [19] and MBZIRC [20] competitions have defined complex manipulation scenarios requiring robots to perform a series of challenging tasks combining perception, localization, navigation, manipulation and even multi-robot cooperation. In [21] a custom mobile manipulator for operating a valve stem was developed under the MBZIRC 2017 challenge. The same competition encouraged development of innovative airborne robot solutions to locate, pick and place small-sized objects from the ground [22, 23]. In [24] a mobile manipulation robot was developed for the DARPA grand challenge to execute several challenging manipulation tasks in a disaster environment.

Employment of robots for civil construction can lead to significant cost and time savings and to satisfy the rising demand for workforce and safety regulations. Robot fabrication is commonly referred to as stationary industrial robots that operate under fixed conditions with a limited working area [25]. However, such approaches result in development of large stationary robots with specific and pre-determined roles while constraining the work-piece size that they can act upon. The use of versatile multi-purpose mobile manipulators can allow cooperative operation directly on construction sites to build complex structures with small building components. This has led to innovative efforts to develop multi-purpose ground mobile manipulators [26,27,28] and aerial robots [29, 30] for autonomous construction of structures. Aiming to push the boundaries of research on automated construction and robot-based 3D printing of civil structures, the MBZIRC 2020 competition hosted an innovative challenge where a team of ground and aerial robots were expected to construct a structure composed of heterogeneous bricks (Figs. 1, 2).

Fig. 1
figure 1

Snapshot from the MBZIRC 2020 competition trial with the goal of constructing a wall composed of heterogeneous bricks, illustrating the bricks and the proposed mobile manipulator

This system paper describes the development of a versatile mobile manipulator for the MBZIRC 2020 competition with the purpose of operating in a semi-organized outdoor environment to locate, pick and place a set of differently sized brick-shaped objects to construct a wall of predefined pattern. It describes integration of different research results and developments into a functional complex robot system for execution of a novel real-world application beyond what has been seen before. Our contribution includes a complete software pipeline for the full brick picking and placement operation including navigation, brick detection, brick alignment, brick picking and brick placing. The integrated system and the functionalities developed for this scenario can directly benefit other purposes and applications such as logistic tasks in an automated warehouse. We point out that the versatility of the system allowed the robot to be easily adapted and employed for another challenge of the MBZIRC 2020 competition, to locate and extinguish fires inside a building, and was awarded as the winner of this challenge. Furthermore, the robot solution is currently being used in a project for autonomous inspection of solar panels under the DURABLE project.Footnote 2

The outline of this paper is as follows: Sect. 2 provides the detailed description of the second challenge of the MBZIRC 2020 competition. Section 3 presents our proposed approach to the challenge by describing the hardware and software components and the main functionalities of the developed mobile manipulator. Functionalities such as robot localization and navigation, brick detection and alignment, vision-based brick picking and placing are described in this section. Section 4 describes the evaluation of the entire system as a whole in performing an autonomous brick picking and placing operation. Finally, Sect. 5 concludes the paper by providing the conclusions and future work.

2 Challenge description

In the second challenge of the MBZIRC 2020 competition, a team of unmanned aerial vehicles (UAVs) and an unmanned ground vehicle (UGV) are expected to work together in an outdoor environment to autonomously locate, pick, transport and assemble a set of brick-shaped objects to construct pre-defined structures composed of multiple walls. Two separate walls are expected to be built by the robots, an L shaped wall that must be assembled completely by the UGV and a wall with U shaped channels to be completed by the UAVs. This paper focuses on the assignment defined for the UGV and describes our developed solution for this purpose.

Four types of bricks with equal cross-section of (0.2m x 0.2m) but different lengths and weights are available in the arena:

  • Red 0.3m (1.0kg)

  • Green 0.6m (1.0kg)

  • Blue 1.2m (1.5kg)

  • Orange 1.8m (2.0kg).

A small (\(\sim\) 0.3m length) ferromagnetic plate is attached on top center of all bricks allowing robots to grab the bricks using a magnetic gripper. This plate is made of a steel plate with 0.6mm thickness. The color of the ferromagnetic plates is white and different from the base color of the brick surfaces.

Fig. 2
figure 2

Top view diagram illustrating the shape and dimensions of the wall to be built by the UGV in the second challenge of the MBZIRC 2020 competition along with the four different brick types available for the construction

The arena size for the challenge is approximately 50m \(\times\) 60m. Initially bricks are stacked according to their colors in different piles. The robots are required to locate, approach and pick the bricks from the piles and to deliver and place them on top of a wall base to construct a multi-layer wall. Each layer of the wall is composed of a randomly generated pattern of bricks that is communicated to the robots at the beginning of a trial. The location of the wall base is unknown, and the robots need to locate it during the trial. The maximum duration of a trial is 30 minutes. More details about the rules and procedure for the challenge can be obtained from the MBZIRC 2020 website.

3 Proposed method

To address the challenge described in Sect. 2, a custom mobile manipulator was developed through refurbishing an old four-wheeled differential drive mobile base (iRobot ATRV-Jr) and integrating it with a six degrees of freedom robotic arm (Universal robotics UR5e), a magnetic gripper and a set of sensors (detailed in Sect. 3.1). The developed mobile manipulator is used alongside a team of three UAVs to work towards completing the overall task.

The proposed method for solving this challenge is described as follows. Once the input wall pattern is communicated to the team by the operator, the mission starts, and a UAV takes off to perform a quick search to find the approximate location of the brick piles and the wall base from the air. This is achieved simply by performing a sweep of the arena by the UAV and detecting the piles and the base through color thresholding, similarly to the method used by the mobile manipulator, described in Sect. 3.5. Upon identifying this information, the UAVs will then communicate a waypoint near every brick pile and the wall base. The manipulator then moves to the waypoint of the desired brick pile based on the input wall pattern to pick up the first brick. This is achieved through a GPS-based localization system and a waypoint navigation algorithm (described in Sect. 3.3) that includes obstacle detection and avoidance based on a laser scanner sensor.

Once the robot is in the vicinity of a desired pile, a laser-based brick detection and alignment method is then employed (described in Sect. 3.4) allowing the robot to move precisely towards the center of the desired brick that is to be picked. A vision based algorithm (described in Sect. 3.5) that uses a color-depth camera attached near the end-effector of the robotic manipulator is then employed to confirm the desired brick color and to estimate the brick pose (position and orientation) as well as the center point of the brick. The robotic manipulator is then moved to have the magnetic gripper approach the center point of the brick with a force feedback to identify when the brick is reached. The motion of the robot base is independent of the manipulator and only after the base is aligned with the brick, the manipulator is then employed to pick up the brick.

Once the brick is attached to the gripper it is picked up by the manipulator and the waypoint navigation algorithm is employed once again to drive the mobile robot towards the wall base where the brick is to be placed. When the robot is in the vicinity of the wall, the laser rangefinder and the vision-based detection are employed (described in Sect. 3.6) to precisely adjust the position of the mobile manipulator and the end-effector to position the brick to its desired location. The brick is then released by deactivating the magnetic gripper and the robot moves towards the next brick in the pile.

3.1 Hardware description

The developed UGV is a mobile manipulator composed of two main parts: a mobile base and a UR5e robotic arm with six degrees of freedom (as shown in Fig. 3).

Fig. 3
figure 3

The mobile manipulator developed from a refurbished ATRV-Jr mobile base and a UR5e robotic arm with a six degrees of freedom used for solving the second challenge of the MBZIRC 2020 competition

The mobile base was developed through refurbishment of an old iRobot ATRV-Jr robot with four wheels connected to 2 high torque, 24V DC servo motors. This robot was used in the past in the Portuguese national RESCUE project, [31], to foster research on multi-agent robotic systems for search and rescue operations, and later in the INFRANET project [32] to test a robotic solution for power line inspection. The ATRV-Jr mobile base has 55 cm of height, 78 cm of length, weights about 50 Kg, and is capable of transporting an additional payload of 25 Kilograms at a maximum speed of 1.4 m/sec.

The ATRV-Jr robot was fully refurbished and upgraded to be used in the challenge. Besides replacing many of the old power circuits and control boards, the UR5e control boards were accommodated inside the mobile robot along with an Intel NUC7i7BNH to act as the new on-board computer. A NovAtel OEM2-G2L GPS antenna and receiver, a Crossbow DMU-6X-003 IMU positioned at the center of the robot and an MPU-6050 IMU positioned at the top of the robot were installed for the purpose of robot localization and navigation. A Hokuyo UTM-30LX laser scanner was also installed at the front of the robot, which provides two-dimensional laser scans from 0.1 to 30m within a field of view of 180\(^{\circ }\).

The UR5e arm was assembled at the top front of the robot with all the control circuits fitted inside the mobile base. For this purpose, the base structure of the robot was reinforced to accommodate the fixation of the arm. Additional sensors and actuators such as a RealSense D435, a Terabee thermal sensor and a HEM1080 magnetic gripper were also added to the robot. The Intel RealSense D435 camera that comprises of a full-HD RGB and depth sensor is installed on the manipulator and near the end-effector allowing the environment to be actively perceived through the movement of the manipulator. The thermal camera placed at the front of the robot is only used to perform heat and fire detection for the third challenge of the MBZIRC competition and is not used in this challenge. The whole robot system can be powered either using two LifePO4 24V 20Ah batteries or using two Pb 12V 35Ah batteries providing an autonomy of more than 5 hours of continuous operation.

3.2 Software architecture and task events

The Robot Operating System (ROS) was used as a common framework for integrating different software components and interacting with the robot hardware. The UGV operates by autonomously switching between a set of predefined states that are triggered autonomously by sensor inputs and the current status of the mission. A state-machine was built for this purpose using the SMACH library [33] allowing the definition of states and state transitions and executing the mission plan. Each state uses simple actions that perform a basic operation with the aim of generating the complex global behaviour. Each independent action was implemented as a Python function that requests operations from the running rosnodes through rosservice calls and rostopic messages. The states of the robot can be divided into four main states:

  • Waypoint navigation;

  • Laser-based alignment;

  • Brick picking;

  • Brick placement.

Figure 4 describes a simplified diagram of the pick and place procedure and the order of the state transitions for the main objective of building a wall from a set of different shaped bricks stacked in piles. The algorithm and sequence of expected events when executing the complete challenge is described in Algorithm 1. Details about each state and the corresponding actions are provided in the following sections.

Fig. 4
figure 4

Simplified diagram of the pick and place approach and the corresponding robot states for the scenario of building a wall from a pile of bricks

3.3 Robot localization and waypoint navigation

A main requirement for a robot competing in the challenge is to be able to navigate reliably in the environment. For example, to reach a waypoint in the proximity of a brick pile communicated by the UAVs or to navigate to a predefined waypoint provided by the user. To obtain an accurate robot navigation functionality, two main system components were implemented:

  • A robot localization system which estimates the position and orientation of the mobile base with respect to the arena frame.

  • A waypoint path planner, which is in charge of computing feasible paths for the robot to reach specific points in the environment.

figure a

Algorithm 1: Challenge 2 routine

The localization system is described in Fig. 5. Due to the outdoor and open-field nature of the problem, the localization system is developed to use the Odometry information from the wheel encoders along with the GPS and IMU measurements to estimate the pose of the robot. This is achieved using an Extended Kalman Filter (EKF) [34] that fuses the three sources of information together and outputs a reliable estimate of the robot’s pose. Note that the laser scanner is not employed for robot localization due to availability of GPS signals and since laser measurements only correspond to dynamic structures, i.e. the bricks. However, the laser scans are used for robot navigation and obstacle avoidance as described later in this section. The use of advanced algorithms for highly dynamic environments [35, 36] could potentially be used to also integrate the laser scans in the localization system and further enhance the reliability of the localization system

Fig. 5
figure 5

Diagram illustrating the EKF-based sensor fusion technique. The filter is composed of two nodes. The EKF node uses Odometry and IMU type ROS messages and fuses them together in a customized way (for example, based on the weight defined for each measurement). The NAV-SAT-TRANSF node transforms the GPS data message into an Odometry type message that is consistent with the robot’s world frame

The measurements are used as standard ROS messages with associated covariances, enabling the filter to weight the information from the sensors according to its expected accuracy and to obtain a more precise pose estimation. The localization system allows the robot to estimate its pose at every time instance with respect to a fixed reference frame and to compute its relative pose to other fixed frames in the arena (for example the starting pose, the wall and the piles of bricks). Figure 6 shows the localization results from an experiment performed in the Instituto Superior Técnico Lisbon campus, where the robot was driven on a path of several hundred meters consisting of a set of black lines used as the ground truth.

Fig. 6
figure 6

Results from an outdoor localization experiment. Left: Google Maps view with raw GPS coordinates. Right: EKF-based localization estimates using the Odometry + IMU + GPS information (red line) along with the covariance of the estimates (pink)

For the waypoint navigation, a global planner and a local planner are defined that work together to calculate the best path from the robot’s current location to the desired waypoint in the arena. The ROS navigation stack [37] is used for this purpose which benefits from costmaps to represent obstacles and to build an occupancy grid representation of the arena. For the Global Planner, which is based on the Dijkstra’s Algorithm [38], a modified version of the ROS Navfn planner [39] is used to compute the global path. However, the planner is allowed to create plans that traverse unknown spaces in the global costmap. This is because the map of the environment is not available in advance and it is not possible to produce a map before the mission as the layout of the arena is expected to be frequently changing. The known space is considered as the area that can be perceived by the laser scanner.

Fig. 7
figure 7

Left: An example of the path planning solution in Gazebo simulation; Right: The correspondent costmap containing both the known (darker) and the unknown spaces (lighter) of the environment and the occupation probability of the cells are used by the planner to compute the path of the robot

Obstacles are represented in the costmap as occupied cells. In their vicinity, the cells are assigned with a value representing the probability of that cell also being occupied (as shown in Fig. 7). This probability decreases exponentially with the distance to the obstacle allowing the planner to compute a smooth path while avoiding collisions between the occupied cells and the cells inside the robot’s footprint. i.e. a cost of zero is assigned to free spaces, a cost of one is assigned to occupied cells and cells leading to collision, and a user specified exponential decay function is used to connect the free space and occupied cells

A Dynamic Window Approach (DWA) Local Planner [40] is used along with a local costmap of 10m \(\times\) 10m to compute circular arc motions (expressed by their linear and angular velocity combinations) towards the local goal pose, taking into consideration the kinematic characteristics of the robot and the obstacles in the scene. By scoring each of the options, the best motion for the robot at each step is then selected. This is regularly repeated throughout the global path provided by the Global Planner until the final goal is reached.

When a path is computed, only the visible obstacles are taken into account. However, in case a new obstacle is suddenly detected by the laser scanner, the costmap is instantly updated and the planner react accordingly. Figure 8 shows two instances from the actual competition trials where an unexpected obstacle and a falling brick was identified and safely avoided by the robot.

Fig. 8
figure 8

Snapshot from the actual MBZIRC 2020 competition trials illustrating the real-time path planning and the robust navigation even in the presence of unexpected obstacles

3.4 Laser-based alignment

The robot localization and navigation algorithm described before allows the robot to move autonomously and safely in the arena and to reach regions of interest such as the wall or the pile of bricks. However, for approaching objects to interact with them, a more precise navigation method is required. To address this situation, a relative localization and navigation system based only on the measurements of the laser scanner is employed to position the robot precisely close to the pile of bricks or the wall, hence allowing the robotic arm to reach, grasp and manipulate bricks.

Figure 9 illustrate the flowchart of the laser-based alignment method. This algorithm starts by segmenting the lines in the vicinity using the 2D point cloud obtained from the laser scanner. The method presented in [41] was employed to extract a list of all lines visible in the point cloud. Once a line that corresponds to a desired brick (or the wall in the case of placing a brick) is detected, the relative angle and distance of the brick is computed and is used to guide the robot to reach within a given distance (30 cm in our examples) of the center of the brick. This computation is updated with a frequency of 10Hz whenever a new laser scan is available. Once the robot reaches the desired brick, it rotates to face the brick. Figure 10 illustrates an example of the brick aligning procedure where the robot approaches and positions itself within manipulation range from the brick.

Fig. 9
figure 9

Flowchart describing the laser-based brick alignment routine

Fig. 10
figure 10

Left: robot starting position; Center: robot final position (aligned with the brick surface); Right: the path calculated to perform the alignment using laser information as feedback

3.5 Brick picking

The previously described methods provide a reliable solution to navigate in the environment and to move the mobile base within manipulation range from the bricks. For picking and placing the bricks a vision-based algorithm was developed that allows the robot to precisely locate the top surface of the bricks and to guide the robotic manipulator to pick the brick from the center. Furthermore, the vision-based brick detection allows the robot to also become aware of bricks on top of other bricks that are undetected by the laser scanner, for example the bricks in the brick pile or in the wall.

Figure 11 describes the brick detection and picking routine. A RealSense D345 depth camera is attached near the end-effector of the robotic manipulator that is used for the vision-based object detection and grasping. Once the mobile base is in place and ready to pick a brick, the arm is initially extended out to a predefined position and orientation to have the camera above the brick and parallel to the ground (as shown by the camera image illustrated in Fig. 12). The top-view image of the camera is then filtered using a depth segmentation to remove the ground planes or points below the surface of the brick. Afterwards, white color segmentation and rectangle fitting is performed to detect the ferromagnetic area of the brick.

Fig. 11
figure 11

Flowchart describing the brick detection and picking algorithm

Once the metallic plate of the brick is identified, the center and the tilt angle of the fitted rectangle is then computed. In addition, the average depth of a set of pixels around the center point of the rectangle is used to compute the relative distance between the camera and brick. This information is used along with the camera intrinsic parameters to obtain the 3D coordinates of the center point and the orientation of the brick with respect to the robot. This information is forwarded to the manipulation planner that computes the inverse kinematic solution as well as the trajectory to have the gripper positioned about 5cm above the brick’s center point. The gripper is then gradually lowered until it grasps the brick which is detected using the force feedback sensors of the manipulator. The motion planner previously reported in [42] is used for computing an efficient inverse kinematics solution and to plan a collision free trajectory for the arm.

Fig. 12
figure 12

Illustration of the vision based algorithm used for picking a brick. Left: A top-view image of the brick is used to perform white-color segmentation and to fit a rectangle to the brick’s metallic surface. Right: The center pose with axis aligned to the brick is computed and communicated to the manipulator planner

3.6 Brick placement

The brick placement algorithm follows a similar principle as the brick picking solution. However, the algorithm also takes into account a priori information on the current wall status and selects a brick on the wall as the reference brick to place the new brick with respect to this reference, i.e. to place it on the right, left or above the reference brick depending on the input wall pattern.

The flowchart in Fig. 13 describes the brick placement algorithm. After picking a brick the robot initially navigates to the wall location, using the waypoint navigation method described in Sect. 3.3, and then approaches the desired region of the wall containing the reference brick and positions itself using the method described in Sect. 3.4. Once in position, the robot extends the arm out to have the camera above the reference brick similar to the picking algorithm described in Sect. 3.4. Note that the position and viewing angle of the camera is selected in such a way that the picked brick does not interrupt the camera’s field of view.

Once a top-view image is acquired, the reference brick is then identified in the image using color segmentation and furthermore a rectangle is fitted to the top surface of the brick, as shown in Fig. 14. The rectangle parameters are then used to compute the edge coordinates of the reference brick, allowing the picked brick to be placed relative to this reference edge. For this purpose, a set of points near the edge of this brick is selected and averaged to compute a reliable depth measurement for the edge. This is to avoid the noisy depth measurements that often appear near the edges of objects. The edge coordinate in the camera frame is then transformed to the robot’s frame and is used to compute the placement coordinate for the picked brick. Finally, the manipulator moves the brick above the desired location and gradually lowers the arm until the force feedback from the manipulator indicates that the brick is in place. Figure 14 illustrates an experiment where the target position is computed based on the top-view image and the pose provided to the manipulator planner.

Fig. 13
figure 13

Flowchart describing the brick placement algorithm

Fig. 14
figure 14

Illustration of the vision based algorithm used for placing a picked brick. Left: Color segmentation with rectangle fitting and then averaging samples at the edge is used to compute a reliable position for the edge of the reference brick. Right: A placement pose is computed relative to the reference edge that is communicated to the manipulator planner

4 System evaluation

Extensive experiments performed in both simulation and on the real robot demonstrated the success of the overall system and the employed algorithms in executing the challenge. Although it is not trivial or even possible to provide a fair comparison with other existing approaches, either because they do not exist or result from a different composition of subsystems based on different subsystems approaches, the results of our experiments have shown the functionality of the integrated system as a whole and the capability of successfully completing the task.

A Gazebo world was initially developed to simulate the robot and the scenario ( Fig. 15). Models of the four types of bricks were added to the world along with a L-shaped frame where the wall should be built on. Since Gazebo uses a physics engine it provides realistic rendering of the robot and the environment including gravity, inertial properties, collisions, lights, shadows and textures with a good approximation. Although simulations cannot completely capture all the details of the real world, it played out to be very important in developing and testing our algorithms, especially regarding the design and testing of the state machines and execution of the mission routines. Figure 16 shows an example run from the simulator where the robot builds a 2 layer wall composed of 6 bricks. The time to complete this scenario was measured over 5 runs and averaged 9 minutes and 12 seconds.

Fig. 15
figure 15

Challenge 2 simulated Gazebo world with realistic measurements. The image represents an arena of 15x12m

Fig. 16
figure 16

Snapshots from a simulation where the mobile manipulator is building a 2 layer wall consisting of 6 bricks

For the real experiments, multiple bricks with identical dimensions and weight as to the ones used in the actual challenge were developed. The robot was then instructed to autonomously complete a full pick and place cycle without any human interruption. This cycle included: navigation to an area containing a brick, detection of the brick to be picked, alignment with the brick, grasping and delivering the brick to the wall location and placing the brick with respect to a reference brick on the wall . Figure 17 illustrate a trial where the robot continuously performs the full pick and place operation. Experiments have shown the success of the system in reliably navigating to desired waypoints with an accuracy of \(<1\) meter, aligning to the center of a target brick with an average error of \(\approx 15 cm\) and picking bricks from their center with a distant error of \(\approx 5cm\). Once the robot is in position, the time required for detection and localization of the brick, after an image is acquired, is about 6 milliseconds, and the time to pick or place a brick with the manipulator was configured to last around 20 seconds.

Finally, the robot was transferred to Abu Dhabi and evaluated during the actual MBZIRC competition and its challenging arena. Several problems were encountered all due to the introduction of a new, unfamiliar and challenging environment, such as the uneven terrain with large wooden ramp in the center of the arena, poor GPS signal reception and highly varying light conditions. However, these problems were all eventually eliminated only by tuning the algorithm parameters to successfully perform the full pick and place cycle autonomously. For example, to eliminate the problem of poor GPS reception at the arena which resulted in localization failures, the EKF parameters were tuned to heavily rely on the odometer and laser readings. For the problem of the uneven terrain and the curved wooden ramp which resulted in detection of imaginary obstacles, the costmap parameters and the lidar thresholds were tuned to eliminate the appearance of such false obstacles in the costmap.

Highlights from some of the experiments and the competition runs are compiled in a video.Footnote 3

Fig. 17
figure 17

Snapshots from an outdoor experiment where the full pick and place cycle is performed autonomously. a The robot searching for a brick with laser scanning. b Robot detects the brick and aligns itself to the brick. c The brick is visually detected and grasped by the manipulator from the center. d The robot carries the brick to the wall location. e Robot aligns itself with the wall using feedback from the laser scanner and uses the camera at the manipulator to localize the red reference brick on the wall. f The robot places the brick on the third layer while using the edge of the reference brick to calculate the placement position

5 Conclusions and future work

This paper describes the hardware and software architecture of an autonomous mobile manipulator, developed for the second challenge of the MBZIRC 2020 competition, with the aim of manipulating a set of differently shaped bricks to build a wall of predefined pattern. A set of tools and methods for autonomous brick picking and placement are presented, using a mobile manipulator while relying on vision-based measurements and 2D laser scanning. A complete software pipeline for the full brick picking and placement operation was presented including navigation, brick detection, brick alignment, brick picking and brick placing. Solutions were successfully integrated and tested using a mobile manipulator, both in simulation and in reality, and at different test sites, demonstrating the success of the integrated system, the employed algorithms and the software pipeline for the intended brick pick and placing application. The presented work highlights the importance of major scientific competitions in contributing to the development of real-world robotic solutions.