Ground-based Search and Retrieve using Aerial ... - Semantic Scholar

1 downloads 0 Views 2MB Size Report
Co-operative ground / aerial vehicle pairs can potentially be ... Unmanned vehicles have had a large research focus in recent years, partly ... overall system to perform search and retrieve tasks. While ... Finally, an extensive list of proposed future work will be provided to ..... Fighting,” 7th International Conference on Systems.
Ground-based Search and Retrieve using Aerial Localisation Daniel Ferguson, Eloise Matheson and Dushyant Rao School of Aerospace, Mechanical and Mechatronic Engineering, University of Sydney, Australia Email: {dfer9299, emat3105, drao7945}@uni.sydney.edu.au

Abstract Co-operative ground / aerial vehicle pairs can potentially be utilised for search and retrieve applications in disaster scenarios. A simplified setup has been implemented using an iRobot Create platform, coloured retrieval targets and a roof-mounted camera for localisation. This paper outlines the design of the entire system, with particular emphasis on perception, navigation, guidance and control subsystems. Preliminary vehicle test results are presented and discussed, and potential future improvements are suggested.

1

Introduction

Unmanned vehicles have had a large research focus in recent years, partly due to their ability to replace manned missions in high-risk situations. They are ideal for missions in hazardous environments and inaccessible terrain, and can therefore be invaluable for search and rescue missions in disaster scenarios. [1] Co-operative air and ground surveillance is an area of research that has emerged in recent years. Unmanned aerial vehicles (UAVs) have the advantage of rapid coverage, but often experience difficulties reaching the target, and can only localise ground targets to a coarse level of accuracy. Conversely, unmanned ground vehicles (UGVs) can locate targets to high precision but cannot see through ground obstacles and move more slowly. Thus, ground-aerial co-operative surveillance is a synergistic combination, offering rapid coverage, localisation and movement to a ground target. [2] Much of the recent work on co-operative aerial / ground vehicles focuses on control architectures, frameworks and algorithms applicable to multiple vehicles. Specific aspects of co-operative control are examined, with respect to aerial and ground-based platforms ([1] , [2] ). In this paper, the approach is more on developing an overall system to perform search and retrieve tasks. While time constraints have made it necessary to simplify the system and operating scenarios, the work performed here represents a general implementation of the entire system.

The implementation discussed here is a simplified version of an aerial / ground co-operative pair. A fixed roofmounted camera is used to represent a UAV localising both the target and the UGV, the retrieval targets are coloured cardboard circles and the iRobot Create platform is used for the UGV. Accordingly, this paper will outline the broad architecture of the system, and examine specific subsystems that have been implemented. In particular, the perception and navigation algorithms responsible for localising the targets and the UGV will be discussed, as well as the guidance and control algorithms that facilitate target retrieval. Preliminary testing has also been performed with the integrated system for a range of simple scenarios; the key results will be outlined and discussed. Finally, an extensive list of proposed future work will be provided to identify the tasks required to more accurately model a true co-operative air / ground vehicle pair.

2

Background

Much work has been done on co-operative ground/aerial search and retrieval using a variety of sensors in different combinations. Perception sensors such as laser scanners, sonar sensors and colour CCD cameras are commonly utilised and sensors including ultrasonic transducers for altitude, Global Positioning Systems for location and Inertial Measuring Units for orientation can be used for navigation. Projects such as the Autonomous Vehicle Tracking and Retrieval (AVATAR) Helicopter use a CCD camera for aerial perception and a camera and sonar sensors for ground perception [3] . The General Robotics, Automation, Sensing and Perception (GRASP) project uses a stereo pair of cameras for ground perception and a high resolution firewire camera for aerial perception [4] . These projects are generic examples of the current practise of co-operative combinations of data acquisition between aerial and ground vehicles. Given limited time scope within our project we decided to simplify the system in a manner that we could test and verify our system to gain significant results. To do this

