• No results found

Range-based Wireless Sensor Network Localization for Planetary Rovers

N/A
N/A
Protected

Academic year: 2021

Share "Range-based Wireless Sensor Network Localization for Planetary Rovers"

Copied!
54
0
0

Loading.... (view fulltext now)

Full text

(1)

Range-based Wireless Sensor Network Localization for Planetary Rovers

August Svensson

Space Engineering, master's level 2020

Luleå University of Technology

Department of Computer Science, Electrical and Space Engineering

(2)

Range-based Wireless Sensor Network Localization for

Planetary Rovers

Department of Computer Science, Electrical and Space Engineering

Master’s Thesis

Lule˚ a University of Technology

August Svensson

Examiner: Dr Johnny Ejemalm

External Supervisors: Michael Dille and Uland Wong

(3)

Abstract

Obstacles faced in planetary surface exploration require innovation in many areas, primarily that of robotics. To be able to study interesting ar- eas that are by current means hard to reach, such as steep slopes, ravines, caves and lava tubes, the surface vehicles of today need to be modified or augmented. One augmentation with such a goal is PHALANX (Pro- jectile Hordes for Advanced Long-term and Networked eXploration), a prototype system being developed at the NASA Ames Research Center.

PHALANX uses remote deployment of expendable sensor nodes from a lander or rover vehicle. This enables in-situ measurements in hard-to- reach areas with reduced risk to the rover. The deployed sensor nodes are equipped with capabilities to transmit data wirelessly back to the rover and to form a network with the rover and other nodes.

Knowledge of the location of deployed sensor nodes and the momentary location of the rover is greatly desired. PHALANX can be of aid in this aspect as well. With the addition of inter-node and rover-to-node range measurements, a range-based network SLAM (Simultaneous Localization and Mapping) system can be implemented for the rover to use while it is driving within the network. The resulting SLAM system in PHALANX shares characteristics with others in the SLAM literature, but with some additions that make it unique. One crucial addition is that the rover itself deploys the nodes. Another is the ability for the rover to more accurately localize deployed nodes by external sensing, such as by utilizing the rover cameras.

In this thesis, the SLAM of PHALANX is studied by means of com- puter simulation. The simulation software is created using real mission values and values resulting from testing of the PHALANX prototype hard- ware. An overview of issues that a SLAM solution has to face as present in the literature is given in the context of the PHALANX SLAM sys- tem, such as poor connectivity, and highly collinear placements of nodes.

The system performance and sensitivities are then investigated for the de- scribed issues, using predicted typical PHALANX application scenarios.

The results are presented as errors in estimated positions of the sensor

nodes and in the estimated position of the rover. I find that there are

relative sensitivities to the investigated parameters, but that in general

SLAM in PHALANX is fairly insensitive. This gives mission planners and

operators greater flexibility to prioritize other aspects important to the

mission at hand. The simulation software developed in this thesis work

also has the potential to be expanded on as a tool for mission planners to

prepare for specific mission scenarios using PHALANX.

(4)

Acknowledgements

I thank NASA and SNSA for my opportunity to participate in the NASA International Internship Project (I

2

).

I also want to heartily thank my mentors Michael Dille and Uland

Wong at the Intelligent Robotics Group at NASA Ames for their help,

advice and discussions throughout the work process.

(5)

Contents

1 Introduction 1

2 Formalization 5

2.1 SLAM: Simultaneous Localization and Mapping . . . . 5

2.2 The full SLAM problem . . . . 6

2.3 The online SLAM problem . . . . 7

2.3.1 Optimal estimation with the Kalman Filter . . . . 7

2.3.2 The Extended Kalman Filter . . . . 9

2.3.3 Alternatives to the EKF . . . . 12

2.3.4 The Particle Filter . . . . 12

2.4 Common issues faced in SLAM . . . . 13

2.5 Issues faced in range-only SLAM . . . . 14

2.5.1 Collinearity of landmarks . . . . 16

2.5.2 Rover trajectory . . . . 18

2.5.3 Wireless sensor networks . . . . 19

2.5.4 Articulation points . . . . 21

2.5.5 Anchor nodes . . . . 22

2.6 SLAM in PHALANX . . . . 22

2.6.1 Data association . . . . 23

2.6.2 Anchorization of nodes . . . . 23

2.6.3 Deployment of nodes . . . . 24

3 Implementing the Simulation Model 25 3.1 The System Model . . . . 26

3.1.1 The process model . . . . 26

3.1.2 Measurements and mutual localization . . . . 27

3.1.3 Process and measurement function Jacobians . . . . 28

3.1.4 Missing measurements . . . . 29

3.1.5 Deployment of sensor nodes . . . . 30

3.1.6 Anchorization . . . . 31

3.2 Evaluation metrics . . . . 31

4 Example scenarios 33 5 Results 34 5.1 Baseline . . . . 34

5.2 Anchorization . . . . 36

5.3 Collinear node-placements . . . . 38

5.4 Rover trajectory and collinearity . . . . 40

5.5 General trajectory strategies . . . . 41

5.6 Articulation points . . . . 43

6 Discussion 44 6.1 Discussion of results . . . . 44

6.2 Limitations of the simulation program . . . . 45

6.3 Future work . . . . 46

(6)

1 Introduction

Planetary rovers continue to play a major role in planetary exploration. They enable a range of science instruments not feasible for orbital sensing, such as sample extraction or analysis and in situ atmospheric measurements. However, the high mission costs result in them being operated in a very risk-averse man- ner. Frequently, scientific targets are located beyond obstacles such as steep slopes and rock formations and are therefore avoided. Many locations, such as lunar pits[23], and lunar or Martian lava tubes[3, 6] are not only difficult for rovers to maneuver, but severely limit return communication links.

(a) (b)

(a) a collapsed lava tube north of Arsia Mons on Mars, as seen from the Mars Orbiter Camera (image ID: R0800159). (b) a slope on

“Bloodstone Hill”, which was beyond the steepness comfort zone of Curiosity.[11] Image from the Left Navigation Camera onboard Curiosity, taken on Sol 2797 of its mission. (Credit: NASA/Jet Propulsion Laboratory, Caltech)

In response to this, a prototype system, PHALANX (Projectile Hordes for

Advanced Long-term and Networked eXploration), is under development at

NASA Ames Research Center[7]. It employs ranged deployments of wireless

sensor nodes: small sensor-equipped units meant to collect scientific data and

wirelessly transmit it back to the rover. The nodes can be equipped with in-

struments that measure gas composition, temperature, microscopic imagery and

even in-flight overhead imaging. Placed nodes can collect data over long time-

