You are here

Progress

This page is meant to be a "book history" of Sherpa by presenting sketchy information about technical progress achieved during the project.

**** May 2015 - November 2015 ****

 

SHERPA System Benchmark Scenario

A winter and a summer benchmark validation scenarios were defined by ETHZ for the final demonstrations of the capabilities of the SHERPA system. The summer scenario (Figure 1) considers a typical rescue mission aiming to find missing people in an alpine search area including both open fields and wilds. When the alarm is raised, the rescue coordination center deploys a rescue team to the site. Once on the mission site, the delegation framework initially support the team in defining the search area, setting the priorities, and assigning the tasks to the SHERPA agents. The initial mission plan can then be updated during the mission according to the mission evolution, the collected data about the mission area and the agents conditions. A preliminary scan of the search area is performed by the SHERPA hawks, including both RMAX helicopters and FW-UAVs. These agents patrol the area and update the dynamic cognitive map of the search area with information useful to support the rescuer and the delegation framework in planning the next phases of the mission. The following detailed search area uses the different platforms of the SHERPA system to perform the involved tasks according to their operating conditions. More precisely, the hawks patrol the search area, map the environment, act as a communication relay and deploy wasps to remote or inaccessible areas. The SHERPA wasps execute a low altitude initial search strategy based on visual clues in order to extend the human rescuers’ perception by streaming video or images taken with their on-board cameras. The SHERPA donkey follows the team leader transporting the SHERPA box, which is the main processing center and communication hub. Some other wasps stored on the donkey can autonomously take off and land from the rover based on delegation framework commands with the aid of the robotic arm. Furthermore, during this phase the wasps can autonomously execute verbal and/or gestural commands issued by the rescuer. The mission ends when the victim is found. If he/she is out of reach from a human rescuer, a wasp reach him/her and interact verbally in order to guide him/her to a safe location. If neither humans nor wasps are nearby, then an RMAX helicopter can deploy a wasp or deliver a first-aid kit before the human rescuers arrive.

 Image

Figure 1- Sketch of the search area in the SHERPA summer mission

 typical winter scenario is the case of an avalanche search-and-rescue mission aiming to find one or more victims buried under an avalanche. Such a mission can be triggered in the SHERPA scenario by an avalanche alert is sent from one of the victims, a member of the general population, the SHERPA Ground Control Station (GCS) via a dedicated application and/or a patrolling FW-UAV hawk. The alert information are then uploaded on the cognitive map and the delegation framework starts the mission. As soon as the alert is received, the SHERPA agents are deployed to the avalanche area. In particular, the fixed-wing hawk flies above the avalanche zone and upload the collected information about the search area on the cognitive map. An helicopter brings the ARTVA receiver for detecting the victims, the SHERPA box and the human rescuers to the avalanche zone. The RMAX reaches the avalanche after the helicopter and starts scanning the terrain through LIDAR and collecting data to be stored on the dynamic cognitive map. The information provided by the cognitive map are used to trigger and support the delegation framework mission replanning when necessary. In the next search phase, the rescuer sends both human rescuers and SHERPA platforms to different search areas. The commands to wasps are sent by means of verbal and gestural commands. Wasps are manually deployed in this phase by the rescuer from his SHERPA box or by the RMAX. A first search, according to the strategy proposed by CAI, is executed by wasps based on visual clues. Then both human rescuers and hawks, including both the FW-UAV and the RMAX, join the operation by searching visual clues according to the preliminary results provided by wasps. The second phase of research consists in identifying the ARTVA transmitter location. This search is executed mainly by the wasps. These are employed in a coordinated search according to the aerial leashing strategy or act in a completely autonomous way. The RMAX and the FW-UAV acts in this phase also as communication relays between SHERPA agents. Once that the ARTVA is localised, the human rescuers start digging and providing first aid to the people involved in the avalanche.

 

Image

Figure 2- Overview of the agents potentially involved in the SHERPA winter  mission

 

SHERPA Robots Reasoning Engine
SHERPA robots implement their decision making and reasoning capabilities through the Cognitive Robot Abstract Machine (CRAM) framework developed by UNIHB. This framework provides programming constructs along with reasoning mechanisms that can infer control decisions.
More precisely, CRAM is a software toolbox that provides a set of libraries in order to implement complex actions (e.g. picking up objects in the environment or searching for injured persons hidden by snow or branches) that requires a tight integration of action execution, reasoning, decision making, execution monitoring and failure handling. Its core libraries include a domain specific programming language, the CRAM plan language, a full-featured Prolog-like reasoning engine, and support for so called designators, symbolic descriptions of plan parametrizations such as objects, locations and actions. The CRAM plan language supports robot control in unstructured outdoor terrains, working with heterogeneous teams of robots, resource-constrained task achievement and coordination with the SHERPA human rescue team leader commands.
The architecture of the CRAM system used in SHERPA is sketched in Figure 3. It contains mechanisms for lightweight reasoning and action execution. It allows the robot to infer control decisions rather than requiring the decisions to be preprogrammed.

Image

Figure 3- The CRAM system architecture

The CRAM reasoning engine uses OpenGL and the Bullet physics engine for performing visibility and reachability reasoning in outdoor settings. Furthermore, it is able to intepret vague instructions based on gesture and speech commands.
The CRAM Semantic Robot Description Language (SRDL) includes in its semantic descriptions the information about current status of a component that can be asserted by the robot's own perception or external sources. Therefore the SRDL is able to manage state changes for robot components. This allows the CRAM reasoning mechanisms to reason about dynamically changing components. This capability is useful to the system for managing components that are exchangeable, like the Sherpa-box, or fixed components that change their status over time, like the capacity of the battery of a SHERPA robot.
The knowledge about the status of components has a direct effect on the estimation of the capabilities and actions that can be executed by the robot. This does not only allow the robot to reason about its own status. It also allows other robots to reason about involving other SHERPA agents as collaborators in executing specific actions which require more robots (e.g. recharging a wasp) or in when they can assist in tasks that benefits from parallel execution (e.g. searching in a big area).
Furthermore, in unknown terrains robots can use information from external information sources like Geographic Information Systems (GIS) to assist initial motion plans and command interpretation. In particular, the donkey can use the information about ways marked in these sources for an initial motion-plan and the wasp can use the height data from the digital elevation models of the search area for the same purpose. This is allowed in the CRAM by an infrastructure allowing the migration of these data from such sources into the reasoning system.

 

