Proceedings of the 2004 IEEE International Conference on Robotics & Automation New Orleans, LA • April 2004

Optimized Motion Strategies for Cooperative Localization of Mobile Robots Nikolas Trawny∗

Timothy Barfoot∗†

Institute for Flight Mechanics and Control University of Stuttgart, Germany [email protected]

Controls and Analysis MD Robotics, Canada, [email protected]

Abstract— This paper presents an approach to optimizing entire trajectories for a group of mobile robots that use one another as localization beacons. The cost function we seek to optimize is a measure of localization uncertainty (as opposed to distance travelled or time). Our initial findings show that, for example, it is possible to improve on the intuitive equilateraltriangle formation for three robots.

I. I NTRODUCTION Multiple robot systems have been proposed for a variety of applications including space exploration, search and rescue, military surveillance, and hazardous cleanup. Common to all these scenarios is the need for robots to determine where they are at all times, often using onboard sensors. The presence of multiple robots, in fact, provides a unique opportunity for localization as the robots may use one another as beacons. This may provide two advantages over using natural landmarks. First, artificial beacons can be more easily segmented from the general scene than natural landmarks, and second, the correspondence problem can be trivially solved by applying unique identifiers to each robot (e.g., colour, symbol, frequency). Also, for a fixed group size, the number of beacons does not increase. However, if all the robots eventually move, the error in localization will not remain bounded. This issue could be resolved by several techniques. In this paper we address the question of what the best trajectories are for such a group of robots to follow, in order to obtain the best localization information possible. Intuitively, some configurations are better than others when it comes to localization. Co-linear situations, for example, can be problematic. The reason some trajectories are better than others is because the system is non-linear, implying that sensor noise (and consequently information gain) is dependent on the system state. As a simple example, a camera pointing in one direction, φ1 , will experience different xy noise correlation than one rotated to a different direction, φ2 . Recognizing that noise depends on the state implies that some states are better than others in terms of localization uncertainty. For systems, such as mobile robots, that move, the entire trajectory will affect the amount of noise received by the sensors. As such, this paper seeks to optimize actions (trajectories) with respect to noise. ∗ Work

carried out while at the U. of Toronto Inst. for Aerospace Studies. author.

† Corresponding

0-7803-8232-3/04/$17.00 ©2004 IEEE

II. L ITERATURE R EVIEW This review focusses primarily on cooperative localization of mobile robots, with emphasis on those approaches that address minimizing uncertainty through choice of actions. One popular approach to cooperative robot localization is to use a mover-observer strategy, wherein two subgroups are employed, a stationary one and a moving one [1] [2] [3] [4] [5]. The measurements are then used to correct the odometry error accumulated by the moving rovers. In some cases, odometry data is discarded and localization relies solely on observations by the stationary robots. In this context, Kurazume [3] introduced the notion of regarding rovers as “portable landmarks”. While the mover-observer approach has proven successful, it slows down overall speed, and requires the rovers to stay within visible range at all times. Moreover, if no environmental information is taken into account, measuring the other robots’ positions will not resolve the unbounded growth of errors inherent to relative localization. Another approach is to allow all the robots to move at the same time. As an example of this strategy, the extended Kalman filter (EKF) approach to robot localization has been applied to cooperative localization by Roumeliotis and Bekey [6]. Their distributed approach allows a robot to store sensor information when not in contact with the group and to incorporate it whenever encounters occur. The motion model of the rovers ensures propagation of position estimate and associated uncertainty when the rover cannot observe any other rover, as well as consistent data fusion in case of a relative measurement. Thus, this framework enables the group of rovers to move continuously without having to be in constant visual range. Fox et al. [7] apply the technique of Monte Carlo Localization (MCL) to a multi-rover scenario. They assume independence of the individual robot’s pose estimates, resulting in a factored representation of the probability distributions. Again, only when the robots detect each other is information transferred from one distribution to the other. Experiments with cooperative MCL have clearly shown the increased accuracy when using multiple rovers instead of just one. Rekleitis et al. [8] also use the MCL approach for cooperative localization. They study the influence of different group trajectories on the accuracy of cooperative positioning.

1027