periods to measure ephemeral and dynamic effects, otherwise not tractable con-

sidering valuable rover mission time. Together nodes form a network, enabling

(7)

communication by relay over longer distances, around obstacles and along caves.

(a) (b)

(a) a prototype launcher in the Roverscape at NASA Ames, and (b) a prototype node projectile with a microscope payload

For the science data to be useful, their geographical locations need to be recorded. But without a convenient satellite positioning system (such as our earthly GPS), we have to establish these coordinates by some other means.

Localization means are limited given the size, shape and use-case of the sensor nodes. Considering the limitations, RF-transceivers are a good choice. They enable easy node-to-node measurements, make for trivial data association, allow to some extent measurements out of line-of-sight, all using minimal additional hardware.

With ranging RF-transceivers, it is possible to measure the distance between connected members of the formed network, be it node to node or rover to node.

The estimating or calculating of positions is called localization. Performing localization using distances between nodes or landmarks is called multilatera- tion[18].

Using only a few known positions and the measured ranges, the remaining po- sitions can thus be established by solving a system of equations. However, in reality, the availability and the accuracy of prior knowledge are often insufficient, and the range measurements are never exact. The solution to the localization problem is therefore in reality an estimate calculated by minimizing a cost func- tion, rather than a single solution from a system of equations.

Because the rover is part of the formed network, an opportunity also arises to

aid rover localization, commonly performed by a combination of dead-reckoning

and visual odometry.[13] The latter is an accurate and precise, although ex-

(8)

pensive computation, typically performed rather infrequently, except in specific high-precision slow-driving modes. The problem of localizing a moving robot or rover while simultaneously localizing (or mapping) surrounding landmarks, features or nodes, is known as simultaneous localization and mapping, or SLAM.

When it comes to range-based localization in wireless networks, performance is dependent on various qualities, such as node connectivity, measurement noise and network geometry. While measurement noise is hard to affect during the mission, with the ability to add sensor nodes rather flexibly and shape the network geometry, this becomes an interesting topic for mission planners and operators. Additionally, regarding the rover as a mobile node in the network, the path that it takes directly influences network geometry.

The required level of accuracy and precision varies by mission and situation.

Real-time rover localization, for example, is of heightened importance in poor terrain such as lunar regolith or soft soils where failure to detect slippage can result in mission failure if it gets irrecoverably embedded[2]. Subject to scien- tific demand, certain measurements taken from node sensors need more exact position estimates accompanying them.

In this thesis I investigate the performance and sensitivities of such a local- ization system using computer simulations, in regards to peculiarities of similar systems in the literature. In section 2, I introduce the reader to range-based localization and SLAM in the context of the PHALANX system. In section 3, I then describe the models used in the implementation of the simulation software.

In sections 4 and 5 I perform experiments using the implemented software and

present the results. Finally, in section 6, I discuss the results, the simulation

software and future work.

(9)

Annotation and Abbreviations

A quick list of abbreviations and mathematical notation conventions is included here for conveniency.

The general mathematical convention

All matrices are represented by capital letters. Some quantities are written as N or M , and the Jacobian operator as J , but context should make this dis- tinction clear.

Vectors are written with a bold font. Functions are written in non-bold font, regardless of their dimension.

Abbreviations

EKF - Extended Kalman Filter GPS - Global Positioning System IMU - Inertial measurement unit

NASA - National Aeronautics and Space Administration

PHALANX - Projectile Hordes for Advanced Long-term and Networked eXploration RF - Radio-frequency

RMSE - Root mean squared error RO-SLAM - Range-only SLAM

SLAM - Simultaneous Localization and Mapping

WSN - Wireless sensor network

(10)

2 Formalization

For rovers to perform their tasks effectively, they need to be able to navigate in their environment. This amounts to two tasks: creating and maintaining an accurate map of the surroundings, and accurately estimating one’s own position in relation to this map. In robotics this is referred to as simultaneous localization and mapping, or SLAM. In this section I describe SLAM generally, and more specifically to PHALANX: range-only and wireless sensor network SLAM. I introduce and describe common issues in these types of SLAM and how they relate to the PHALANX system.

2.1 SLAM: Simultaneous Localization and Mapping

The SLAM problem has a big presence in the field of robotics. It applies when- ever robots must navigate in an unknown or uncertain environment. To do so effectively, they must map their surroundings while also keeping track of their own position and bearing. The information available to the robot is at a minimum typically in the form of measurements and control input. Using measurements of quantities such as speed and direction to estimate position is known as dead reckoning or deduced reckoning. This is very computationally cheap, and is a legitimate strategy when traversing areas where there are no obstacles to avoid and that requires no mapping, such as wide open flat areas in between mapping objectives. However, this form of localization is very er- ror prone, as the errors are essentially free to accumulate. By incorporating measurements of the surroundings, the error can be constrained in relation to these surroundings. A map of the surroundings thus needs to be maintained to estimate the position of a robot in movement.

Figure 1: A robot is updating its position estimate using dead reckoning. The error grows (represented by the blue ellipses) as it drives and integrates its measurements.

There are many SLAM algorithms each with their own strengths and weak-

nesses. At a high level, they can be roughly divided into full SLAM and online

SLAM. Many prominent algorithms in the latter category use variations and

(11)

extensions of the Kalman Filter and the Particle Filter. These are known as state observers in control theory. The state of a system is a collection of quanti- ties typically relevant to the control of the system. In SLAM the state consists of the robot pose and the map. The role of the observer in a control system is to as accurately and precisely as possible estimate the current state given the information available through both measurements and control input.

Next I will briefly describe the full SLAM problem and some algorithms fit- ting this category. After that, I will describe the online SLAM problem in further detail, as the algorithm implemented later in this document falls under this category of SLAM.

2.2 The full SLAM problem

In the full (sometimes “global” or “offline”) SLAM problem, the system state, measurements and control inputs are saved in time series throughout the oper- ation. All of these values are used to calculate the estimate of the entire path and map. This commonly amounts to minimizing a nonlinear cost function. A very simple example of such a function is

C = X

t

Tx

W

x

δ

x

)

t

+ (δ

zT

W

z

δ

z

)

t

(1)

where the superscripted

T

denote the transpose, and where δ

x,t

and δ

z,t

are differences between actual pose and map (variables to estimate by minimizing C) and constraints or prior estimates. For example, if a function f estimates the next position given a previous position and control input, then

δ

x,t

= x

t

− f (x

t−1

, u

t

)

would be the difference between the actual pose x

t

at time t and the prior estimate given the prior pose x

t−1

and the control input u

t