the perception for our aerial vehicle has been simplified to a single roof mounted stationary colour web camera and this data is fused with the navigational data gained from our robotic platform equipped with wheel speed encoders. The use of colour segmentation in perception is widespread, with many algorithms implemented using various techniques. Many of the algorithms processing images in the HSV space as opposed to RGB space as it is quite insensitive to change in intensities such as variance in lighting conditions. 0 Colour segmentation algorithms can be loosely categorized into four classifications: pixel based, region based, edge detection and physics based. Pixel based imposes thresholds on the histogram, or clustering using techniques such as clustering or mean shift. [3] [7] [8] Region based evaluates uniformity criteria to obtain homogeneous regions. Edge based uses the edges as a guide to identifying homogeneous regions. Physics based rely on modelling the underlying physical reflectance property of the material. [6] As the scenario for this robot is quite contrived with simplistic shapes and colours in a reasonable saturation invariant environment, a simple HSV space pixel based colour segmentation algorithm was implemented in our system. Navigation for a UGV is typically a fused estimate of multiple localisation measurements. Given that vehicle navigation is typically a non-linear problem, it is often achieved using estimation techniques such as a particle filter or an Extended Kalman filter, using the evolution of the vehicle’s state based on past observations to estimate the future state of the vehicle. Simpler implementations may employ a low pass filter to estimate the vehicle’s position, and this is the method that has been employed here. Guidance and control of ground vehicles is highly dependent on the platform involved and the application. Path planning techniques vary considerably, some emphasising traversability and others focusing on obstacle avoidance. Dubins’ curves and cubic Bezier paths [14] are typically used where vehicle turning curvature is a constraint, while obstacle avoidance may be achieved using potential field methods [15] , occupancy grid based methods, or network-based methods such as visibility graphs and Voronoi diagrams. Optimal paths may be obtained by using grid-based search algorithms such as A* or D* [16] , which can also account for obstacles. Path following is again highly platform and mission dependent. For a non-holonomic vehicle (one that is not controllable in all of its degrees of freedom), PID controllers are the most widely used, and the heading

error (between path and vehicle headings) and cross-track error (perpendicular distance between vehicle and path) may be used to determine the required control inputs [18] . The pure pursuit guidance law has also been widely implemented, using a single look-ahead distance parameter to specify a point ahead on the path and set the controls to steer the vehicle to that point [17] . This has the key advantage of easier tuning, with only one parameter determining how closely the path is followed and how erratically the vehicle steers. The current system is operating in an obstacle field, and continuous paths are desirable for efficient path following, so the potential fields approach has been used for path planning, and a pure pursuit guidance algorithm implemented for path following.

3

Design Overview

Given that this experiment aimed to develop many aspects of co-operative ground/aerial search and retrieval, the design of the complete system needed to be simple and easy to navigate for a user, so as to aid future expansions to the system. To do this a modular framework of subsystems and a state transition method was adopted for the software design and previously documented and tested hardware was used for the mobile platform, namely an iRobot.

3.1

Software

The software system is a state based transition architecture where certain modular sub-systems are called when necessary. Using a modular approach to the design means that the algorithms and methods adopted can easily be manipulated to suit a particular situation, giving a higher degree of flexibility to the overall system. The modular subsystems that we have used are Perception, Navigation, Guidance, Control and Communication. In more depth, single or multiple sub-systems may be called by the states Get Target, Collect, Go Bin and Complete which encompass all the actions our system can be commanded to complete. This assumes that the system has been correctly initialised; which calibrates the camera and sets up communication with the mobile platform.

Figure 1: State Transition Diagram

A brief overview of each system is stated below, though further details of each subsystem are given in Section 4. The perception subsystem seeks to establish the localisation of both the mobile platform and the objects in the specified arena. Furthermore, it differentiates between different coloured and sized obstacles and targets, using HSV colour space and blob extraction algorithms. The system returns centre points and radii of all targets and obstacles, as well as the position and heading of the mobile platform. The OpenCV source libraries were used extensively in the perception module, including those for image capture, colour segmentation and blob extraction. Navigation is responsible for outputting a more refined estimate of the mobile platforms localisation by fusing data gained from the vision subsystem as well as that directly from the onboard wheel encoders of the robot. The guidance subsystem takes in inputs of what is in the arena area and duly plans a path for the mobile platform to follow, given the desired target position and pose. The path is planned based on obstacle avoidance whilst producing an achievable path for the robot to follow using potential field theory. The control system follows the guidance system in that once a path plan has been established the correct movement commands are sent to the robot. The communications system ascertains whether these commands are sent via Bluetooth (not currently implemented in this stage of development) or through a serial connection. Feedback is present in the software design from the perception subsystem, which can check whether each state transition has successfully occurred.