They find experimental evidence for a randomized moving strategy being superior to a deterministic robot formation, where the robots start in a single line and move abreast one at a time. The authors suggest that there might exist even better deterministic strategies but admit they might be difficult to compute with growing group size. Their research shows that collaborative localization error decreases with an increasing number of rovers. Grabowski et al. [9] have developed the Millibots, a group of small, heterogeneous, modular robots for mapping and exploration. The Millibots are equipped with an omnidirectional ultrasonic transducer that allows ranging between all rovers. They perform cooperative localization using a maximum likelihood estimator in order to build an occupancy grid map. In the context of this project, Grabowski et al. [10] comment on the optimality of the rovers’ formation geometry, i.e., the question of how a group of rovers should be spatially distributed in order to achieve good localization results from mutual range measurements. This is precisely the problem under investigation in the current paper. In another paper connected to the Millibot project, NavarroSerment et al. [2] look at an optimal motion strategy to cover larger distances in a group. In an approach termed ‘leapfrogging’, three rovers serve as fixed beacons, while the rest of the group is free to move around in the surrounding area. The moving robots position themselves at the frontier of the region covered by the beacons and the roles are exchanged, allowing the group to move forward. For the moving rovers, position estimation is accomplished by means of an EKF. The positioning of the beacon landmarks is accomplished by a more accurate maximum likelihood technique. As the beacons remain stationary for the next segment of the group motion, their position estimate is not affected by process noise. The paper claims that the localization algorithm is most accurate when the beacons are at the vertices of an equilateral triangle. The moving strategy then consists of covering the distance by ‘leap-frogging’ along a chain of triangles. It is mentioned that several parameters should affect the localization accuracy including the number of leaps, the shape of the leap-frogging pattern and the size of each leap. The characterization of these dependencies is still subject of ongoing research. Kurazume and Hirose [11] investigate optimal motion strategies for a cooperative positioning system. By numerically minimizing a weighted least squares problem for the covariance of the rovers, they find three different promising moving configurations. One consists in having the two child robots move abreast to the parent robot, the second in having them move one in front and one behind the parent, and the third in having the rovers move in a fixed triangular shape. The optimization is carried out for travelling a straight path of 1 km in steps of 10 m. However, Kurazume and Hirose do not use a motion model to fuse odometry data with their relative pose measurements. Our current work shows that a static formation is not optimal due to the dynamic nature of uncertainty in the system. Feder et al. [12] present an adaptive navigation and mapping

strategy for the single robot case. They use an EKF-based SLAM-algorithm, in which they determine the next command for their rover by minimizing the uncertainty after this step. As criterion, they use the sum of the areas of the individual error ellipses of the rover and the mapped features. This approach balances the gain of information by a new measurement and the loss of information by moving (odometry noise). They verify their theoretical findings by in-air sonar experiments and underwater sonar experiments. The performance of the robots in localization and mapping is shown to be superior to straightline and random motion. Being a local method that considers only the next action of the robot at each cycle, it is inferior to a global adaptive navigation algorithm. However, a global strategy would incur a much bigger action space for which computationally efficient search methods would have to be found. The authors state that integration of adaptive navigation into global path planning would be an interesting topic of future research. III. T HE M ODEL In this paper, we will use the classic EKF approach to robot localization. A single monolithic filter will be employed for the entire group of robots. We make no attempt to distribute the filter across robots, but this could be done if desired [6]. We require both a motion model and an observation model. Let the £ state of robot¤rT at time-step k be given by the usual xrk = xrk yrk φrk . We assume each robot is subject to the classic nonholonomic constraint such that our discrete-time motion model [13] for robot r may be given by ¡ ¢ xrk+1 = fr xrk , urk , vrk , xrk + ∆T Φrk (urk + vrk ) (1) where

Φrk

 ¡ ¢ cos¡ φrk ¢ =  sin φrk 0

 ¸ · ¸ · 0 V rk δVrk  , vrk = 0 , urk = ωrk δωrk 1