. Similarly,

δ

z,t

= z

t

− h(x

t

)

would be the difference between the actual measurements z

t

and the expected measurements. W

x

and W

z

are weight matrices that can assign different impor- tances to the estimates.

The cost function can be solved by numerous numerical methods such as the iterative Nelder-Mead method.[19]

The GraphSLAM algorithm is another example that solves the full SLAM prob-

lem.[21] During robot operation, it populates a graph with soft constraints in

the form of measurement and control data across time. When calculating an

estimate, it uses this graph to reconstruct the map and the path.

(12)

2.3 The online SLAM problem

The online SLAM algorithms maintain a momentary, current estimate of the robot pose and the map. This is in contrast to those under the full SLAM category, where historical values are saved. Online SLAM is therefore iterative, and updated continually. Where full SLAM algorithms integrates all past val- ues for each new estimate, in online SLAM the integration is in a sense ongoing throughout their operation.

The simulation used in this thesis uses the Extended Kalman Filter which is an online SLAM algorithm. It is relatively simple to implement and convenient to use. Additionally, a continually updated estimate is desired in the case of interplanetary rovers, as momentary changes in pose are significant information for ensuring mission safety.

I will now first introduce the Kalman Filter and then briefly the general principle of the Particle Filter.

2.3.1 Optimal estimation with the Kalman Filter

In the late 1950s to early 1960s, Rudolf E. K´ alm´ an and others developed what has become known as the Kalman Filter. The Kalman Filter is an optimal filter provided that certain assumptions can be made about the system. Consider a system that can be described by the equations

x

t

= A

t

x

t−1

+ B

t

u

t

+ v

t

(2)

z

t

= C

t

x

t

+ w

t

(3)

where x

t

and u

t

are the state and control input vectors respectively, z

t

is the measurement vector and v

t

and w

t

are vectors of zero-mean Gaussian (nor- mally distributed) noise. The state vector contains the “state” of the entire system, which in the case of SLAM typically includes the position and bearing of the robot, as well as the positions of landmarks in the environment. The first equation is called the process equation and v

t

is therefore called the process noise. The A matrix describes the system dynamics: how the state evolves in the absence of control input. The B matrix simply models how the control input affects the state. The second equation is called the measurement equation and so w

t

is the measurement noise. The C matrix models how the state relates to the measurements, which are observations of the state. Given that the system can be modeled with these equations, one can make use of the Kalman Filter.

The Kalman Filter maintains a covariance matrix P

t

, the understanding of

which is important in understanding the Kalman Filter. It can be thought of as

a measure of the certainty or uncertainty of each state variable. It is a square

matrix with a number of columns and rows equal to the number of state vari-

ables in x

t

. The diagonal entries of P

t

are the variances of the state variables

and the off-diagonal entries are the covariances of each pair of state variables.

(13)

A large variance means that the corresponding state variable is very uncertain and conversely, a small variance means that the variable is certain in its estimate.

The optimality of the filter follows from theory assuming that equations 2 and 3 match the system exactly and that the variances of the noises are known and mutually uncorrelated. I will omit the derivation and proof of optimality for the Kalman Filter in this document. (For the interested reader these are read- ily found online and in most robotics and control theory textbooks due to the filter’s popularity. Some good resources include Welch and Bishop [24], Thrun, Burgard, and Fox [22], and Maybeck [16].) However, below I describe the steps and the equations that make up the algorithm when used in a control loop.

0. Initialize the state x

0

and its covariance matrix P

0

.

1. Apply control (e.g. move forward) and add the modeled result to the estimated state according to the process equation:

x ˆ

t

= A

t

x ˆ

t−1

+ B

t

u

t

(4) where the circumflex (ˆ) in ˆ x

t

implies that it is an estimate. This estimate is called the prior estimate.

2. Update the covariance matrix corresponding to the above trans- formation. This amounts to applying the equation:

P

t

= A

t

P

t−1

A

Tt

+ Q

t

(5)

where A

t

is the state-transition matrix and Q

t

is the covariance matrix corre- sponding to the process noise v

t

in equation 2.

3. Take measurements and calculate expected measurements using the measurement equation and the prior state estimate:

ˆ z

t

= C

t

ˆ x

t

(6)

Here again the ˆ in ˆ z

t

implies that it is an estimate. That is, given the prior estimate ˆ x

t

and the measurement model, ˆ z

t

is the measurement vector that is expected. The actual measurement vector z

t

gotten from the sensors will differ slightly from the expected.

4. Calculate the Kalman gain matrix:

K

t

= P

t

C

tT

(C

t

P

t

C

tT

+ R

t

)

−1

(7)

where C

t

is the observation matrix and R

t

is the covariance matrix of the mea-

surement noise w

t

in equation 3.

(14)

5. Calculate the posterior estimate using the Kalman gain, the prior estimate and the actual and expected measurement vectors:

x ˆ

t

= ˆ x

t

+ K

t

(z

t

− ˆ z

t

) (8) The asterisk on ˆ x

t

is used to denote that it is the posterior estimate.

6. Calculate the posterior covariance matrix using the equation:

P

t

= (I − K

t

C

t

)P

t

(9)

That summarizes the Kalman Filter used in a control loop. Steps 1 and 2 are repeated for every time step.

1

Steps 3 through 6 are repeated every time step for which there are measurements available to be used. The loop can be summarized neatly as in figure 2.

Figure 2: Summary of the main processes of the Kalman Filter

One big limitation of the Kalman Filter stems from the fact that most sys- tems in SLAM are not linear. They can therefore not be described by equations 2 and 3. To use the Kalman Filter with nonlinear systems, one can look to the Extended Kalman Filter (EKF), as we shall do next.

2.3.2 The Extended Kalman Filter

As mentioned, the Kalman Filter in its original form does not apply to nonlinear systems. This is a problem because most SLAM problems are of this kind.

1

As a side note, in SLAM systems where the state doesn’t change in the absence of control

input u

t

, the state-transition matrix A

t

is equal to the identity matrix. It therefore suffices

to repeat these steps every time step that also has a non-zero u

t

.

(15)

Consider for example a bearing measurement from a robot r to a landmark i:

θ

ri

= arctan y

i

− y

r

x

i

− x

r

− θ

r

(10)

or a range measurement:

d

ri

= kx

r

− x

i

k (11)

These types of measurement are very commonly used in SLAM.

If equations 2 and 3 are rewritten in a more general form, the Extended Kalman Filter can be used:

x

t

= f (x

t−1

, u

t

) + v

t

(12)

z

t

= h(x

t

) + w

t

(13)

where, as in the original equations, v