Dynamical Cognitive Map
Significant work was also done by KUL on the development of the Dynamic Cognitive Map (DCM), the structure of which is sketched in Figure 4. The DCM is a virtual repository where all the information regarding the mission area available at the mission start is available and also the information collected by the SHERPA agents during the mission is aggregated. The DCM architecture includes the following information, despite the following list can be extended in a quite flexible way:

  • geographical terrain map as known before the mission, e.g. given as ESRI ASCII grid files;
  • OpenStreetMap data, such as mountain footpaths and streets;
  • trajectories (to be) executed by SHERPA agents;
  • metadata of available sensors information captured by the SHERPA animals (that can be used to retrieve raw sensor data);
  • metadata of geotagged optical and thermal camera photos acquired by SHERPA animals;
  • semantic data that are also compatible with the KnowRob system (like missing persons/victims, human made structures like houses and power lines, natural elements like forest, rocky or snowy areas).

Image

Figure 4- A sketch of the DCM structure

The SHERPA agents can add data to their local DCM that then synchronizes these changes with the DCMs running on other agents. They can also query the DCM for information about their operating zone, other destinations, and other agents to support reasoning and autonomous mission planning. Furthermore, the Human Machine Interface queries its DCM for information requested by the human operator.

 

SHERPA Donkey
The hardware integration of the rover of the SHERPA donkey (Figure 5) have been accomplished by BLUE. UNIBO is currently finalising the software in the ROS environment allowing the movements of the rover based on the delegation framework and human rescuer commands. In particular, the following software functionalities were developed.

Image

Figure 5- A picture of the SHERPA donkey rover with the robotic arm installed on it

The SLAM of the rover was enhanced from the initial solution developed by BLUE. In particularm the laser scanner installed on the rover is now able to roll in order to create a 3D points cloud of the environment. This points cloud is used to contribute to the perception of rover of its environment. This functionality is of paramount importance for significantly improving tasks such as 3D navigation and mapping, and hazard avoidance.
A ROS navigation stack based on the graphical user interface software Rviz was setup on the rover in order to visualise and integrate in the rover navigation the SLAM functionality. In particular, a localization algorithm is used to calculate the position of the rover with respect to the map and send the corresponding data to Rviz, where the position and 3D pose of the rover are visualized. Based on the map and position of the Rover in the map, the user can send on the Rviz application or from a ROS node the waypoint commands to be reached by the rover.
From the point of view of the navigation, a ROS node was produced to read the GPS current position and receive new waypoints expressed in terms of target latitude and longitude. These are read from a ROS topic on which the delegation framework publishes the waypoints. These waypoints are used to derive a target trajectory in the local cartesian reference frame starting from the current position expressed in terms of latitude and longitude. This trajectory is then executed by the routine described in the previous paragraph taking advantage of its autonomous obstacle avoidance capability.
The donkey robotic arm was completely assembled from UT, except for the gripping system that is still under design. The overall weight of the arm is 15 kg and it is able to carry a payload of 3 kg. Its maximum extension is 1.5 m. It is charecterised by 7 DoF implemented by 3 DoFs for the shoulder, 1 DoF for the elbow and 3 DoFs for the wrist. The actuators are standard brushless and brushed DC motors. The motor drives and microcontrollers are the Elmo drives ExtrIQ and Hornet. The CPU is based on an Arm processor with Linux operating system. The sensors set includes hall-effect sensors for brushless motors, absolute encoders for motor axes, force sensors and vision system for high-level control. The communication is based on CAN-bus for internal communication and ethernet and WiFi for external communication. The implementation of the software for the robotic arm control is in progress. It communicates with the rest of the Sherpa robots through the ROS-MicroBLX bridge, developed by KUL, with the TST framework and the world model, developed by LKU.

SHERPA Wasp
The high-level controller implemented in ROS environment for the SHERPA wasps was further refined by UNIBO and successfully tested in different flight tests in the alpine environment. These tests (Figure 6) demonstrated the excellent performances in terms of autonomous navigation and correct operations of the ARTVA sensor acquisition of the wasps.

Image

Figure 6- A picture of the SHERPA wasp during a flight test on the Alps

It was also possible to validate the integration of the multimodal HMI (voice, gesture and tablet) developed by CREATE in the SHERPA wasps control. The flying platforms demonstrated in fact the ability to autonomously execute high-level flight commands including take-off, landing and waypoints navigation. Furthermore, it was also possible for the wasps to autonomously define and execute a monitoring path over a search area and stream the captured videos based on voice and gesture commands provided by the busy genius. Also the coordinated flight operations capabilities of a swarm of two wasps were successfully tested with multimodals commands.
In the last months, the SHERPA high level architecture was then integrated with Delegation Framework in order to have a full compliance with the SHERPA system communication network.  In particular, a list of executors were implemented to interact with the wasp autopilot. The list of executors were defined and implemented during a joint work between UNIBO and LKU. The delegation and the execution of TSTs were successfully tested via simulations and by mean of real flight experiments during the second integration week. 

 

SHERPA Fixed Wing Hawk
ETHZ developed an algorithm capable of detecting and localizing potential human victims using a combination of visual and infrared cameras onboard the fixed-wing Hawks. The algorithm was demonstrated during the final field demonstrations of the ICARUS FP7 Project in Marche-en-Famenne, Belgium in September, providing rescuers with potential GPS locations of missing people in real time. A significant stride in flight endurance goals was made in July when AtlantikSolar UAV set a new world record for aircraft below 50 kg, flying for 81.5 hours straight on solar power alone. Auto-landing control has been successfully tested on the fixed-wing platforms using a small light-weight LiDAR sensor. Efforts continue on the integration of the senseSoar (Figure 7) solar UAV platform. Further work has been directed into visual-inertial state estimation from the fixed-wing platforms for mapping the environment, with the end goal of providing sparse point clouds in real-time.

 

Image

Figure 7- The senseSoar  fixed-wing drone developed by ETHZ

 

 

**** November 2014 - April 2015 ****

 

Requirements, regulations and potential fields