and ∆T is the time-step. Vrk and ωrk represent the openloop translational and rotational speeds, corrupted by additive, white, zero-mean, Gaussian noise δVr and δωr , with covariance · 2 ¸ ¤ £ σ 0 Qr = E vr vrT = δVr (2) 2 0 σδω r Control inputs or odometry measurements can be used for ur interchangeably. In practice, odometry information might be preferred since it more accurately reflects the actual robot motion [14]. In this case, odometry data is sampled at intervals ∆T . The Jacobian of the motion model with respect to the state, ˆrk (the state estimate), ur = urk , and xr , evaluated at xr = x vr = 0, will be denoted Frk and is given by ¡ ¢  1 0 −∆T Vrk sin φˆrk ¡ ¢ Frk = 0 1 +∆T Vrk cos φˆrk  (3) 0 0 1 The Jacobian of the motion model with respect to the noise, ˆrk (the state estimate), ur = urk , and vr , evaluated at xr = x

1028

T

T

det(H H) 10 8

T

det(H H) 1.5

det(H H) 2.2

1.5

2.2

Landmark

0.9 2

Optimal Region

6

0.8

4

0.7

2

0.6

1

2

1

Landmark Optimal Regions

1.8

1.6

0.5

1.8

0.5

1.6

Optimal Regions

1.4

1.4

Landmark 0

0.5

Landmark

0

1.2

−2

0.4

−4

0.3

0.8

−6

0.2

0.6

−8

0.1

0

1.2

1

−0.5

Landmark

Landmark

1

−0.5

Landmark 0.8

Landmark

−10 −10

0.6

−1

−1 0.4

0.4

0

−5

0

5

10

−1.5 −1.5

0.2

−1

−0.5

0

0.5

1

1.5

−1.5 −1.5

−1

−0.5

0

0.5

1

1.5

Fig. 1. (left) Contours showing the relative value of localization based on range measurements to two landmarks, throughout the plane. The locus of optimal points is a circle with the two landmarks at opposite ends of the diameter. (middle) Similar plot with three landmarks on the vertices of an equilateral triangle. Here the locus of optimal points is again a circle plus its center point. (right) Similar plot with three landmarks on the vertices of a scalene triangle. Here the circle of optimal points collapses to a single point.

vr = 0, will be denoted Grk and is given by   ¡ ¢ cos φˆrk 0 ¢ ¡ Grk = ∆T  sin φˆrk 0 0 1

(4)

motion ¤ model for the entire system state, x = £ Our T xT1 · · · xTn , is simply a block-diagonal construction of the individual robot quantities as follows: Fk Gk

= diag {F1k , . . . , Fnk } = diag {G1 k , . . . , Gn k }

(5)

Q = diag {Q1 , . . . , Qn } For the observation model, we will assume that each robot measures the range to each of the other robots (but not to itself). In general one could also measure the bearing to and heading of each of the other robots. The range from robot r to robot s is given by p (6) ρrs = (xs − xr )2 + (ys − yr )2

The measurement, for robot 1, z1k , is given by z1k = h1 (xk ) + w1k

(7)

where xk is the global state of the system, w1k is additive white, zero-mean Gaussian noise and h1 is the observation model, for robot 1, given by ¤T £ (8) h1 (xk ) = ρ12k ρ13k · · · ρ1nk The variance is assumed the same for each range measurement, independent of the actual distance measured [8]. The covariance matrix associated with the noise is given by ¤ £ (9) R1 = E w1 w1T = σρ2 I

where I is the identity matrix. The Jacobian of the observation model, h1 (x) , with respect to the state, x, evaluated at x = x ˆk (the state estimate) and

wr = 0, will be denoted H1 k and is given by  H12 −H12 0 ... 0 H13 0 −H ... 0 13  H1 k =  . . . . .. .. ..  .. . .. H1n

0

0

...



0 0 .. .

0 −H1n

   

(10)

where Hrs

¯ h ∂ρrs ¯¯ xr − xˆsρˆ−ˆ , = rs ∂xr ¯x=ˆxk

yr − yˆsρˆ−ˆ rs

0

i

(11)

and the hatted quantities are based on the state estimate, x ˆk . Although we have worked out the example for robot 1, the procedure is very similar for the other robots. The global observation model, h, is then given by £ ¤T h = h1 T · · · hn T (12)

We can also construct the Jacobian of the global observation model, h, with respect to the global state, x. It is denoted Hk , and can be computed as ¤T £ (13) Hk = H1 Tk H2 Tk · · · Hn Tk