t

and w

t

are Gaussian, zero-mean noise.

f and h are the state-transition and measurement functions.

The EKF follows the same steps as outlined in the Kalman Filter section pre- viously, but A

t

, B

t

and C

t

are replaced by linearizations of f and h around x

t

. To perform these linearizations we use the Jacobian:

J

f

(x) = δf δx =

δf1

δx1 δf1

δx2

. . .

δxδf1

n

δf2 δx1

δf2

δx2

. . .

δxδf2

..

n

. .. . .. .

δfn

δx1

δfn

δx2

. . .

δxδfn

n

(14)

The linearizations are updated each time they are to be used. The Jacobian of f around x

t

is written as F

t

below, and similarly that of h as H

t

. We can then adjust the algorithm as below.

0. Initialize x

0

and P

0

1. Calculate prior estimate ˆ

x

t

= f (ˆ x

t−1

, u

t

) (15)

2. Calculate prior covariance

P

t

= F

t

P

t−1

F

tT

+ Q

t

(16) 3. Measurements and expected measurements

ˆ

z

t

= h(ˆ x

t

) (17)

(16)

4. Calculate the Kalman gain

K

t

= P

t

H

tT

(H

t

P

t

H

tT

+ R

t

)

−1

(18) 5. Calculate the posterior estimate

ˆ

x

t

= ˆ x

t

+ K

t

(z

t

− ˆ z

t

) (19) 6. Calculate the posterior covariance matrix

P

t

= (I − K

t

C

t

)P

t

(20)

The EKF process is shown in figure 3.

Figure 3: Summary of the main processes of the Extended Kalman Filter

Crucial to SLAM is the addition of features as new ones are discovered. In EKF SLAM, this amounts to augmenting the state vector x and the covariance matrix P . This can be as simple as appending the Cartesian coordinates of the feature to x and the corresponding rows and columns to P .

Clearly a linearization around a point is an approximation of the function lin-

earized around that point. The EKF is therefore not the optimal filter, as

the model no longer describes the system fully, as was a required condition for

optimality in the original Kalman Filter.

(17)

2.3.3 Alternatives to the EKF

As mentioned, the EKF performance relies on the quality of the linearizations it uses to approximate the system. The linearizations are poor if the system is highly nonlinear. In those cases, the linearization diverges quickly from the original modeling function. The noise present in the input, whether process noise or measurement noise, becomes the distance from the point around which the function was linearized. This can result in big modeling errors.

The Unscented Kalman Filter[22] similar to the EKF is another way to apply the Kalman Filter to nonlinear systems. Instead of linearizing with Jacobians, the nonlinear functions are evaluated at several points surrounding the point of linearization. From these values a new Gaussian mean and covariance is con- structed for the function. As this method does not use derivatives, it can be applied to systems whose functions aren’t differentiable.

The Kalman Filter assumes normal distributions for the noise and state vari- ables, which aren’t always good representations of the true distributions. This is the case in range-only SLAM as we shall see in a later section. Djugash, Singh, and Grocholsky [9] solve this by maintaining a multi-hypothesis EKF.

The multi-hypothesis filter works analogously to a particle filter, a category of algorithms which I will briefly describe next.

2.3.4 The Particle Filter

One drawback of the Kalman Filter is that it assumes normal distributions of noise and state. Normal distributions are unimodal, so Kalman Filters are very vulnerable to measurements that produce solutions with multimodal distribu- tions.

The particle filter is a category of algorithms that can be applied to SLAM

in various forms. It uses particles: N-dimensional points where each point is a

possible state vector, and that collectively represent the state probability distri-

bution. In this way, the particle filter can represent any distribution, including

multimodal ones.

(18)

Figure 4: A 1-dimensional example of a bimodal distribution that is approximated using a unimodal distribution, vs. using particles There are many extensions of the particle filter, but the general algorithm can be roughly outlined as follows.

1. Produce M particles estimating the state vector and assign them appropri- ate weights (also known as importance factors), a high weight represents a higher probability. If completely uncertain, a uniform distribution is achieved by assigning equal weights.

2. Apply the process update (f in this document) to each particle, but in- clude a sample of the noise model. This is the prior of the particle filter.

3. Get the measurement (z). Update the particle weights by calculating the likelihood of the measurements given each particle. I.e. calculate the probability of the noise z − h(x) in your noise model.

4. Use the new weights to calculate the weighted average of the particles.

This is the state estimate of the particle filter.

5. Back to step 2.

Sampling the noise model in the second step will make the particles “spread out” to account for the uncertainty of the true state value.

2.4 Common issues faced in SLAM

In most SLAM problems, one has to deal with relative positioning. As the robot

moves through and observes an unknown environment, given that the measure-

ments are relative to the robot, the resulting map will be relative as well. While

the errors may be small local to the robot, their accumulation throughout the

robot’s journey can produce a significantly warped map in comparison with

ground truth.

(19)

Another issue to consider arises in feature-based SLAM. A feature, such as a beacon or a landmark needs to be identified correctly. Is it a newly discovered feature to be added to the map, or is it a repeated measurement that should update the location of a previously discovered one? This is an important issue, as a few misidentifications can quickly lead to confusion such as mapping several positions that in reality belongs to the same feature. It is easy to understand how error that arises of such duplicities propagates in the map of a system using measurements such as bearing between two features.

The choice of SLAM method and technology is often secondary to other mis- sion requirements and design limits. There are therefore many subcategories of SLAM, using different instruments and types of measurements, such as cameras for visual SLAM methods[20], or lidar SLAM[5]. Each such subcategory en- counters unique problems to solve and mitigate. The PHALANX system deals with range-based measurements in wireless sensor networks, and so that is what we shall look at in the following section.

2.5 Issues faced in range-only SLAM

Range-only SLAM (RO-SLAM) is a subcategory of SLAM where all measure- ments are distances to features. Range measurements can be obtained by many different sensors and techniques. Time-of-arrival techniques[14, 12] are tractable methods when using RF transmitters.

Figure 5: Range-only measurements from a robot to several land- marks.

On its own with no prior knowledge, a single measurement would not be able to yield a resulting position estimate, even with zero measurement error.

The possible positions given a perfect measurement to a landmark lie on a circle

with the measured distance as its radius, as illustrated in figure 6.

(20)

Figure 6: A single measurement (blue dashed line) from the robot to the feature (black triangle) produces a circle of possible locations that said feature can be in, relative to the robot.