3.2

Hardware

The iRobot Create Programmable Robot was chosen as our mobile robotic platform. This development package provides an established working system which can be modified to suit various robotic applications. This versatility made it a good choice in our experiment, as it was able to provide the dependability and flexibility in hardware that was required. This mobile platform has a diameter of 0.35 m and has onboard wheel encoders which provided constant information on the robot’s speed and direction. The accuracy of this data was dependent on the speed at which the robot was operating, but still was still able to provide useful data which could be fused in the navigation subsystem. The iRobot provided a physical platform which we could perform our searches with, but was not able to activate any retrieval methods. To do this, we constructed and added a novel onboard electromagnetic retrieval system.

This consisted of an electromagnet made from a modified transformer which was powered by a bank of six 9 volt batteries, supplying a total capacity of 3.5 AH. The electromagnet was activated by a 0-5V digital signal from the iRobot, which enable the retrieval system to be turned on or off using a N-fet switching circuit. Thin strips of iron were attached to the targets, ensuring that the targets could be collected by the iRobot without impinging on the mobility of the platform. As the system was designed to perform cooperative ground/air based localisation, a camera was needed to act as the aerial perception unit. The Logitech E2500 QuickCam was used for this application. When placed at average roof height of a room (approximately 2.5 m) it had a field of view of 1.5x2.5 m which was of adequate size to perform applications of our system considering the small scale of our platform. The sizes of our targets were designed to be smaller than the robot itself whilst bases were larger. This enabled the perception subsystem to produce reliable and accurate results. To communicate with the robot two options were tested, one using a direct RS232 serial connection and the other using an AVR microprocessing board with an onboard Bluetooth module which was able to send serial commands wirelessly to the robot.

4 4.1

Implementation Perception

This module seeks to localise the robot and detect all the obstacles, targets and home bases from an image. To do this colour segmentation was done on an image of the arena, filtering applied and finally blob extraction algorithms used. However before this could be achieved, the camera needed to be calibrated for our purposes and setup. In general, vision based range measurements rely on calibrating the camera using known intrinsic and extrinsic properties of the camera. A widely used calibration technique is to solve a set on linear equations with 12 unknowns. [11] This technique is valid for unknown scenes as long as the intrinsic properties of the camera do not change, however calibration often needs to be repeated when using modern CCD camera for changing scenes. [12] In our scenario the situation has been simplified as the roof mounted camera is stationary, and so is at a constant distance from the scene picture at a known angle. As long as the camera does not move from its localised spot, simple calibration only needs to occur once to establish the limits of range that the camera perceives. To perform calibration, the physical size of the image plane needs to be known, adopting a similar approach used in [13] . Depth perception is not of consequence in our setup, as we have simulated a two dimensional arena for the robot.

A BGR image is captured from the webcam, such as shown in Figure 2 and converted to a HSV representation.

This filtered saturation image is then used as the basis for filtering the hue image, shown in Figure 5.

Figure 2: Webcam Sample Image. From this HSV image, the saturation channel is isolated as shown in Figure 3.

Figure 5: Hue Channel The ‘zero value’ saturation pixels are ‘removed’ from the hue image, leaving only the hue values of the targets.

Figure 3: Saturation Channel The pixels in this channel corresponding to values lower then a threshold (which was set such to remove the floor) are ‘zeroed’ out in the image to give Figure 4.

Figure 6: Hue Channel after Saturation Filtering From the filtered Hue image, Figure 6 , the image is segmented based on the value of the hue to give three distinct RGB segmented images as shown in Figure 7. As seen in the blue segmented image of Figure 7 there is some noise generated in the segmentation. To remove this noise the image is eroded (black pixels enlarged) and then dilated (the white pixels enlarged).