A preliminary version of the final summer and winter validation benchmark scenarios was elaborated in accordance with deliveralbles D2.1 and D2.2. ETHZ, UNIBO, LKU produced the necessary documentation for obtaining their permit-to-fly and, in particular:

  • ETHZ prepared a permit-to-fly application for their AtlantikSolar FW-UAV in operations Beyond Visual Line of Sight (BVLoS) in restricted Swiss airspace. The application was submitted to the Swiss Federal Office of Civil Aviation (FOCA).
  • UNIBO, LKU and ETHZ produced the documentation necessary for a permit-to-fly application for operations within Visual Line of Sight (VloS) for their respective aerial platforms in Italian airspace. UNIBO's application has already been approved by the Ente Nazionale per l'Aviazione Civile (ENAC). LKU's application has been submitted to ENAC and is currently at the first iteration stage. ETHZ's application is under internal review.

Mechanical design and construction, HRI technologies and technology integration

  • The rover desing has been completed and its construction started: the locomotion system is composed of a main body and 4 motorized tracks. Each track has its own motor, motor controller and can rotate freely around a pivot axis to best fit the ground shape. The pivot axis of each track is off-centered so that a force that is applied to the track creates a torque that makes the track rotate upwards and ease the climbing of an obstacle. The rover embeds a 3D laser, an IMU, angular sensors and a CPU that is responsible for rover autonomous navigation.

SHERPA rover

Figure 1- The SHERPA rover

  • The construction of the first arm prototipe has been started: the SHERPA arm is composed of four parts which are the shoulder, the elbow, the wrist and the grasp. The shoulder is currently assembled and used in testing whereas the design of the elbow and the gripper have been finalized. Three degree of freeedom are implemented by means of a motor, attached to the rover, and two actuators exploiting a differential mechanism. The mechanical design of the elbow features allows the lower arm to rotate with respect to the upper arm over a range of more than 360°. This facilitates the large workspace on either side of the arm with a single actuator and a compact arm. The gripping mechanism is based on a spring loaded linkage mechanism and to ensure a stable grip three fingers are extend outwards from the center of the interface.

Image

Figure 2- Rendered SHERPA arm with wrist and gripper placeholders.

Image

Figure 3- Shoulder of the SHERPA arm.

Image 

Figure 4- The gripper of the SHERPA arm.

  • Completion of the small-scale UAVs: The RW-UAV developed by ASLATECH is a very lightweight quadrotor that is specifically designed to dock on the sherpabox and to be grasped by the robotic arm: weight under 2 kg, size of 900 mm with propellers. The payload (about 500g) can be attached in any desired position and can contain any electronics or sensors that is suitable for SHERPA tipical missions. The algorithm initial validation will be performed by means of a bigger UAV (shown in the figure below)  ith relaxed constraints in terms of weight, size and payload. Designed for SAR operations, this machine guarantees more than 2 kg payload and flight time of about 25-30 minutes. The quadrotor is equipped with a 2-axes gimbal system which allows advanced localization, planning and control based on the integration with  standard IMU and GPS. The RW-UAV has been adapted for SAR operations in winter scenario so that an ARTVA receiver can be carried. The result can be seen in the figure below. To facilitate outdoor testing in hostile environments (such as the winter scenario), a portable ground station (see figure below) had been developed and built that is intended to run ground control station software for the RW-UAV testing. This can also be used for different UAVs and to develop and test HRI operations. The case is equipped with a touchscreen display and an it provide wireless connectivity and, optionally, internet connection. The case itself is certified IP67, and the components inside are placed to be protected from light rain or snow when opened.

Image

Figure 5- The RW-UAV

Image

Figure 6- The winter RW-UAV ARTVA machine

  • Completion of the design of the SHERPA box (UT): the SHERPA Box has been designed with the aim to become an off-the-shelf modular platform, useful in creating a network to connect all the different SHERPA robots, i.e. a data and communication relay node. One of the aims was the need to create something robust so that it can be used in harsh environment, especially in difficult weather. It also carries some sensors, such as GPS, temperature and humidity probes. The SHERPA Box has been designed to be mounted either on the ground rover or to be carried by a human operator. The enclosure is rated IP67 and it features a unit with 4G and Wi-Fi/Wi-Max connectivity. On the rover, a RW-UAV battery interchange mechanism is also present. It consists of a rotating plate that allows the storage of 8 batteries.

Image

Figure 7- Sherpa box - rover assembly

  • Adaptation of the fixed wing big-scale UAV: integration efforts for the fixed-wing patrolling hawks (ETHZ) have focused on sensing payload modularity, adapting the platforms to the needs of the SHERPA project. In the senseSoar prototype and in the AtlantikSolar UAV, some inner mechanical design has been reworked and installed for capacity to carry the ASL sensor pod. These modifications will allow more efficient sensor payload development, irrespective of the platform, facilitating a greater ease in flight testing new algorithms or hardware.
  • Selection of the HMI devices: the human operator is equipped with a non-invasive human-machine-interface that facilitates inertial and electro-myographic inputs so that the safety level can be overruled by interpreting the gestures of the human operator. Non-invasive haptic (vibro-tactile) and graphical (video) information are fed back during performing the mission. The figure below shows the human-machine technology.

Image

Figure 8- Human-machine technology

Environment and Situation Awareness

  • The partners have defined the interface in terms of: cognitive map structure and contents along with software tools and shared scenarios, distributed application programming interface (for multiagent mapping), human-robot interaction framework, reasoning engines and delegations systems.
  • Progresses have been made on sensor fusion, in particular: visual-inertial state estimation, sparse-to-dense map alignment and monocular dense reconstruction, integration of the LIDAR processing pipeline and testing on the RMAX system.

Image

Figure 9- Thermal image (right) collected during a flight test in Rothenthurm, Switzerland: each image patch contains a human.

Image

Figure 10- LIDAR processing pipeline and flight-test area in Sweden

 

  • Preliminary experimental results on LIDAR data classification have been obtained using the LIDAR data acquired by the RMAX helicopter. Moreover, data format for efficient LIDAR data storage and data compression methods for efficient LIDAR data processing and distribution have been explored.

Image

Figure 11- Automatic classification of the three LIDAR strips. Brown = ground , yellow

  • Human interpretation and interaction: a multimodal human-robot interaction framework has been designed and tested both in simulation and with real robots in the Twente arena.