Typically this circle would be constrained to a point if an additional bearing- measurement would be available. In RO-SLAM however, this is clearly not pos- sible and more involved methods must be used. One way of dealing with this is to iteratively update each feature with multiple measurements from different points in the robot’s path. Using the combined data of the robot’s odometry and of the multiple measurements, the positions of the features are constrained.

With additional landmarks and associated measurements, the number of possi- ble solutions decrease. The use of circles to visualize the range-only localization problem is a very useful one, as we shall see. Consider adding one additional landmark, shown in figure 7. This time, we center the measurement circles on the landmarks. The circles representing the set of possible positions have only two common points, their intersections. Adding a third landmark and measure- ment further constrains the solution set to one point (in two-dimensional space).

A more realistic illustration takes into account the noise present in the mea-

surement. In the case of a zero-mean, unimodal error distribution, this is then

represented by an annulus rather than a circle, see figure 8. The annular area is

a confidence interval that to some degree of certainty contains the true distance.

(21)

Figure 7: Measurements to two landmarks are available. The re- sulting possible robot positions are marked by green crosses.

Figure 8: The true measurement (dashed blue) forms a circle (dashed black), and the noisy measurement with an error σ shapes the circle into an annular area (dashed red).

The visualization of a range-measurement as an annulus can provide further insight into the limitations of RO-SLAM. We will see that the relative positions of landmarks and robot become more significant. Specifically, we are talking about the collinearity of the positions of the involved landmarks and robot.

2.5.1 Collinearity of landmarks

To illustrate the issue of collinearity in landmarks, we consider again a robot

measuring ranges to two landmarks. First, in figure 9, we place two landmarks

to either side of the ranging robot.

(22)

Figure 9: A robot is right between two landmarks, forming almost a perfect line. The overlapping region of the annuli, the area dashed red, is large.

Next, for comparison, in figure 10 we move one node to the side, so that the collinearity is decreased.

Figure 10: The robot is no longer forming a line together with the landmarks. The overlapping region of the annuli, dashed in blue, is smaller.

These illustrations provide an intuition of why collinearity is bad in range-

based localization. This is analogous to “dilution of precision,” a term commonly

seen in the area of GPS technology. The overlapping area grows (is diluted) for

collinear positions. Remember that these annuli are confidence areas, i.e. they

contain the real measurement value with some specific probability. For the

same probability, a larger area implies a less certain solution. The smaller the

overlapping area of these annuli, therefore, the better the localization result is

likely to be.

(23)

2.5.2 Rover trajectory

The path of a robot in relation to landmarks can also be significant for the localization performance. Consider a robot moving in a path tangentially to the circle of measurement from a landmark, shown in figure 11.

Figure 11: A robot is driving tangentially to the circle of the range measurement.

The information gain from measurements along the robot trajectory is zero, as the range to the landmark doesn’t change. As a consequence the position uncertainty will grow large in this direction as there is no information to correct the errors that accumulate in the robot’s odometric estimate. Now consider adding another landmark to this scenario, as seen in figure 12.

Figure 12: The robot is driving tangentially to the circle of the range measurement of one landmark, but not for the other.

Again, there is the issue of collinearity. But in addition to the overlapping

areas of the annuli, there is the issue of the confidence area of the robot’s

position. This is the previously mentioned error bound that grows as the robot

drives, due to process noise. For many models of this process noise, it can be

modeled fairly well as a growing ellipse centered on the moving robot. The

(24)

difference in noise magnitudes between directional (bearing) and along-path translation (speed) shapes the ellipse.

(a) (b)

Figure 13: The direction in which the robot drives relative to the landmark affects the size of the overlapping area (in dashed red).

In (a) the robot drives tangentially to the measurement circle, and in (b) it drives towards the landmark.

Typically, the along-path noise is greater and so the error and the ellipse grow faster in this direction. In such cases, driving tangentially to the line of the measurement (i.e. perpendicularly to the circle) produces a smaller overlapping area, illustrated in figure 13. Again, the smaller area implies a more certain position estimate.

2.5.3 Wireless sensor networks

For RO-SLAM in wireless sensor networks (WSNs) the addition of distance measurements in between landmarks, then referred to as nodes, are available.

Range measurements between nodes are necessary for solving the multilateration problem.

2

2

If the term multilateration is unfamiliar to the reader, it is similar to the more colloquially

well-known triangulation, only here it is distances that are used rather than angles.

(25)

Figure 14: Range-only measurements between nodes in a wireless sensor network

However, without prior knowledge of any node locations, the multilatera- tion problem cannot be solved. Even with some known locations, if the network connectivity is low, the equation is likely underconstrained and the resulting solution set large.

A typical erroneous result of an underconstrained equation is a mirror image of the actual solution in some subnet of nodes. It is fairly straight-forward to intuit: measured ranges between a group of nodes would be the same if said group was flipped about some axis. Lacking additional information, the erro- neous solution and the correct one are equally probable. The most obvious flip ambiguity is that of the whole network, as shown in figure 15.

(a) (b)

Figure 15: In this illustration of a flipped network, both sets of node positions are valid given the measured distances.

But flip ambiguity can also occur for subnets or single nodes, as is shown in

figure 16.

(26)

(a) (b)

Figure 16: The position of the single node “E” within the network cannot be disambiguated, since both positions are valid given the exact same measured distances.

A general solution strategy to mitigate flip ambiguities of single nodes and subnets is to increase network rigidity, i.e. increasing the amount of connections for each node. Take the network in figure 16 again, for example. An additional measurement from node B to node E would be enough to resolve the ambiguity in node E’s position. The nodes are then more constrained in relation to each other by the additional distance measurements in the equation.

2.5.4 Articulation points

When the number of connections in a network is low as in a sparse network, it is likely that some nodes are what is known in graph theory as articulation points (or cut vertices). In short, an articulation point is a point in a graph, which if removed, disconnects the graph.

Figure 17: 5 nodes form a small network, with one articulation

point in the middle, connecting the two nodes on the lower left to

the two nodes in the upper right. Available range measurements

are marked by the dashed lines.

(27)

An example of an articulation point in a network is shown in figure 17. If the node in the center is removed, the network is disconnected. While a single- point failure is of concern for communication, the main concern in the context of localization is the resulting poor constraints on the relative node positions.

The range measurements between the nodes constrain the relative positions to some extent, but the occurrence of the articulation point allows the subnets of nodes to rotate around it. Figure 18 shows this where a subnet of two nodes move along with the marked “axis” line. Of course, the subnet is also free to flip about this line within the constraints of the measurements.

Figure 18: Subnets are free to rotate around articulation points due to the low constraints resulting from such poor connectivity.

2.5.5 Anchor nodes