Figure 4: Saturation Channel with Threshold Applied

Top: Left: Hue Channel Middle: Saturation Channel Right: Value Channel Middle: Left: Red Threshold Image Middle: Green Threshold Image Right: Blue Threshold Image Bottom: Left: Red Segmented Image Middle: Green Segmented Image Right: Blue Segmented Image

Figure 7: Colour Segmentation Sample A blob detection algorithm is then applied to these segmented images to find the properties of the targets. This openCV source algorithm [10] has advantages over other blob extraction techniques as it maps component contours in linear time in one image pass. This outperforms other techniques which can take more than one image pass to label every component. Furthermore this algorithm does not need to relabel components as contour mapping is able to connect internal and external components at the same time. The algorithm is applied on a binary image of one colour channel. Doing this makes it easy to analyse one set of target colours, as well as finding obstacles and localising the robot. Blob features are extracted and organised according to their size, and the position and radius of each recorded. For the targets or obstacles the largest target found is set to be the base or home plate, and the smaller ones the targets and/or obstacles depending on the state of the program. The robot is localised according to two green blobs placed in such a manner on the robot that the line between the two centre points on the blobs can be used to find the pose of the robot.

4.2

Navigation

The navigation solution for the system is obtained by fusing the perception pose observation  ,   with a prediction from the vehicle wheel encoders  ,  . Each predicted pose estimate is obtained by polling the vehicle encoders, and the encoders output the change in forward position Δ and the change in angular position Δ since the previous reading.

The pose prediction can then be determined by:   =   − 1 + Δ

  =   − 1 + Δ   − 1

  =   − 1 + Δ   − 1

(1)

To obtain the vehicle pose, these estimates are combined with a low pass filter, using:       =   + 1 −   

   = !  + 1 − ! 

(2)

Here, the α coefficient specifies the linear weightings of the predicted and observed pose estimates, and has been set based on test results presented in the following section of this paper. When vision-based observations are not available, α is set to zero, such that the pose estimate is purely based on that predicted by the vehicle encoders. This enables the vehicle pose to be estimated even when the vehicle is out of visual range of the camera or the camera malfunctions.

4.3

Guidance and Control

A number of sub-states have been defined within the guidance subsystem to facilitate guidance and control operations. The mission of the robot is subdivided into a number of smaller tasks, each consisting of a start position  ,   and goal position $ , $ . At the start point, the vehicle is in the rotate state, rotating on the spot to face the goal point.