Image

Figure 12- Multimodal Interaction in the Twente Flight Arena

References

[1] G. Bevacqua, J. Cacace, A. Finzi, V. Lippiello, "Mixed-Initiative Planning and Execution for Multiple Drones in Search and Rescue Missions", to appear in Proc. of ICAPS 2015.

[2] J. Cacace, A. Finzi, V. Lippiello, G. Loianno, D. Sanzone: "Aerial service vehicles for industrial inspection: task decomposition and plan execution". Appl. Intell. 42(1): 49-62 (2015)

[3] G. Bevacqua, J. Cacace, A. Finzi, V. Lippiello. "A Mixed-Initiative System for HumanRobot Interaction with Multiple UAVs in Search and Rescue Missions". AIRO-14 workshop at AI*IA Symposium on Artificial Intelligence.

[4] J. Cacace, A. Finzi, V. Lippiello, F. Cutugno, A. Origlia. "Multimodal Interaction with Multiple UAVs in Search and Rescue Missions". AIRO-14 workshop at AI*IA Symposium on Artificial Intelligence.

[5] G. Conte, P. Rudol, and P. Doherty. "Evaluation of a light-weight LiDAR and a photogrammetric system for unmanned airborne mapping applications". PFG Journal of photogrammetry, remote sensing and geoinformation processing. Photogrammetrie Fernerkundung - Geoinformation, Volume 2014, Number 4, August 2014, pp. 287-298(12).

[6] T. Cieslweski, S. Lynen, M. Dymczyk, S. Magnenat, and R. Siegwart. “Map API Scalable Decentralized Map Building for Robots”. 2015. In Robotics and Automation (ICRA), 2015 IEEE International Conference on. IEEE, p. to appear, 2015.

[7] M. Dymczyk, S. Lynen, T. Cieslweski, M. Bosse, and R. Siegwart and P. Furgale. “The Gist of Maps – Summarizing Experience for Lifelong Localization”. In Robotics and Automation (ICRA), 2015 IEEE International Conference on. IEEE, p. to appear, 2015.

[8] S. Leutenegger, "Unmanned Solar Airplanes", PhD thesis, Diss., Eidgenössische Technische Hochschule ETH Zürich, Nr. 22113, 2014.

[9] A. Origlia, V. Galatà, F. Cutugno, "Introducing context in syllable based emotion tracking", IEEE International Conference on Cognitive Infocommunications, pag. 337 – 342, 2014

[10] A. Origlia, F. Cutugno. "A simplified version of the OpS algorithm for pitch stylization". In Proc. of Speech Prosody, 2014

Cognitive-enabled reasoning and decision making

  • Interpretation of ambiguous and vague commands: the representation and reasoning methods, that have been prototypically realized in the first period of the project, have been extended with speech acts. These speech acts can be orders, representatives or questions and are interpreted and tested with our reasoning mechanisms.
  • Lightweight reasoning for decision-making: the heuristic reasoning mechanisms have been adapted and extended with inference mechanisms that reason about visibility and reachability of given objects within the given task context.

Figure 13- Simulation-based Reasoning

  • Hybrid knowledge representations and reasoning mechanisms: the RoboSherlock [1] has been integrated together with UIMA (Unstructured Information Management Architecture), for answering task-relevant  queries about objects in a scene. In addition, the framework allows for semantic retrieval of objects from semantic environment maps.
  • Semantic robot description language for mixed human-robot teams: The Semantic Robot Description Language that has been static so far, was extended to handle dynamically changing robot capabilities. Dynamic aspects include semantic descriptions and kinematic descriptions that are used by for motion planners.

References

[1] M.Beetz, F. Balint-Benczedi, N. Blodow, D. Nyga, T. Wiedemeyer and Z.-C. Marton, “RoboSherlock: Unstructured Information Processing for Robot Perception”, in IEEE International Conference on Robotics and Automation (ICRA), Seattle, Washington, USA, 2015, Accepted for publication.

[2] M. Beetz, M. Tenorth and J. Winkler, “Open-EASE — A Knowledge Processing Service for Robots and Robotics/AI Researchers”, In IEEE International Conference on Robotics and Automation (ICRA), Seattle, Washington, USA, 2015. Accepted for publication.

[3] F. Yazdani, B. Brieber, M. Beetz, "Cognition-enabled Robot Control for Mixed Human-Robot Rescue Teams", In Proceedings of the 13th International Conference on Intelligent Autonomous Systems (IAS-13), 2014.

[4] Patrick Doherty and Andrzej Szalas. 2015. "Stability, Supportedness, Minimality and Kleene Answer Set Programs". In T. Eiter, H. Strass, M. Truszczynski, S. Woltran, editors, Advances in Knowledge Representation, Logic Programming, and Abstract Argumentation: Essays Dedicated to Gerhard Brewka on the Occasion of His 60th Birthday, pages 125–140. In series: Lecture Notes in Computer Science #9060. Springer. DOI: 10.1007/978-3-319-14726-0_9.

Mixed-Initiative Cooperative Systems

  • Efforts have brought the functionalities of WP6 software to a higher qualitative level: most importantly, the software has been made ROS compatible, and, additionally, the system structure has been defined in a manner that provides swift delivery of modules to the participating partners for testing and feedback. This activity resulted in use of these software systems during the integration week in the Fall of 2014.
  • An initial version of the Task Specification Trees (TSTs) framework has been implemented as a ROS-based module: the TSTs are used to declaratively specify tasks and missions to be delegated to one or more participating SHERPA actors, documented and made available to all SHERPA partners for testing.

Image

Figure 14- Schematic overview of the role TSTs play in the RMAX robotic architecture.

  • An initial version of the Delegation Framework has been implemented, following the design specification presented during the first year [2], and is currently being validated in concrete test scenarios in cooperation with selected SHERPA partners.
  • An initial version of the distributed temporal planner has been implemented. This implementation has also been integrated directly into the Delegation Framework to support goal nodes: TST nodes that do not directly specify how a task should be performed but instead provide goal specifications to be achieved.
  • Further improvements have also been made in terms of efficiently handling Simple Temporal Networks with Uncertainty (STNUs) [4]. In particular, integration of this functionality with the temporal planner is in its early stages.
  • Prototipation, wrappingn and testing of team coordination algorithms: it permits the distributed allocation of partitions in a region of interest and the generation of scan patterns for each partition suitable for search or mapping.
  • Development of monitoring algorithms based on the use of Hop-constrained Directed Steiner Trees [3]. This has resulted in the LKU group winning a prestigious algorithmic competition organized by DIMACS. The 2014 competition focused on Steiner Trees. These ideas could be used as a basis for additional coordination algorithms in the SHERPA project.