While increasing node connectivity reduces the risk of flip ambiguities for indi- vidual nodes and subnets, prior knowledge of some nodes are still necessary, as the entire network would otherwise be free to rotate and flip as we saw before. It is for this reason that anchors, sometimes referred to as beacons, are important.

Anchors are nodes for which positions have been established to high accuracy, often by external means. The external means vary depending on availability and can be careful hand-placement utilizing analog or laser measurements in re- lation to the environment, or assigning position by GPS. These methods are not available for PHALANX, operating on another planet. However, I will describe some examples of feasible methods later in this section.

2.6 SLAM in PHALANX

The PHALANX system uses range-only, wireless sensor network SLAM. Recent work done in similar RO-WSN SLAM problems include Menegatti et al. [17]

and the extensive work done by Djugash et al. [10, 9, 8], where a mobile robot

drives through an environment populated with sensor nodes. In the PHALANX

(28)

system, there are some additional distinctions that are important: crucially, the deployment of nodes and the possible process of anchorization of nodes.

Rovers operating today and in the past have implemented SLAM successfully using onboard equipment. The SLAM possible with PHALANX can serve to augment the current systems, offloading them while operating around deployed nodes. It would also enable the rover to navigate in the dark, something that pose difficulties for visually based SLAM, such as caves or craters. Conversely, existing SLAM systems can aid PHALANX SLAM, by for example decreasing process noise and correcting the rover pose estimate.

2.6.1 Data association

The issue of data association is trivial in wireless sensor networks as all features are controlled and digital signatures can be sent with each measurement and communication. In each range measurement it is then clear which nodes are involved. This is one of the foremost arguments for using RF transceivers, as data association can be very complex for other forms of measurement.

2.6.2 Anchorization of nodes

Anchor nodes in PHALANX cannot be established in before-hand, as all nodes are deployed from the rover. They must therefore be generated after their de- ployment. This becomes a unique issue, as most means by which anchors would be established are unavailable, such as manual placement and measurements or usage of GPS. However, I will suggest some tractable methods of achieving this, given circumstances and tools typical to that of a rover mission.

One way of anchorizing nodes involves visual observations, using the rover cameras. Upon seeing a node with the high resolution rover cameras, a high- precision bearing measurement is in effect gotten. Several such measurements to distant landmarks in the environment can be used for triangulation of the rover after which the bearing measurement and the range measurement can provide a precise and accurate node location estimate.

Another way of anchorizing nodes is to do so early in a node cluster. In that

way, one can crucially avoid adding excessive process noise to the anchor place-

ment. Lacking other alternatives, a node can be dropped right at the rover’s

position, making for a more precise deployment than the usual launch. If the

rover includes a high-precision range finder such as a laser, the rover can perform

a precise drive in a straight line to a second location where it can drop another

anchor node. If such a high-precision range finder is not available, the original

range-finding measurements can be used. The error of these measurements in

the prototype units typically lie below 20 cm according to the testing that has

been done at the time of this writing.

(29)

2.6.3 Deployment of nodes

Deploying nodes remotely in a precise manner is difficult, largely owing to the unpredictability of the node landings. Still, the actual landing position can be roughly estimated as the sample of a distribution centered around the de- ployment target position. This initial information gain is highly valuable in range-only SLAM where the solution set is large. In the case of EKF SLAM, the landing distribution is approximated as a Gaussian distribution, with the launch target as its mean. It is especially useful for when the solutions are far from each other, as then even a large and uncertain landing area will be sufficient for that disambiguation. This is visualized in figure 19.

Figure 19: A rover deploys a sensor node that has two possible solutions (blue triangles) based on measurements to the rover and another previously deployed node (red triangle). The green area is the estimated landing zone based on the deployment target loca- tion.

The issue of collinearity enters here again, though, as for two nodes that are measuring to a third node where all three nodes are collinearly placed, the possible solutions lie nearer each other. The solutions are then harder to disambiguate to the correct position. This is shown in figure 20.

Figure 20: Here is the same scenario as in figure 19, but here the

possible solutions lie closer to each other.

(30)

3 Implementing the Simulation Model

In this section I will describe the model that is used in my simulations. The ex- periments are done using 2D simulations. Each simulation samples the involved noise distributions with its unique seed. For one scenario setup and configura- tion, many simulations are run. From all the simulations, time-series data are saved and processed to produce the result statistics. The use of the simulation program to generate results is illustrated in the diagram in figure 21.

Figure 21: A diagram describing how results are generated in an experiment, using the simulation software.

The simulations assume a coordinate system relative to the start position of the rover. This means that all the results are relative to the error of the initial rover pose estimate. For instance, if the initial rover pose estimate is assumed perfect, then the ground truth of the simulation correspond to global “absolute”

coordinates.

The system will be mostly modeled by an Extended Kalman Filter (EKF) as

described in section 2. Two state vectors will be kept separately: the ground

truth state vector that is updated with errors sampled from the noise models,

and the state vector that is maintained by the EKF. The difference between

each state vector give rise to the error statistics.

(31)

3.1 The System Model

To begin with, recall the general non-linear state equations 12 and 13 from section 2, which we write again here:

x

k

= f (x

k−1

, u

k

) + v

k

(21)

z

k

= h(x

k

) + w

k

(22)

Where the k-subscript denotes the discrete time instance. The system state vector x consists of the rover pose, i.e. the 2-dimensional coordinates and its bearing, and the 2-dimensional coordinates of all the sensor nodes. For a net- work of N sensor nodes, the state vector will therefore be a vector with 2N + 3 elements. The elements of the input vector u = [u

1,k

, u

2,k

] are simply speed and bearing rate, respectively. Since this is a range-based SLAM problem, the measurement vector z consists of measured ranges to all the other nodes includ- ing the rover, and is therefore of size N .

There are two state vectors, one belonging to the EKF and the other being the ground truth that is to be estimated, which is “unknown” to the rover.

Associated with the former, there is the covariance matrix P

k

that is also main- tained by the EKF. This is a square matrix with 2N + 3 rows and columns, where the diagonal entries are the state variable variances and the off-diagonal entries are the covariances between the state variables.

3.1.1 The process model

In our case, the process function f is very simple as the only change in the state vector due to our process is the rover motion; the sensor nodes are not moving.

The function is

f (x

k−1

, u

k

, t

k

) =

x

r,k−1

+ τ

k

u

1,k

cos θ

r,k−1

y

r,k−1

+ τ

k

u

1,k

sin θ

r,k−1

θ

r,k−1

+ τ

k

u

2,k

x

1,k−1

y

1,k−1

.. . x

N,k−1

y

N,k−1