Figure 8: Potential field path surfaces (top) and contours (bottom) for two obstacles (left), with a local minimum (centre) and with local minima avoidance (right) This is achieved by rotating the vehicle at a constant velocity of 150 mm/sec based on the heading error of the vehicle pose: +, (+-

 = tan() *.

, (.-

/ − 

 0 0, direction = 89:;

 < 0, direction = =>?;

(3)

Once the heading error has a magnitude of less than A/90 radians, the guidance state is set to goto. The path planning and path following operations for this state are outlined here. 4.3.1 Path Planning and Obstacle Avoidance At any point in the goto state, all objects apart from the current target / bin pair are considered as obstacles. The vehicle has a radius of ~175mm and the bins have a radius of ~75mm. Thus, for a point model of the vehicle in configuration space, the obstacles can be modelled as circles with radii of 250mm. Safe trajectories are generated for the vehicle through the obstacle field using a heuristic potential field path planning approach. A path is planned each time the vehicle enters a goto state, and as such, the system assumes obstacles are stationary for the duration of current state. A positive parabolic potential well is generated at the goal

point, and the obstacles are modelled by positive Gaussian potentials. The parabolic potential is advantageous for the goal since it propels the path towards the goal at any distance, while Gaussians are useful for obstacles since they can be scaled and normalised to negate their effect at certain distances from the obstacle. This means that the potential function can be a continuous analytical expression, rather than having to manually set the field to zero outside the distance of influence of an obstacle, as in [15] . The magnitudes of the goal potential and obstacle potentials are scaled to modify their effect on the generated path. The final potential field is parameterised as follows: N

N

D,  = GOALIJKLM   − $ +  − $  + OBSIJKLM ∑` exp

W

W

(*.(.UV  X+(+UV  / T _ YZI[\]^

(4)

The scale factors here determine the relative magnitudes of the goal and obstacles potentials, while the normalisation factor determines the width of the potential (and consequently its effect over a distance). From each path point, the next path point is determined by the gradient descent method, propagating the path along the direction of the negative 2D gradient: ∆ = −

cd.,+ e.

, ∆ = −

ef.,+ e+

(5)

The problem of local minima is a well-documented downfall of the potential field approach to path planning. Numerous methods have been prescribed to resolve this issue, including mathematical techniques to regenerate a field without local minima, or escape algorithms to propel the path away from local minima. Local minima avoidance has been implemented but has not been integrated with the current system. The method implemented here employs a virtual obstacle at the robot’s position when it finds itself in local minima [19] . The virtual obstacle field is another Gaussian, but has lower scale and normalisation factors than the obstacles, such that it represents a flat, broader peak. This is necessary; if the virtual obstacle is narrow and has a larger magnitude, there will be situations where the path will be propelled directly over the obstacle peak [19] . The path planning implementation is shown in Figure 8. With GOALSCALE, OBSSCALE and OBSNORM set at 0.4, 1 and 0.05 respectively the generated path safely avoids all obstacles in configuration space (indicated in red). 4.3.2 Path Following A pure pursuit guidance law [17] is applied to follow the generated path. This method utilises a constant lookahead distance 8 from the vehicle to a point on the path ahead (look-ahead point), and sets the vehicle curvature to turn onto this point.

k = ==

With a path point (x,y) relative to the vehicle frame, and the vehicle position as shown in Figure 9, it is possible to determine the radius of the turn required to move the vehicle onto the look-ahead point:

==

N.

(7)

k =  − ;s() 

+(+t .(.t



(8)

Thus, at each point in time, the generated path is searched to find the look-ahead point , , based on distance 8, and the required turning radius is obtained from the above equations. With a constant look-ahead distance, the vehicle turns in towards the path and then follows the path smoothly. The look-ahead distance can be tuned to directly affect the path following characteristics of the vehicle. With a lower look-ahead distance, the vehicle follows the path more closely, but this requires more aggressive turning and greater control effort. Conversely, a larger look-ahead distance yields a smoother vehicle trajectory, but the path is not accurately followed. If the goal point is within this fixed look-ahead distance, then the goal point is used as the look-ahead point, to ensure the vehicle passes over the goal.

Communications

As previously stated a direct serial RS232 connection was used to communicate from a laptop to the iRobot. This two way communication was able to relay the required serial control commands to the robot and receive data from the robot.

Figure 9: Geometry of the Pure Pursuit algorithm [17]

iW

Nlmn opqq

This error angle is the heading angle to the look-ahead point in the vehicle frame. In other words, it is the difference between the vehicle heading and the lookahead heading:

4.4

 N + hN = = N ,

i

The vehicle is controlled by commanding a drive velocity and a turning radius, which is directly mapped to the vehicle’s differential drive system. By employing the pure pursuit algorithm, the turning radius is directly determined from the look-ahead point, and this simplifies the control process. The vehicle velocity is set constant at 250 mm/s.

θerr

 N +  N = 8 N,

i

.

==+h (6)

For a curved path, it is easier to work with the error angle:

Vehicle commands are in the form of 8-bit words sent over a serial RS232 connection. A generic initialisation sequence is sent to the vehicle to enable user control. The motion commands are specified with a 5-byte sequence: vwxyz, yz{_}, yz{_{ , w~_}, w~_{ The first byte specifies the drive command, the next two bytes denote the velocity in mm/sec, and the final two bytes represent the radius in mm. The velocity and radius are signed, allowing for forward and backward velocities, and both left and right turns.

Blob Detection Algorithm Performance

Vehicle encoder readings are obtained synchronously sy by sending one byte at regular intervals in the program flow. Once this byte is sent,, triggering encoder readings readings, the distance and angle measurements are read in as two byte words from the serial connection.

3 Blobs 3%

A Bluetooth module has also been implemented but integration with the system has not been completed at this stage. The he Bluetooth module on the AVR board has been found to have interfacing problems where the wrong commands are re sent to the robot or incorrect signals are received from the encoders. With time this will need to be corrected however for the aim and development stage of this experiment a direct line of communication is adequate.

5

Perception

Usingg proven openCV colour segmentation and blob extraction algorithms helped to minimise problems or errors in the code for the perception module, however the manner in which we combined techniques did need some analyse to check the results gained were accurate accura and reliable. Using dilation and erosion algorithms changed the shape of the detected features from their true representation. The amount of change can be seen in Table 1. Table 1: Effect of Erosion andd Dilation on Parameters

Average Delta Average Value Percentage Difference

2 Blobs 82%

Figure 10:: Pie chart on the reliability and accuracy of the blob detections when searching for the two blue features.

Results

The key test results for each subsystem are detailed below.

5.1

1 Blob 15%

Area

x position

y position

66.00

2.00

1.00

5.2

Navigation, Guidance and Control

The navigation, navigation and control results are combined, because a different navigation solution directly affects the path following characteristics of the vehicle, and its trajectory changes. Testing for these subsystems was performed with constant target, bin and home positions for consistency. The α value used in the navigation low-pass low algorithm was altered to observe its effect on the vehicle trajectory. The generated First, the path planning ing results have been showcased in Figure 11. These have been superimposed over a snapshot of the layout to indicate the actual target, bin and home positions.

358.13 18.43%

Once the colour channels had been filtered and changed to a binary representation the blob extraction algorithm was applied. According to the inputted image the blob extraction could detect false positives and miss positive readings.. This error was minimised by experimenting with the threshold value, which represented the smallest number of pixels that the algorithm would wou classify as a feature. The performance of the blob extraction algorithm and the detection as a whole can be seen in Figure 10. Figure 11 Planned paths for the four successive successiv trials

Figure 12: Vehicle trajectory for α = 0.1(bottom left), α = 0.2 (bottom right), α = 0.5 (top left), α = 0.9 (top right) The results obtained showed inconsistencies, and the generated path varied dramatically for two of the trial runs (α = 0.5 and α = 0.9). While the path planning itself is independent of α, it is believed that other factors (discussed in the next section) were responsible for these anomalies. All four trials were successful. On every occasion, the vehicle successfully lifted the targets and deposited them onto the corresponding ‘bins’ before proceeding to the vehicle home. However, during the second two trials, the vehicle trajectories were adversely affected by the incorrect planned paths and oscillated significantly about the planned path. The resulting trajectories for the four trials are shown in Figure 12. Also shown in Figure 12 are the navigation position estimates obtained, based on the vehicle encoder measurements (predicted, shown in blue), vision measurements (observed, shown in green) and fused pose estimate (updated, shown by the red line). The corresponding heading estimates are presented in Figure 13. The estimates have been made continuous to eliminate oscillations between ± 180°, enabling the results to be interpreted more clearly.

Figure 13: Navigation heading estimates for α = 0.1 (above) and α = 0.2 (below)

6

Discussion

Using vision as our perception method was an adequate tool for our experimental setup, and colour segmentation and blob extraction was found to be a versatile and sensible way to extract features from our arena. From a single original BGR image, certain key features were extracted, and this involved funnelling the information through various control filters to leave the desired information behind. Doing this means some information could be lost, but the following results show that the information lost was inconsequential in that the final result was adequate for the navigation, guidance and control subsystems to function correctly. By filtering the HSV image and applying erosion and dilation algorithms information about the blobs was altered, as shown in Table 1. The effect on the Cartesian coordinates of the targets was minimal (less than 2 pixels, as indicated in Table 1) and thus dilation and erosion has minimal effect on the performance of the detection of the targets position. The change in area was much more significant, however beyond differentiating the biggest from smallest, this information was not poignant, and assuming this difference was roughly the same for different sized objects, it would not alter their size rankings. The change in area is however important in calibration procedure however the percentage change was minimised by using a large calibration area. The blob extraction was a verifiable way to extract the features. False positive readings were detected 3% of the time, and this occurred when a noisy signal was large enough to be considered as a blob. This caused inconsistencies in the path planning section if the noisy blob signal was bigger than the real target blob, as this false signal would have been labelled as the next target. The 15% of the time where only 1 blob was detected was expected, as this represented the stages where the robot had collected the target, effectively blocking it from the camera’s view, and once the target had been dropped off on top of the same coloured bin. With respect to the vehicle trajectories, the path planning system yielded mixed results. The generated paths were successfully able to manoeuvre around the blue bin in all four trials. However, the two latter trials produced some erroneous path segments. Upon closer inspection of the path points generated, it is evident that the sharp deviations along the path segments are due to outlier points, but the entire path segments are not fully complete.

Figure 14: Erroneous path planning segments This anomaly could be the result of: • Software errors in the path planning system • False positives in the vision observation suggesting a target is present at a different point. This could easily be caused by interference from the vehicle tether. The local minima avoidance method applied needs further work before it can be applied vehicle system. Realistically, more vigorous required with different obstacle types before ascertained to work for all situations.

here also to a real testing is it can be

The navigation solution appears reasonable, with both predicted (encoder-based) and observed (vision-based) pose estimates yielding good results. However, the software system is not currently threaded, which means that the same sampling rate is the same for both encoder and vision measurements. Realistically, multiple encoder measurements should be available for each observation, so the predicted path would be propagated forward at each update point. With only one prediction for each observation, the navigation solution is degraded. Additionally, from Figure 12 we can observe that the measurements are fairly spaced, suggesting that the sampling rates for navigation are quite poor. Incorporating multi-threading into the system would enhance its performance in both aspects here. It would enable faster prediction measurements, since these could be obtained in parallel with the time-consuming vision measurements. With regards to data fusion, the navigation filter is far more effective at low values of α. With large α values, the vision observation, which is usually further away from the planned path, is more heavily weighted. With the pure pursuit algorithm, this makes the vehicle steer more sharply, and the vehicle overshoots the path to a much greater extent.

The guidance and control aspects are generally strong, with the vehicle successfully navigating the waypoints specified. In particular, by rotating the vehicle on the spot at each path segment, the vehicle can change direction sharply, and there is less path overshoot than if it were to move continuously onto the next path segment. This is clearly evident in the α = 0.1 and α = 0.2 plots, but less so for the other two trials, where a lack of consistency is apparent. The path following algorithm is sufficient, but produces some unnecessary oscillation about the path as seen in Figure 12, and represented by the oscillations in Figure 13. This sort of behaviour is uncharacteristic for the pure pursuit algorithm. In cases where the lookahead-distance is too low, the vehicle turns sharply onto the path and may oscillate slightly, but these oscillations occur over a relatively large distance and are unusual. It is likely that this issue is a result of the poor sampling rate for the system. The magnitude of vision processing required means the navigation and guidance aspects are slower than desirable, and the system cannot rapidly be controlled. Multi-threading the system would again have an impact here.

7

Conclusion and Future Work

In this simplified implementation, the system was successful in locating and retrieving the colour targets across a number of trials. However, on some trials it still exhibited some inconsistent behaviour, and while the system was still successful, this contributed to less desirable results. Thus, the system needs to be further developed for consistency, in a number of proposed areas: • The errors in the path planning system need to be rectified. • Multi-threading needs to be incorporated to improve the navigation estimate and the controllability of the vehicle. • More analysis needs to be performed on the guidance aspects, to determine the optimal lookahead distance for this application. • Bluetooth communications needs to be implemented to eliminate dependence on the vehicle tether, which is unrealistic and can occasionally interfere with vision observations. Once the simplified system is complete and reliable, further steps will be needed in developing a system that better models an aerial / ground co-operative pair. These include: • Mounting the camera on a moving gimbal to simulate UAV motion. • Implementing dynamic obstacles avoidance as would be required for moving obstacles in the environment. • Employing the algorithms on a larger UGV that could be realistically used in a disaster scenario.







Implementing a local perception system for the UGV to supplement the coarse data provided by the UAV. Applying a more robust navigation filter such as an Extended Kalman Filter, as the vision observations would be less reliable from a UAV than from a stationary source. Replacing the electromagnet hardware with a more realistic mechanism for retrieving survivors in a disaster scenario.

References [1] Phan, C., and Liu, H. H. T., “A Cooperative UAV/UGV Platform for Wildfire Detection and Fighting,” 7th International Conference on Systems Simulation and Scientific Computing, 2008 [2] Grocholsky, B., Keller, J., Kumar, V., Pappas, G., “Cooperative air and ground surveillance,” IEE Robotics & Automation Magazine, Vol. 13, Issue 3, pp. 16-25, 2006. [3] Richard T. Vaughan, Gaurav S. Sukhatme, Javi Mesa-Martinez, and James F. Montgomery, "Fly spy: lightweight localization and target tracking for cooperating ground and air robots," In Proceedings of the International Symposium on Distributed Autonomous Robotic Systems, Knoxville, Tennessee, Oct 2000. [4] Grocholsky, B., Bayraktar, S., Kumar, V., and Pappas, G. “UAV and UGV collaboration for active ground feature search and localization.” In Proc. of the AIAA 3rd Unmanned Unlimited Technical Conference, 2004. [5] D.Comaniciu and P.Meer, “Robust analysis of feature spaces: Color image segmentation," IEEE Conference on Computer Vision and Pattern Recognition, pp. 750 - 755, 1997. [6] W.Skarbek and A.Koschan, “Colour image segmentation - a survey,” Technical report, Technical University of Berlin, 1994. [7] J.L.Baker, D.Campbell, and A.Bodnarova, “Colour image segmentation using optimal fuzzy clustering," IASTED Artificial Intelligence and Soft Computing, pp. 63 – 68, 2003. [8] J.L.Baker, D.Campbell, A.Bodnarova, and V.Chandran, “Hue-intensity segmentation for stereo correspondence," IASTED Robotics Applications, pp. 195 – 200, 2003. [9] Ohta, Y.I.; Kanade, T.; and Sakai, T., "Color Information for Region Segmentation", Computer

Graphics and Image Processing, 13, pp.222-241, 1980. [10]

Fu Chang, Chun-Jen Chan, Chi-Jen Lu. “A linear-time component-labeling algorithm using contour tracing technique”. Computer Vision and Image Understanding, September 2003.

[11]

Sonka, M., Hlavac, V., Boyle, R.: “Image Processing, Analysis and Machine Vision.” PWS Publishing, New York 1999

[12]

A. Tsalatsanis & K. Valavanis & N. Tsourveloudis “Mobile Robot Navigation Using Sonar and Range Measurements from Uncalibrated Cameras”. Journal of Intelligent and Robotic Systems, Vol. 48, Issue 2, pp. 253-284, 2007.

[13]

Sahin, E., Gaudiano, P.: “Mobile Robot Range Sensing Through Visual Looming”. In: Proceedings of IEEE ISIC, pp. 370–375, September 1998

[14]

Nelson, W., “Continuous-curvature paths for autonomous vehicles,” IEEE International Conference on Robotics and Automation, 1989.

[15]

Khatib, O., “Real-Time Obstacle Avoidance for Manipulators and Mobile Robots,” The International Journal of Robotics Research, Vol. 5, No. 1, pp. 9098, 1986.

[16]

Mellon, I. C., Stentz, A., “Optimal and efficient path planning for unknown and dynamic environments,” International Journal of Robotics and Automation, 1995.

[17]

Coulter, R. C., “Implementation of the Pure Pursuit Path Tracking Algorithm,” Technical Report, Robotics Institute, Carnegie Mellon University, 1992.

[18]

Pham, H.N., “A Comprehensive Architecture for the Cooperative Guidance and Control of Autonomous Ground and Air Vehicles,” Australian Centre for Field Robotics, University of Sydney, 2007.

[19]

Chengqing, L., Hang, M., Krishnan, H., Yong, L. S., “Virtual Obstacle Concept for Local-minimumrecovery in Potential-field Based Navigation,” Proceedings of the 2000 IEEE International Conference on Robotics & Automation, 2000.

Suggest Documents