References

[1] Bevacqua, Cacace, Finzi, Lippiello, Mixed-Initiative Planning and Execution for Multiple Drones in Search and Rescue Missions, to appear in Proc. of ICAPS 2015.

[2] Patrick Doherty, Jonas Kvarnström, Mariusz Wzorek, Piotr Rudol, Fredrik Heintz and Gianpaolo Conte. Aug 2014. HDRC3 - A Distributed Hybrid Deliberative/Reactive Architecture for Unmanned Aircraft Systems. In Kimon P. Valavanis, George J. Vachtsevanos, editors, Handbook of Unmanned Aerial Vehicles, pages 849–952. Springer Science+Business Media B.V.

[3] Oleg Burdakov, Patrick Doherty and Jonas Kvarnström. 2014. Local Search for Hopconstrained Directed Steiner Tree Problem with Application to UAV-based Multi-target Surveillance. In Butenko, S., Pasiliao, E.L., Shylo, V., editors, Examining Robustness and Vulnerability of Networked Systems, pages 26–50. In series: NATO Science for Peace and Security Series - D: Information and Communication Security #Volume 37. IOS Press.

[4] Mikael Nilsson, Jonas Kvarnström and Patrick Doherty. 2014. Incremental Dynamic Controllability in Cubic Worst-Case Time. In Proceedings of the 21st International Symposium on Temporal Representation and Reasoning (TIME), pages 17–26.

Low-level and reactive control

  • A novel control strategy for robust navigation of a class of mobile robots in potentially cluttered and dynamically changing environments was developed and tested on a ground robot and an UAV by UNIBO.
  • ETHZ made the low-level guidance and control of the fixed-wing patrolling hawks more robust to severe wind conditions, while simultaneously targeting optimality in scan trajectory tracking. Actuator fault tolerance was also investigated. Highlevel path planning was designed and tested for low cost mission planning providing full area coverage of the visual sensing payload via optimized viewpoint generation. Regarding sensor fusion, ETHZ implemented a pipeline for visual-inertial odometry based on a nonlinear optimization formulation.
  • A robust low-level estimation and control architecture was developed and tested through indoor flights for the SHERPA wasps by UNIBO. The implemented solution was refined in order to take into account the mission and operating environment constraints of SHERPA.
  • Successful virtual leashing experiments based on human test subjects were accomplished by LKU with small quadrotor systems. Additionally, online-learning techniques wereinvestigated for safe trajectory generation.
  • BLUE integrated the sensors necessary for the implementation of the kinematics estimation algorithm of the rover.
  • Sensor fusion techniques were applied by UT to the SHERPA robotic arm to improve tracking capabilities and to achieve a reactive behaviour during the docking of the small scale UAVs. A bilateral human-robot control for the semi-autonomous navigation of UAVs was also developed.
  • Fast path and trajectory planning techniques were implemented by CREATE to allow the continuous action invocation and replanning of SHERPA aerial platforms.
  • CREATE developed several techniques to improve the quality of the reactive interaction with SHERPA aerial vehicles. In particular, aerial leashing strategies based on camera sensor data, reactive control via deictic communication using direction pointing through arm and mixed-initiative teleoperation are currently investigated.

References

[2] Furci, M.; Naldi, R.; Paoli, A.; Marconi, L.. 2014. “A robust control strategy for mobile robots navigation in dynamic environments” In: Decision and Control (CDC). 2014 IEEE 53rd Annual Conference on 1 The planned person-months refer to the whole project while the actual person-months refer to the reporting period.

[3] R. Naldi, M. Furci, R.G. Sanfelice and L. Marconi. 2014. “Robust Global Trajectory Tracking for Underactuated VTOL Aerial Vehicles using Inner-Outer Loop Control Paradigms” Submitted to journal.

[4] Olov Andersson, Fredrik Heintz and Patrick Doherty. 2015. “Model-Based Reinforcement Learning in Continuous Environments Using Real-Time Constrained Optimization” In: Proceedings of the Twenty-Ninth AAAI Conference on Artificial Intelligence.

[5] Rudin, K., Mosimann, L., Ducard, G., Siegwart, R., “Robust Actuator Fault-tolerant Control using DK-iteration: Theory and Application to UAS” In: 9th IFAC Symposium on Fault Detection, Supervision and Safety for Technical Processes (Safeprocess’15), Sep. 2-4, 2015. Paris, France (under review).

[6] J. Cacace, A. Finzi and V. Lippiello. 2014. “A Mixed-Initiative Control System for an Aerial Service Vehicle supported by force feedback” In: Intelligent Robots and Systems (IROS), 2014 IEEE/RSJ International Conference on.

[7] L. Aldrovandi, M. Hayajneh, M. Melega, M. Furci, R. Naldi, and L. Marconi. “A smartphone based quadrotor: Attitude and position estimation” In: ICUAS’15 – The 2015 International Conference on Unmanned Aircraft Systems, June 2015. Paper under submission.

[8] M. Melega, M. Hayajneh, R. Naldi, M. Furci, , and L. Marconi. “An aerial robot for alpine search and rescue : the sherpa platform” In DroNet 2015 – Workshop on Micro Aerial Vehicle Networks, Systems, and Applications for Civilian Use, May 2015. Paper under submission.

[9] A. Bircher, K. Alexis, M. Burri, P. Oettershagen, S. Omari, T. Mantel, and R. Siegwart, “Structural Inspection Path Planning via Iterative Viewpoint Resampling with Application to Aerial Robotics”. In: IEEE International Conference on Robotics and Automation (ICRA), May, 2015 (accepted).