The global covariance matrix is simply R = σρ2 I as all the individual range measurements are assumed to be statistically independent. Extended Kalman filtering normally requires that we keep track of the state estimate, x ˆ, as well as an associated covariance matrix, P, which accounts for the confidence we have in each component of x ˆ. Thus, the classic EKF equations provide updates to both x ˆ and P. As we will see in the next section, we will only require the updates for P in this paper. When the rovers move but do not take measurements, the covariance matrix is updated according to: Pk+1 = Fk Pk FTk + Gk QGTk

(14)

When the rovers do not move but instead take measurements, the covariance matrix is updated according to:

1029

−1 T −1 P−1 Hk k+1 = Pk + Hk R

(15)

Rover Movement in xy−plane.

Rover Movement in xy−plane.

12

12

Development of Uncertainty 10

Development of Uncertainty 10

−16

10

−16

10

−18

−18

10

10 8

−20

y

6

−20

10

−22

10

6

−24

−22

10

−24

10

10

y

det(P)

10

det(P)

8

−26

−26

10

10

4

4

−28

−28

10

10

−30

−30

10

2

10

2

time

time

0

0 log (det(P)) at final destination = −25.9512

log (det(P)) at final destination = −15.9475

10

10

−2

0 x

2

−2

0 x

2

Fig. 2. (left) Development of uncertainty for three rovers during a 10m straight line movement (starting at the bottom and finishing at the top), no ranging measurements are performed. (right) Same trajectory but four ranging measurements are performed afterwards. The ellipses drawn around each robot represent the uncertainty in localization. These are constructed by projecting the covariance matrix, P, onto the xy-plane, for each robot.

where we have chosen to show the equations in inversecovariance form for succinctness. In practice, as we have done in our implementation, one might prefer to use the computationally-safer Joseph form. IV. O PTIMALITY To better understand what we mean by optimal sensing configurations, it is useful to consider a simplified situation with a reduced state vector, wherein a single robot is measuring ranges to a number of static landmarks (later these will be other robots). Figure 1 depicts this situation. These plots show contours of the relative ‘value’ of localizing based on range measurements to landmarks, from every point in the xy-plane, assuming the robot has no a priori knowledge of its location. For example, we can see that if a robot is co-linear with two landmarks, the measurement is of little value. Having no a priori knowledge implies that our initial covariance matrix is such that P−1 0 = 0. The covariance matrix after incorporating one set of range measurements will be given by (15) such that P−1 1

T −1 = P−1 H1 0 + H1 R T ∝ H1 H1

where we have used the fact that R ∝ I. The determinant of P1 provides a good measure of uncertainty as in this case it is proportional to the area of the one-standard-deviation error T ellipse. Since det(P−1 1 ) = 1/det(P1 ), the higher det(H1 H1 ) is, the less uncertainty there is in the measurement. It is tempting to try and look for analytical solutions to the more general problem of finding entire trajectories that minimize uncertainty. This indeed may be possible, but the problem is complicated by the inclusion of a priori knowledge (i.e., P−1 0 6= 0). Then the relative value plots of Figure 1 can look entirely different. Thus, even the simple case of a robot moving (along some arbitrary path) and then taking one set of measurements, is quite difficult to treat analytically. For this work we chose to use a numerical technique to optimize robot trajectories. Setting up the optimization problem is the subject of the next section.

V. T HE O PTIMIZATION P ROBLEM In this section we set up an optimization problem in which open-loop (noise-free) robot trajectories are the parameters and localization uncertainty is the objective function. To do so, we originally had planned to run the full EKF update equations for both x ˆ and P and apply the filter to a computer simulation of a mobile robot. In other words, noise would be simulated and would be slightly different each time, resulting in widely varying state and covariance estimates. We quickly found that in order to compute a repeatable measure of localization performance, a very large number of simulations would have to be averaged, for every set of open-loop control inputs. Our conclusion was that it would be computationally inefficient to proceed in this regard. Instead, we decided to take a different approach. Rather than using the state estimate, x ˆk , in the computation of the Jacobians, Fk , Gk , and Hk , we used the state, xk , that would be present in the absence of noise. This had the rather nice effect that for a given open-loop robot trajectory, the covariance matrix, P, updated deterministically. This is naturally an approximation but we reasoned that this case would represent something similar to an ensemble-average over all possible noisy cases. Futhermore, if a controller were used to track the open-loop trajectory, the approximation would hopefully be reasonable. This would be even more justifiable if we could find trajectories where the localization estimates were expected to be very good. On the basis of this premise, we proceeded to set up the optimization procedure as follows. A trajectory1 with m segments is specified by the open-loop control inputs £ ¤T U = UT1 UT2 . . . UTm (16) where each Uj is given by £ Uj = V1j ω1j V2j ω2j