(23)

where x

r

, y

r

and θ

r

are the rover coordinates and bearing, and τ is the time step.

The ground truth state vector is updated with process noise added through

the control vector u

k

.

(32)

The wheel odometry error is modeled after a conservative rule-of-thumb fig- ure

3

for what rovers can achieve: that is, a 5 % error on the distance driven.

This is implemented via the speed control noise in the process update. The speed input noise is governed by two sample processes. First, in each individual simulation, a mean-error is sampled once, this error will remain for the whole simulation. The mean-error is a ratio with distribution mean of 1.0 that is mul- tiplied with the speed input value to simulate a consistent model error. The second is sampled at each process update, with a mean around the input speed after the previous mean-error sample.

The bearing rate input noise is a simplified model of an inertial measurement unit (IMU). Error figures of IMUs used in rover applications are around 1 ° h

−1

to 2 ° h

−1

. This is modeled as a Gaussian distribution with a time-dependent increasing variance.

3.1.2 Measurements and mutual localization

The measurement function h is a bit more complicated in a network where nodes can all measure to other nodes. The result is several measurement vectors and functions. I will write the kth measurement vector and measurement prediction function for node i as z

i,k

and h

i,k

respectively.

h

i,k

(x

k

) =

kx

i,k

− x

r,k

k kx

i,k

− x

1,k

k

.. . kx

i,k

− x

j,k

k

.. . kx

i,k

− x

N,k

k

, j ∈ {r, 1, 2, ..N }, j 6= i (24)

Like before, the r subscript denotes rover quantities. The usage of multiple measurement vectors will be detailed later in this section when describing the implementation of the EKF.

The ranging noise is modeled as samples from a Gaussian distribution cen- tered around ground truth value. Due to the workings of RF ranging, the error doesn’t change with distance for signals with good identification. Therefore the standard deviation is an absolute value. Results from the testing of prototype units yield an error figure of about 0.20 m, and is therefore used in the simula- tions as the standard deviation in the Gaussian distribution. For two nodes i and j, the ranging-measurement becomes

z

ij,k

∼ N 

kx

i,k

− x

j,k

k , (0.20 m)

2



(25)

3

This rule of thumb is based on results for rover-missions, gotten from private conversation

with mentor Michael Dille.

(33)

3.1.3 Process and measurement function Jacobians

The EKF linearizes the process and measurement functions by calculating their Jacobian matrices (see equation 14). First we look at the process function, f from equation 23.

F

k

= δf

δx = I

2N +3

+

0 0 −τ

k

u

1,k

sin θ

r,k−1

0 . . . 0 0 0 τ

k

u

1,k

cos θ

r,k−1

0 . . . 0

0 0 0 0 . . . 0

.. . .. . .. . .. . . . . .. .

0 0 0 0 . . . 0

(26)

This equation is used in calculating the prior estimate covariance matrix P

k

= F

k

P

k−1

F

kT

+ Q

k

(27) where Q

k

is the process noise covariance matrix. However, currently we have the noise variances in terms of speed and bearing rate, u

k

:

Q

0k

= σ

2u

1

0

0 σ

u22



(28) We can solve this by calculating the Jacobian of f with respect to u:

G

k

= δf δu =

τ

k

cos θ

r,k−1

0 τ

k

sin θ

r,k−1

0

0 τ

k

0 0

.. . .. .

0 0

(29)

and then we get Q

k

as

Q

k

= G

k

Q

0k

G

Tk

(30)

Next we look at the measurement function h from equation 24. As we saw previously, measurements between multiple pairs of nodes results in multiple measurement vectors. Therefore, there will be multiple linearizations. First we look at measurements taken from the rover to other nodes,

h

r,k

(x

k

) =

kx

r,k

− x

1,k

k .. . kx

r,k

− x

i,k

k

.. . kx

r,k

− x

N,k

k

, i = 1..N

(34)

For convenience we write ∆x

ij

= x

i,k

− x

j,k

and ∆y

ij

= y

i,k

− y

j,k

and the distance d

ij

= kx

i,k

− x

j,k

k. The Jacobian of h

r,k

with respect to x is

H

r,k

= δh

r,k

δx

k

= (31)

∆xr1

dr1

∆yr1

dr1

0 −

∆xdr1

r1

∆ydr1

r1

0 0 . . . 0 0

∆xr2 dr2

∆yr2

dr2

0 0 0 −

∆xdr2

r2

∆ydr2

r2

. . . 0 0

.. . .. . .. . .. . .. . .. . .. . . . . .. . .. .

∆xrN drN

∆yrN

drN

0 0 0 0 0 . . . −

∆xd rN

rN

∆ydrN

rN

 The matrix is large but there is a clear pattern. Note that the third column corresponding to the bearing state variable is filled with zeros as bearing does not enter the measurement function. For other nodes, a few columns are swapped.

H

i,k

= δh

i,k

δx

k

= (32)

∆xdir

ir

∆ydir

ir

0 0 0 . . .

∆xd ir

ir

∆yir

dir

. . . 0 0

0 0 0 −

∆xd i1

i1

∆ydi1

i1

. . .

∆xd i1

i1

∆yi1

di1

. . . 0 0

.. . .. . .. . .. . .. . .. . .. . .. . . . . .. . .. .

0 0 0 0 0 . . .

∆xd iN

iN

∆yiN

diN

. . . −

∆xdiN

iN

∆ydiN

iN

3.1.4 Missing measurements

In reality, not all nodes in the network may have range measurements available due to an obscured line of sight, being out of range, or other connectivity issues.

In such cases, the measurement functions and therefore the resulting Jacobians must be adjusted before calculating the Kalman gain K.

By replacing columns in H

k

in accordance with the missing measurement values in z

k

, implementation becomes easier. This can be done efficiently by matrix multiplication. First we create the measurement matrix without the rows for which the measurements are missing. If node 6 is measuring to nodes 1, 3 and 4 in a network of 7 nodes, for example, this matrix becomes

H

6,k

=

∆x6, 1 d6, 1

∆y6, 1

d6, 1

∆xd6, 1

6, 1

∆yd6, 1

6, 1

0 0 0 0

∆x6, 3 d6, 3

∆y6, 3

d6, 3

0 0 −

∆xd6, 3

6, 3

∆yd 6, 3

6, 3

0 0

∆x6, 4 d6, 4

∆y6, 4

d6, 4

0 0 0 0 −

∆xd6, 4

6, 4

∆yd6, 4

6, 4

(35)

We then construct a matrix to adjust its shape and reorder the columns

M =

0 0 0 0 0 0 0 I

2

0