Architecture and Simulator

  • A world model architecture has been designed to address the needs of the SHERPA project. The 'SHERPA World Model' contains multiple agents for different tasks. The world model contains now robot data, which includes robot poses, and can easily be augmented with additional robot data. In addition, it was agreed that the task specification tree, which is the outcome of the delegation framework, would be stored to simplify the delegation to the actors while keeping the world model informed. The SHERPA World Model plays a central role for the integration of the work of the partners in the consortium. During the first integration week and (remote) follow-up meetings, efforts have started to integrate the delegation framework (LKU), multimodal interaction framework (CREATE), and the semantic reasoning (UniHB) with the world model. These integration steps also required us to start working on customized interfaces for LKU, UniHB, and CREATE.

Image

Figure 15- A graphical sketch of the world model architecture.

Experimental Validation

  • UNIBO, ETHZ, LKU and ATECH worked towards integrating the hardware and software necessary for providing the functionality described in D2.1, and for interfacing with the Delegation Framework. Several flight tests were carried out in order to validate both lowlevel and high-level functional primitives.
  • On 2015/04/11 UNIBO, ATECH and CAI performed several “winter scenario” experiments to assess the performance of the ARTVA signal search function also in presence of human and animal (rescuer dog) interaction:

o    Finding single ARTVA (on the snow): the ARTVA beacon is placed (known position) about 30m far from the takeoff position. By means of a slow speed approach the ARTVA signal is correctly identified when the RW-UAV is about 5 meters close to the beacon and, once the initial detectionis accomplished, the singal is correctly tracked up to 12m far from the ARTVA.

Image

Figure 16- Finding the single ARTVA

o    Finding multiple ARTVA (on the snow): Two beacons are placed 3m far each other ad both about 30m far from the takeoff position. As in the previous case, by means of a slow speed approach, the two signals are correctly indentified as separate items with tracking performance comparable to that of a single ARTVA scenario.

o    Finding single ARTVA (1m under the snow): Same scenario of the “finding single ARTVA” test but with the beacon 1m under the snow. The detection performance slightly decrease but guaranteeing the correct beacon identification. In future tests the ARTVA beacon will be placed more in depth under the snow.

Image

Figure 17- ARTVA concealing

o    Finding ARTVA by predefined path serach (ARTVA 20cm under the snow): the ARTVA beacon has been placed under 20cm of snow (unknown position) within a predefined search zone of 20x40m. By following a predefined searching path (paraller and alternate straight lines) the first valid signal is received 90s after the takeoff (flown ground track of about 120m). After further 2’30’’ the beacon position is identified with 1m of accuracy.

Image

Figure 18- ARTVA found 1m close to ita estimated position

o    RW-UAV – rescuer dog interaction: this experiments tests the impact of the presence of a RW-UAV on the research performance of the rescuer dog. After the natural transient during which the dog “understands and accepts” the presence of the RW-UAV, the rescue tasks are accomplished by following the same procedures of the “RW-UAV free” scenario, thus leading to the same final searching performance.

Image

Figure 19- RW-UAV - rescuer dog  interaction

  • CREATE implemented and tested the multimodal interaction system, and performed an initial integration of the HRI, the reasoning engine, the drones, and the delegation system.

 

 

**** March 2014 - October 2014 ****

Trained Wasps (quadrotors, UNIBO & ATECH): UNIBO and ATECH were mainly involved in the development of the small scale quadrotors, identified in this project as trained wasps. Their main task is to support the rescuing and surveillance activity by enlarging the patrolled area with respect to the area potentially “covered” by the single rescuer, both in terms of visual information and monitoring of emergency signals. In order to develop this type of platform the following three types of prototypes were implemented and tested:

  • Mini Wasp, small scale academic platform derived by a commercial nano-quadcopter used for testing the performances of the low-level control algorithms for acrobatic and formation flight, and wind rejection;
  • Winter Wasp, the actual wasp operated in the winter scenario of SHERPA missions and designed for victim detection based on ARTVA signal;
  • Summer Wasp, the wasp employed in summer SAR missions and with an hardware equipment much wider of the previous two platforms.

 

The mini wasp was derived by the nano quadcopter CrazyFlie of Bitcraze. This is a small and lightweight unit (around 19g and about 90mm motor to motor) allowing remote control by computer through his on-board low-energy (1mW) radio with up to 80m range. It includes moreover a 6-DoF sensors set (3-axis high-performance MEMs gyros with 3-axis accelerometer). The control is based on a powerful 32 bit MCU on which the algorithms developed for the other platforms were compiled for executing flight tests. More precisely, the wind rejection was based on an algorithm developed by UNIBO and described in [1]. The acrobatic flight capabilities were based on the Globally Asymptotically Stable (GAS) algorithm described in [2]. This algorithm was implemented on the mini-wasps in order to develop the hand-deployment capabilities of the bigger-scale wasps. The mini wasps were actually tested with hand-deployment. The formation flight was finally allowed by the consensus algorithm proposed in [3]. Also in this case flight tests were done considering a formation of three mini wasps.

The winter wasp is a bigger but very light quadrotor allowing the transport of a 300 g payload and with an autonomy of 20-25 minutes. The propulsion power generated by the rotors is controlled by an Electronic Speed Control (ESC). The low-level control of the quadrotor is based on the Pixhawk autopilot with an internal IMU (3-axis digital output gyroscope, 3-axis accelerometer and 3-axis magnetometer). A GPS receiver, an external magnetometer and a laser telemetry sensor and a RC receiver feed also the controller. The ARTVA transceiver is a Ortovox M2 connected with the board Odroid-U3 of Hardkernel co., Ltd. providing higher-level position commands to the low-level autopilot. The Odroid board allows also the communication with a Personal Computer (PC) acting as ground control station through a WiFi connection. Some preliminary flight tests were successfully accomplished for the winter wasp in indoor and outdoor environment.

 

Summer Wasp 3D CAD Drawing

Summer Wasp 3D CAD Drawing