...

V nj

ωnj

Tj

¤

(17)

Here, Vrj and ωrj specify the translational and rotational speed for rover r for segment j, and Tj denotes the time for which these open-loop control inputs are applied.

1030

1 It

is actually a trajectory for the entire group of robots.

Rover Movement in xy−plane.

Rover Movement in xy−plane.

12

12

Development of Uncertainty

10

Development of Uncertainty

10 −22

10

−22

10

8

8

−24

10

−24

y

−26

10

−26

10

−28

−28

10

4

det(P)

6 y

det(P)

10 6

10

4

−30

−30

10

10

2

2

time

time

0

0

log (det(P)) at final destination = −26.456

log (det(P)) at final destination = −25.4799

10

10

−2

0 x

−2

2

0 x

2

Fig. 3. (left) Initial guess for the equilateral triangle configuration: Four equally spaced segments. (right) Optimized trajectory for the equilateral triangle configuration with four path segments.

The objective function, C(U), we chose to optimize is given by C(U) = log(det(P))

(18)

where the covariance matrix, P, is the final one after having applied all the open-loop control inputs in U. More specifically, the evaluation of the cost function is carried out by way of the following procedure: 1) Specify U, the open-loop control inputs, for all robots and initial conditions for the covariance matrix, P0 , and the global state, x0 2) For each segment, j = 1 . . . m, in U, do the following: a) Use the open loop control inputs, Uj , and the motion model to compute the state of the system, xk (noise-free) to be used in the computation of all Jacobians. b) Let Pj− represent the covariance matrix after the robots have executed segment j, just before receiving a new range measurement. This is computed by repeatedly applying Pk+1 = Fk Pk FTk + Gk QGTk a total of Tj /∆T times. c) Let Pj represent the covariance matrix at the end of segment j, just after receiving the range measurement. This is computed from Pj = ¡ −1 ¢−1 Pj− + HTj R−1 Hj , where Hj is the observation Jacobian at the end of segment j. 3) Compute the cost, C = log(det(Pm )) In our implementation, we imposed the following constraints on the specification of U: ¯ Vr¯ ¯ Vr ¯ ¯ ¯ ¯ ωr ¯ ρrs

6 V µmax¶ V > ω min > ρmin

(19)

where Vmax is the maximum translational speed of a robot, (V /ω)min is the minimum radius of curvature of a robot trajectory, and ρmin is the minimum distance between robots, when ranging to one another. An additional constraint we imposed was that the final locations of robots would be specified (but not their orientations).

Using the above procedure to compute cost, C, given inputs, U, we then turned to a numerical optimizer to improve on the cost for an initial guess we provided for the inputs. The optimizer we used was fmincon in Matlab, which allows the inclusion of non-linear constraints. It is a gradient-based optimizer and thus the best it will do is converge to a local optimum of the attractor basin in which the initial guess resides. VI. R ESULTS AND D ISCUSSION Parameters for the noise covariance matrices, initial covariance matrix, and constraints were chosen to be representative of real mobile robots. We present results for two typical cases: Case I: Figure 3 (left) shows a typical initial guess for the open-loop (noise-free) trajectories for the group of robots. They begin in an equilateral triangle formation and advance straight ahead in four equal segments. After each segment a set of ranging measurements is performed. The equilateral triangle formation is already expected to be quite good in terms of localization. However, the optimizer found that the trajectories on the (right) of Figure 3 were better. The improvement is noticeable in the area of the error ellipses (one order of magnitude in det(Pm )), but it is not visually striking. Not portrayed in the figure is the fact that the correlation between rovers has been improved significantly. Case II: Another case is depicted in Figure 4. Here the initial and final configuration of the formation is such that the three rovers are co-linear (a poor configuration for localization). We initially chose the open-loop trajectories on the (left), wherein the robots proceed to their final locations before taking all four measurements. This, however, turned out to be a particular poor initial guess as the optimizer struggled to improve it at all. We later resorted to using the (middle) of Figure 4 as the initial guess, wherein the robots move from colinear to a triangle formation, move forward in this formation, and then return to the co-linear final configuration. This initial guess allowed the optimizer to come up with Figure 4 (right), which had a similar improvement to that of Case I. We are encouraged by the fact that our procedure did in fact improve our initial guesses for the open-loop trajectories. It is particularly interesting to find that the intuitively-appealing