0 0 I

2

0 0 0 0 0 0

0 0 0 0 I

2

0 0 0 0

0 0 0 0 0 I

2

0 0 0

where each bold-font 0 is a 2-by-2 zero-matrix and I

2

is the 2-by-2 identity matrix. We also have to remember the bearing state variable, and because bearing is not involved in the range measurements, we add a column of zeros to M . The resulting Jacobian H

k

is then

H

i,k

= H

i,k

M (33)

which has the shape of H

i,k

in equation 32, but with the proper entries replaced by zeros, in regards to the missing measurements.

3.1.5 Deployment of sensor nodes

The continual deployment of sensor nodes is a crucial component of PHALANX.

As a new node is deployed, it has a target location and an actual location where it landed. Upon deployment, both the ground truth and the EKF state vector are augmented with the new node’s two-dimensional coordinates added at their ends. Since the target is known to the rover, its coordinates can be used for the initial estimate. The ground truth differs from the target to simulate the imperfections of the launch, and is constructed from

x

i

= x

r

+ ρ cos (θ

r

+ β) sin (θ

r

+ β)



(34) where ρ and β are the launch range and azimuth polar coordinates sampled from Gaussian distributions, visualized in figure 22.

ρ ∼ N (ρ

target

, σ

ρ2

) (35)

β ∼ N (β

target

, σ

β2

) (36)

The initial estimate is ˆ

x

i

= ˆ x

r

+ ρ

target

cos (ˆ θ

r

+ β

target

) sin (ˆ θ

r

+ β

target

)



(37)

and the resulting initial covariance matrix becomes

P

i

= P

r

+ J

l

P

l

J

lT

(38)

where P

l

is the covariance matrix

P

l

= σ

ρ2

0 0 σ

β2



(39)

(36)

Figure 22: Visualization of the remote deployment of a sensor node in the simulation, with azimuthal and radial noise.

and J

l

is the Jacobian of the second term in equation 37 with respect to ρ

target

and β

target

:

J

l

= cos (ˆ θ

r

+ β

target

) −ρ

target

sin (ˆ θ

r

+ β

target

) sin (ˆ θ

r

+ β

target

) ρ

target

cos (ˆ θ

r

+ β

target

)

!

(40)

3.1.6 Anchorization

As described in section 2, anchorization is the process where the position es- timate of a node is improved as well as possible using external means. After this process, the node is called an anchor. In the simulation model, the position estimate of an anchorized node is sampled from a Gaussian distribution with the ground truth as the mean. Rover cameras make for high precision bearing measurements. The Mars Science Laboratory (Curiosity rover) for example, is equipped with cameras with 5.1 ° field-of-view and 1200 pixels on the horizontal.

This results in a resolution of 0.004 ° per pixel. Using the ranging measurements, the error is approximately 20 cm, based on prototype testing. The standard de- viation used in sampling the anchorization estimate is therefore conservatively set to σ

x

= 0.20 m:

x

anchor

∼ N



x

truth

, σ

x2

0 0 σ

x2



3.2 Evaluation metrics

In this section I will define the metrics that are used in the experiments, RMSE and a collinearity measure.

The root mean squared error (RMSE) is simple to understand, especially

intuitive in the case of physical positions, and simple to implement. The defi-

nition of RMSE is spelled out in its name: the square root of the mean of the

(37)

squares of the errors,

RM SE = s

P

N i

e

2i

N (41)

where e

i

is one error out of N total. In this document RMSE will be applied on the rover position and the sensor node positions. The error is the distance between the estimate position and the ground truth position. In the case of rover position, the errors are evaluated at evenly spaced time points throughout each simulation. This is because rover localization is important for its entire drive. For sensor nodes, the errors are only evaluated at the final time. While accurate node position estimates, i.e. an accurate map, is important for good lo- calization during the drive, the accuracy of the final map is more relevant when considering mission-level goals. For node RMSE, the errors of anchor nodes will not be considered as these are by definition localized as accurately as possible, often by means external to PHALANX.

When applied on large sets of simulations, the resulting distribution that is made up of all RMSE values is telling of the “robustness” of the simulated scenario configuration. For example, a large variance where the percentiles are widely spaced from the median, suggests that the configuration is unreliable and prone to failure.

Collinearity for a set of positions describes how well a straight line approxi- mates the positions. The measure of collinearity should therefore reflect this.

Positions that are approximated well by a line have a higher collinearity value.

There are two extremes of collinearity: the most collinear, where positions lie on a single line, and the least collinear, where positions lie evenly distributed on a circle.

I will define the collinearity measure I use that follow the above requirements.

For a set of N positions x, calculate the covariance matrix

Q = 1

N − 1

N

X

i

(x

i

− ¯ x)(x

i

− ¯ x)

T

where ¯ x is the mean of x and x

i

is the coordinates vector of the ith position.

The covariance matrix Q is a square matrix, 2-by-2 for two-dimensional posi- tions. Then we calculate the eigenvalues and eigenvectors for this matrix λ

i

, and v

i

. The eigenvectors are new orthogonal axes, or components, and the corresponding eigenvalues are the “strengths” of the components. The vectors with the largest eigenvalues are called the principal components of the sample set. To get our collinearity measure, I will use a ratio of the largest and small- est eigenvalues, call them λ

+

and λ

respectively. We define the collinearity measure as follows:

C = 2 λ

+

λ

+

+ λ

− 1 (42)

References

Related documents

Establishing a language for innovation to institutionalise a definition, use corporate culture as a control system, standardising internal processes, fostering a learning

Through a field research in Lebanon, focusing on the Lebanese Red Cross and their methods used for communication, it provides a scrutiny of the theoretical insights

This section presents the resulting Unity asset of this project, its underlying system architecture and how a variety of methods for procedural content generation is utilized in

46 Konkreta exempel skulle kunna vara främjandeinsatser för affärsänglar/affärsängelnätverk, skapa arenor där aktörer från utbuds- och efterfrågesidan kan mötas eller

The increasing availability of data and attention to services has increased the understanding of the contribution of services to innovation and productivity in

Generella styrmedel kan ha varit mindre verksamma än man har trott De generella styrmedlen, till skillnad från de specifika styrmedlen, har kommit att användas i större

I regleringsbrevet för 2014 uppdrog Regeringen åt Tillväxtanalys att ”föreslå mätmetoder och indikatorer som kan användas vid utvärdering av de samhällsekonomiska effekterna av

Parallellmarknader innebär dock inte en drivkraft för en grön omställning Ökad andel direktförsäljning räddar många lokala producenter och kan tyckas utgöra en drivkraft