The summer wasp was finally designed as a light-weight and high-stiffness quadrotor with the capability to hover a payload of more than 2 kg payload for about 25-30 minutes, that is a strong requirement for its involvement an SAR missions. The propulsion power generated by the rotors is controlled by an Electronic Speed Control (ESC) and produces a maximum thrust of 2 kg for each rotor. The low-level control of the quadrotor is based on the same Pixhawk autopilot of the summer wasp. This board takes inputs also from the GPS receiver, the external magnetometer and the optical flow sensor, as well as the RC receiver. At an higher-level, Vi-Sensor stereo camera of Skybotix and a gimbaled laser scanner are used to refine the position measure, estimate the pose of the vehicle and to produce a 3D map of the surrounding environment. The laser scanner is a UTM-30LX-EW of Hokuyo Automatic CO., LTD. mounted on a 2-axes gimbal system designed for obtaining quick 3D scanning of outdoor environments. The system is designed to compensate for rotation around the pitch axis inside the range ±35° and complete rotations around the roll axis. These higher level sensors communicate their acquisitions to an Mini PC - kit Intel® NUC D54250WYK computer allowing also the communication with the PC acting as ground control station through WiFi connection. This computer performs moreover the reactive supervisory control.

References

  1. P. Castaldi, N. Mimmo, R. Naldi and L. Marconi, "Robust Trajectory Tracking for Underactuated VTOL Aerial Vehicles: Extended for Adaptive Disturbance Compensation", accepted to IFAC WC 2014
  2. R. Naldi, M. Furci, R.G. Sanfelice and L. Marconi, "Global Trajectory Tracking for Underactuated VTOL Aerial Vehicles using Cascade Control Paradigms", accepted to IEEE Conference on Decision and Control, 2013
  3. G. Casadei, M. Furci, R. Naldi and L. Marconi, "Quadrotors Motion Coordination Using Consensus Principle", submitted to ACC 2015

Fixed-Wing Patrolling Hawk (fixed-wing UAV, ETHZ): ETHZ worked on different aspect related with the fixed-wing patrolling hawk implementation. In particular, the following topics were developed:

  • low-level control and guidance,
  • high level path planning,
  • integration with the delegation framework,
  • integration of the SenseSoar platform,
  • flight testing.

The low-level control development dealt with the implementation of low-level guidance and of control algorithms robust to the relatively high winds. After some modifications to the controller, it was demonstrated the aircraft’s resistance to strong thermal updrafts and downdrafts during a 12-hour flight test. It was also looked into ways of integrating online wind estimates as inputs to new spatially optimal guidance logic for robustly tracking trajectories in the presence of wind-to-airspeed ratios approaching unity.

A fast and efficient inspection path-planning algorithm for executing mapping and surveillance missions was developed. Given a set of waypoints, the method finds a low-cost mission trajectory considering the dynamics of the fixed-wing aircraft and its sensor limitations, providing full coverage of the search area. The method has potential for efficient mapping and surveying during search-and-rescue missions. The approach has been successfully tested in field demonstrations organized within the framework of the ICARUS FP7 project in Barcelona, Spain and Marche-en-Famenne, Belgium.

In the weeks leading up to the first SHERPA integration week it was performed the initial integration of the Pixhawk PX4 autopilot system with the SHERPA delegation framework. It was created platform-specific TST nodes and tested them on an Multiplex EasyGlider test platform, completing waypoint-following tasks similar to those potentially encountered during a search-and-rescue mission. There are plans to provide further delegation functionalities. There is also a scheduled bilateral test between ETH Zürich and Linköping University, where a sample search-and-mapping mission will be flown simultaneously with the Atlantik Solar UAV and RMAX Helicopter in Zürich and Sweden, respectively.

the AtlantikSolar platform

the AtlantikSolar platform

Leichtwirk AG delivered the new SenseSoar platform, with solar cells installed. The new airframe is roughly 200 grams lighter than the prototype, which increases payload capacity. Efforts are underway to integrate flight systems and avionics into the new vehicle. Some of the mechanical design has also been reworked in order to obtain a more modular system capable of carrying the same sensor payload as the AtlantikSolar. In particular, these modifications will allow the SenseSoar to carry the sensor pod, allowing for efficient sensor payload development irrespective of the platform, and quick-and-easy flight testing.

Extensive field tests were conducted with the AtlantikSolar platforms to prove their flight worthiness (Figure 3). The series aircraft, AtlantikSolar AS-S1, performed a continuous 12-hour flight without solar power. Despite rough winds of up to 44 km/h and strong thermal updrafts and downdrafts, the battery remained above 20% charged. The maximum endurance is estimated to be approximately 15 hours. A further test in turbulent conditions was performed during the first SHERPA integration week at the Nijverdal RC club just outside of Enschede, NL. The AtlantikSolar proved to be remarkably robust to high winds, which at some points exceeded the airspeed.

Intelligent Donkey (ground rover): Since March 2014 BlueBotics has worked mainly on the design of the ground rover. The goal was to design a research platform allowing to demonstrate the various benchmarking scenarios. The chassis carries the SHERPA box, the robotic arm and has good off-road capabilities thanks to its passively articulated kinematics. The four tracked bogies can rotate freely around their pivot axis and the transverse bogie ensures good lateral compliance for optimal terrain adaptation. At the time of the writing of this document, the design (Figure 3) is finished and the production of 3 units is about to start.

 

The ground rover current layout

3D CAD drawing of the ground rover current layout

**** September 2013 - February 2014 ****

Flight tests: some experimental flight tests were performed in “Valle d'Aosta” in collaboration with CAI during a training session for rescuers. The experiments were carried out at an altitude of 2000m.

One RW-UAV prototype, equipped with the ARTVA receiver was piloted in semi-automatic mode to track the signal coming for a buried ARTVA transmitter to simulate a person buried under the snow.
The drone, guided by the commands of one CAI rescuer and by the ARTVA signal, successfully found the buried ARTVA in short time.
Some problems of electromagnetic interference between the RW-UAV avionics and the ARTVA receiver were addressed as first step by distancing the receiver from the drone by mean of a hanging structure.
The video of the operation could be find here: http://www.youtube.com/watch?v=0ISRp0t7ofk

Mechanical design: in the first year of project the mechanical design of the agents have been designed. In particular the focus was on designing the ground rover, the RW-UAV, the arm, the SHERPA box, and adaptations of the FW-UAV.
Ground Robot: the role of ground rover will be only in summer scenario and consist in carrying the SHERPA box, some RW-UAV and act as communication relay and main computation station.

RW-UAV:  the design of these agents was guided by the needs of a simple but effective drone, with some key feature. In particular the RW-UAV should be grasped by the robotic arm, should have protected propellers for the security of rescuers and should have enough space and payload to carry avionics and sensors.