1031

Rover Movement in xy−plane.

Rover Movement in xy−plane.

Rover Movement in xy−plane.

12

12

Development of Uncertainty 10

12

Development of Uncertainty

10

Development of Uncertainty

10

−16

10

−18

−18

10

10

−18

10 8

−20

−20

8

10

8

10

−20

6

−24

6

−24

10

y

y

10

−22

det(P)

−22

10

−22

10

−26

10

4

10 4

−28

10

−30

−30

−30

10

10

10

2

2

time

time

0

0

log (det(P)) at final destination = −25.1591 −2

2

log10(det(P)) at final destination = −26.259

10

10

0 x

time 0

log (det(P)) at final destination = −24.7447 −2

−28

10

10

−28

2

−24

10

−26

−26

10

4

10

y

6

det(P)

det(P)

10

0 x

2

−2

0 x

2

Fig. 4. (left) Development of uncertainty for three rovers when performing four relative distance measurements in a co-linear configuration at the end of a 10m straight path. (middle) Development of uncertainty for three rovers when performing four relative distance measurements. The rovers start in a co-linear configuration, but are brought into a triangular shape to increase information gain. (right) Optimized trajectory for the co-linear configuration with four path segments.

equilateral-triangle formation can be improved. It would have been positive if, for example, the initial guess of Figure 4 (left) could also have been improved. We feel the main reason for lack of success with this initial guess was our selection of a gradient-based numerical optimizer. Not only does this preclude the possibility of finding a global optimum, it became clear through our investigations that although all of our parameters in U were continuous, the cost function itself had some subtle discontinuities at the implementation level. These were primarily a result of using a numerical integration technique to propagate the motion model forwards in time. The optimizer struggled with these on occasion. Perhaps a non-gradient-based (global) approach, such as a genetic or simulated annealing technique might be more appropriate to this problem. Another difficult issue only briefly mentioned in our previous presentation, was the constraint that the robots had to end up in specific locations. We initially applied a penalty term to the cost function, proportional to the distance from the target location but later found that it was more elegant to automatically generate the final set of control inputs, Um , to meet this constraint. This, too, was problematic as we assumed constant control inputs for each segment, implying solutions could not always be found to end up at the final location. In this case, an additional Um+1 would be required. These implementation issues aside, a large question mark still remains in our approach, namely the assumption that we can optimize using Jacobians computed from noise-free trajectories. The next major step to justifying this assumption is to validate the optimized trajectories against a large number of trials where noise is present (preferably in hardware), to see if indeed these trajectories are superior. This, however, requires the inclusion of such issues as trajectory tracking and iterated EKFs. This validation is left for future work but we underscore its importance. VII. C ONCLUSION We have presented an approach to optimizing entire trajectories for a group of collaboratively localizing robots, with

the goal of minimizing the uncertainty in localization. Our initial findings are that it is worthwhile to try and optimize trajectories on this basis. However, the gradient-based local optimizer we chose was not found to be the most appropriate to the problem. We hope this initial investigation and formulation of the problem will provide impetus for further study of this exciting topic. R EFERENCES [1] H. Sugiyama, “A method for an autonomous mobile robot to recognize its position in the global coordinate system when building a map,” in Proceedings of the 1993 IEEE/RSJ Int. Conf. on Intelligent Robots and Systems, vol. 3, Yokohama, Japan, 1993, pp. 2186–2191. [2] L. Navarro-Serment, C. J. J. Paredis, and P. K. Khosla, “A beacon system for the localization of distributed robotic teams,” in Proceedings of the Int. Conf. on Field and Service Robotics, Pittsburgh, PA, Aug. 1999. [3] R. Kurazume, S. Nagata, and S. Hirose, “Cooperative positioning with multiple robots,” in Proceedings of the IEEE International Conference on Robotics and Automation, vol. 2, May 1994, pp. 1250–1257. [4] J. Hyams, M. W. Powell, and R. Murphy, “Cooperative navigation of micro–rovers using color segmentation,” in Proceedings of the IEEE Int. Symp. on Comp. Intell. in Robotics and Automation, 1999, pp. 195–201. [5] A. Howard and L. Kitchen, “Cooperative localisation and mapping,” in Proceedings of the 1999 Int. Conf. on Field and Service Robotics, 1999. [6] S. I. Roumeliotis and G. A. Bekey, “Distributed multirobot localization,” IEEE Trans. on Rob. and Autom., vol. 18, no. 5, pp. 781–795, Oct. 2002. [7] D. Fox, W. Burgard, H. Kruppa, and S. Thrun, “Collaborative multirobot localization,” in Proc. of the German Conference on AI (KI), 1999. [8] I. M. Rekleitis, G. Dudek, and E. E. Milios, “Multi-robot cooperative localization: a study of trade-offs between efficiency and accuracy,” in Proceedings of the 2002 IEEE/RSJ Int. Conf. on Intelligent Robots and Systems, vol. 3, Lausanne, Switzerland, Oct. 2002, pp. 2690–2695. [9] R. Grabowski, L. E. Navarro-Serment, C. J. J. Paredis, and P. K. Khosla, “Heterogeneous teams of modular robots for mapping and exploration,” Autonomous Robots, vol. 8, no. 3, pp. 293–308, 2000. [10] R. Grabowski and P. Khosla, “Localization techniques for a team of small robots,” in Proceedings of the IEEE/RSJ Int. Conf. on Intelligent Robots and Systems (IROS’01), vol. 2, October 2001, pp. 1067–1072. [11] R. Kurazume and S. Hirose, “Study on cooperative positioning system: optimum moving strategies for cps-iii,” in Proceedings of the IEEE Int. Conf. on Robotics and Automation, vol. 4, May 1998, pp. 2896–2903. [12] H. J. S. Feder, J. J. Leonard, and C. M. Smith, “Adaptive mobile robot navigation and mapping,” International Journal of Robotics Research, vol. 18, no. 7, pp. 650–668, July 1999. [13] R. Madhavan, K. Fregene, and L. E. Parker, “Distributed heterogeneous outdoor multi–robot localization,” in Proceedings of the IEEE Int. Conf. on Robotics and Automation, vol. 1, 2002, pp. 374–381. [14] S. Thrun, “Robotic mapping: A survey,” in Exploring Artificial Intelligence in the New Millenium, G. Lakemeyer and B. Nebel, Eds. San Francisco, CA: Morgan Kaufmann Publishers, 2003.

1032

Optimized Motion Strategies for Cooperative ...

rover, as well as consistent data fusion in case of a relative measurement. ... visual range. Fox et al. ... [12] present an adaptive navigation and mapping strategy ...

653KB Sizes 1 Downloads 295 Views

Recommend Documents

Cooperative Caching Strategies for Minimizing ...
objects caching strategies for minimizing content provisioning costs in networks with homogeneous and ... wireless networks to improve data access efficiency.

A Fast Algorithm For Rate Optimized Motion Estimation
uous motion field reduces the bit rate for differentially encoded motion vectors. Our motion ... In [3], we propose a rate-optimized motion estimation based on a “true” motion tracker. ..... ftp://bonde.nta.no/pub/tmn/software/, June 1996. 477.

A Fast Algorithm For Rate Optimized Motion Estimation
Abstract. Motion estimation is known to be the main bottleneck in real-time encoding applications, and the search for an effective motion estimation algorithm has ...

download Cooperative Learning and Strategies for ...
... classroom environments for students from preschool through high school. ... Second Edition, Online Cooperative Learning and Strategies for Inclusion: ...