Arm: the design of robotic arm was carried out following the specification about the interaction with RW-UAV. In particular the arm will act as a docking station for quadrotors.

FW-UAV: some adaptation were planned for the FW-UAV, in particular to carry all the necessary sensors (thermal camera, stereo vision camera)  and improved avionics.

Sensor fusion and data collecting: some algorithms for sensor fusion and data collecting were developed and tested.
Visual odometry: a novel algorithm was developed. In particular using just information from a stereo camera and a high precision IMU (no GPS), it was possible to reconstruct a trajectory performed outside ETH main building with very good performances. The comparison with state-of-the-art algorithm and with ground thruth (GPS) can be seen in the figure below.

Progress Image 01

Object detection: a novel algorithm was developed to detect people with infrared images. Some tests were performed with the use of a thermal camera.

Progress Image 02

Airborne terrain mapping: during the first year of SHERPA a set-up for terrain mapping was developed. In particular an airborne LiDAR system and photogrammetric system were used to perform test with the use of RMAX helicopter.

Human interpretation and interaction: the main achievements in this field:

  • On-the-field data has been collected receiving feedback from the end users about initial interface concepts.
  • A preliminary emotional speech analysis of the collected data was carried out.
  • An initial human-robot interaction platform has been set up.
  • An initial multimodal human-robot interaction architecture for the SHERPA domain has been designed and developed.
  • A corpus of fixed gestures was collected to train a first classifier on a predefined set of expressive motions.
  • A generative model approach for the resolution of designators in the CRAM framework have been designed.
  • Gesture classification methods for continuous gesture recognition have been designed and developed.
  • An initial simulation environment for data collection and testing in a human-robot interaction scenario has been set up.

Progress Image 03

Cognitive-enabled reasoning and decision making: the main achievements in this field:

  • Interpretation of ambiguous and vague commands: we have designed, realized and tested prototypical representation and reasoning methods that can sample command instances and test whether they satisfy the vague instruction.
  • Lightweight reasoning for decision making: we have designed and realized first heuristic reasoning mechanisms that enable robotic agents to perform decisions based on foresight, e.g. by considering the reachability.
  • Hybrid knowledge representations and reasoning mechanisms: we have started to realize knowledge processing mechanisms building on the open source UIMA (Unstructured Information Management Architecture) framework. Among other features, the framework allows for the interpretation and analysis of semantic environment maps.
  • Semantic robot description language for mixed human-robot teams: we have extended our Semantic Robot Description Language to represent and reason about the capabilities of team members of rescue teams, including humans. The capability reasoning mechanisms allow us to specify, in selected example use cases, robot plans that can abstract away from the agent executing the plans and that automatically generate behavior which is tailored to exploit the available capabilities.

Low level Control: several algorithms were developed for the low level control, in particular for RW-UAV. One of the focuses was developing a control law suitable for robust hand and helicopter deployment.

Progress Image 04

Some robust control strategy were develop, to perform emergency maneuvers in case of fault of propellers/motors. The aim was to ensure safety for human rescuers in case of faults.

Some parameter estimation algorithms has been proposed to estimate unknown parameters and effects as unknown payload,  disturbances, wind and aerodynamics effects.
Finally, a new image-based visual servoing controller for the coordinated landing of a VTOL UAV on a landing platform actuated by a mobile manipulator has been proposed.

Progress Image 05

Robotic arm modeling: a competent kinematic and dynamic model of the SHERPA robotic arm has been realized in order to specify the actuator requirements and as a basis for developing the low and high-level control strategies.

 

**** March 2013 - August 2013 ****

Specifications: a number of meetings with the end-user CAI have been organized in order to discuss features of rescue missions in the alpine setting. In particular, descriptions and information about real mountain and avalanches scenarios and rescue missions were used to define specifications in terms of capabilities of the “animals” and SHERPA box. Main specifications for the aerial and ground platform have been also identified. Aerial vehicles will be based on multi-rotors configurations with variable pitch blades. Foldable configurations have been also discussed and are now under study. As far as the ground rover is concerned, it is calibrated to carry three-four aerial vehicles and to operate mainly in the summer scenario. It will be equipped with a robotic arm to have autonomous features in term of UAVs deployment. Typical terrain roughness in which the vehicle is required to operate has been identified.  Specific onboard hardware has been identified.    
 
Benchmark definition: three benchmarks have been defined. Each benchmark includes increasing capabilities for every platform. In particular the functionalities and actions of the platforms as well as the software modules and the HMI have been defined. The level of cooperation between the working groups to develop joint functionalities  has been evaluated. 
The emphasis in the first benchmark is to develop the basic software and hardware tool for operation in the “average” environmental conditions.
In the second benchmark emphasis is put on the composition of the individual platforms and their capabilities to complete SHERPA teams, composed of one or more Human Rescuers leading their own robotic platforms (Ground Rover, RW-UAV, FW-UAV and Rmax).
The final benchmark is on a realistic search and rescue mission. In particular, summer and winter scenarios have been identified. The winter benchmark is focused on the avalanche case and it mainly consists of finding an ARTVA transmitter with tight time constraints. The summer benchmark is calibrated on a rescue mission typically accomplished by the end-user on summer. It mainly consists of localizing a person lost in the forest within a very large area.  Both the scenarios have been calibrated in order to demonstrate all the capabilities of the SHERPA team building on top of the foundations set on the first two benchmarks. 
 
Flight tests: preliminary flight tests were performed at high altitude to test actual commercial platforms. The tests were mainly conducted at “Passo dello Stelvio” on the occasion of a SHERPA meeting. The tests allowed the team to analyze performance of RW-UAVs and propellers in hostile conditions typical of high altitude. Flight tests took place at about 3000m. Preliminary tests were conducted with standard cameras and infra-red cameras, with manual pilot, trying to locate a person half buried by snow.
Video could be seen here: http://www.youtube.com/watch?v=IYGOocsX-GI
 
Website and dissemination: sherpa website is online, containing pictures, videos and deliverables.
A Youtube account, a twitter account and a blog on DIYDrones have been created.
A SVN (subversion repository system) has been created to keep important documents/code and to share them among the partners.
 
 

**** February 2013 ****

Kick-off meeting.

 

Theme by Danetsoft and Danang Probo Sayekti inspired by Maksimer