Patient-Cooperative Control Strategies for Coordinated ...
support the subject in a patient-cooperative way during the training is introduced. .... In order to define support, an ideal reference trajec- tory is needed.

Patient-Cooperative Control Strategies for Coordinated ...
to use admittance control, a force/torque sensor is needed. Since there are ... filter are the velocities ˙qc in the joint space. The velocities ˙q in the joint space are subtracted from the reference velocities. jZr. -1. J. jD. jYc. Force/ Torque.

Parallel Evolutionary Optimized Pitching Motion Control ...
System (SAS) is designed to improve the stability ... A controller to stabilize F-16 aircraft flying ... this model, a pitching motion controller is designed for fast.

Kirby Motion for PJR
May 17, 2013 - and plugs for producing Kirby Sailboats, copies of the Construction Manual, ISAF Plaques, and. New ISAF ... Telephone: (203) 324-6155.

The Case for Cooperative Networking - CiteSeerX
1. The Case for Cooperative Networking. Venkata N. Padmanabhan. £. Kunwadee ... Efforts in this space have included file swapping services (e.g., Napster,.

The Case for Cooperative Networking - Semantic Scholar
tion among peers complements traditional client-server com- munication ... vided by the system, be it improved performance, greater robustness, or ... crowd on server performance. A. Where is the ... servers drawn from [21] was estimated using the Ne

Censoring for cooperative positioning
positions of anchor nodes and the cell phones indicate the positions of agents. ... Cooperative positioning is an emerging topic in wireless sensor networks and navigation. It ..... select the best links by receive censoring [using Algorithm 4.2]. 8:

Incremental Cooperative Diversity for Wireless ...
be used in cognitive wireless systems to mitigate interference and to improve spectrum .... the number of relays involved in the incremental phase is not fixed, i.e. ...

Energy-Efficient Protocol for Cooperative Networks - CiteSeerX
Apr 15, 2011 - model a cooperative transmission link in wireless networks as a transmitter cluster ... savings can be achieved for a grid topology, while for random node placement our ...... Comput., Pacific Grove, CA, Oct. 2006, pp. 814–818.

Deploying the BIG-IP System for WAN-Optimized ... - F5 Networks
Jun 11, 2013 - 11.4, 11.4.1, 11.5, 11.5.1, 11.6 (BIG-IP AAM must be licensed and provisioned) .... Associated TCP service port (445 is the default for CIFS):.

Evolutionary algorithms for optimized SDN controllers ...
Placement of virtual machines in a data center and placing Virtual Network Function or ... example optimizing consumption & global bandwidth simultaneously…

Evolutionary algorithms for optimized SDN controllers ...
Telco & cloud operators need to conform to SLA constraints negotiated with customers such as latency, reliability, downtime, affinity, response time or duplication ...

Social-optimized Win-win Resource Allocation for Self-organizing Cloud
Cloud computing offers scalable and on-demand virtualized resources as a utility service over the Internet with bypassed inter-operability constraints. With VM's ...

Deploying the BIG-IP System for WAN-Optimized ... - F5 Networks
Jun 11, 2013 - 11.4, 11.4.1, 11.5, 11.5.1, 11.6 (BIG-IP AAM must be licensed and provisioned). FTP .... Associated TCP service port (21 is the default for FTP):.

Optimized Gain Control for Single-Frequency ... - Semantic Scholar
amplify-and-forward single-frequency relay link in which loop interference from the relay transmit ... The authors are with the Department of Signal Processing and Acoustics,. Helsinki University of Technology, P.O. ... with the amplify-and-forward p

Deploying WAN-Optimized Acceleration for Replication ... - F5 Networks
Jun 11, 2013 - 11.4, 11.4.1, 11.5, 11.5.1, 11.6 (BIG-IP AAM must be licensed and .... On the Main tab, expand iApp, and then click Application Services. 3.

Deploying WAN-Optimized Acceleration for VMware ... - F5 Networks
Jun 11, 2013 - The iApp template acts as the single-point interface for building, managing, and monitoring this ... Using this guide to configure the App template ..... Any other products, services, or company names referenced herein may be ...