<<

TERRAIN-RELATIVE PLANETARY DETERMINATION

Kevin Peterson1, Heather Jones1, Corinne Vassallo2, Allen Welkie3, and William “Red” Whittaker1 1The Robotics Institute, Carnegie Mellon University, 5000 Forbes Ave, Pittsburgh, PA 15213, USA 2The Department of Physics, Carnegie Mellon University, 5000 Forbes Ave, Pittsburgh, PA 15213, USA 3The Department of Engineering, Swarthmore College, 500 College Ave, Swarthmore, PA 19081, USA

ABSTRACT enable fully autonomous operation from launch to land- ing.

This paper presents an approach to visual navigation for Deep Space 1 demonstrated visual navigation far from a spacecraft during planetary orbit. Spacecraft orbital pa- planetary surfaces by triangulation to distant . rameters are determined autonomously by registration to These observations relied on the appearance as a terrain. To accomplish this, individual camera images are single pixel in an imager, reducing measurements to dis- registered to pre-existing maps to determine spacecraft criminating a point source from black background. Vi- latitude and longitude. Using knowledge of orbital dy- sual navigation during terminal descent has been shown namics, the time history of sensed latitudes and longi- in terrestrial demonstrations to be more accurate than ra- tudes is fit to a physically realizable trajectory. Outlier dio navigation and operates with latency independent of measurements are rejected using robust estimation tech- distance to Earth. With new high-resolution and niques. Simulation results using data from the Lunar Re- Moon imagery, terrain relative navigation can achieve connaissance Orbiter show that method determines the 30-meter localization precision. However, autonomous orbit semi-major axis with an average error less than 6km visual-only navigation is undeveloped for planetary ap- for a 500km altitude lunar orbit. proach, capture, and orbit.

Key words: orbit determination; vision; robotics. This paper describes Terrain Relative Planetary Orbit De- termination (TROD), an approach to visual navigation for orbiting spacecraft. TROD matches terrain appearance to on-line imagery and utilizes knowledge of orbital dynam- 1. INTRODUCTION ics to determine position, , and orbital parame- ters of the spacecraft trajectory. Simulation results using data from the Lunar Reconnaissance Orbiter show that Visual navigation for precise, reliable guidance of crewed the method determines the semi-major axis with an aver- and robotic planetary missions offers the opportunity to age error less than 6 km for a 500 km lunar orbit. revolutionize space exploration by improving targeting of landing sites, substantially reducing mission risk, and extending human reach through autonomous missions to 1.1. Related Work distant locations such as the Jovian moons. State-of- practice radio-based navigation exhibits unacceptable la- tency at long range, relies on interaction with Earth, and Orbit determination has a deep history dating back cen- cannot achieve the landing accuracy possible through vi- turies to early physicists. The related work is deep and sual means. Autonomous navigation via camera offers it is out of scope to discuss most aspects of orbit deter- an alternative to radio without the mass and power re- mination here. Rather, we focus on spacecraft orbit de- quired for traditional altimetry (e.g., and laser), termination and computer vision approaches to trajectory and without communication to Earth. Visual navigation modeling. will enable autonomous spacecraft to land in radio-dark locations like craters and the far sides of . In deep space, camera-based navigation measures an- gles to distant asteroids to triangulate location [RBS+97, Visual navigation provides three primary advantages over BRK+02]. These observations rely on the asteroid ap- alternatives: accuracy, low latency, and autonomy. Dur- pearance as a single pixel in an imager, reducing mea- ing descent, accuracy and latency are important factors in surements to discriminating a point source from black mission success. Far from earth, visual navigation is crit- background. Objects that appear larger than a few pixels ical, as communication latency precludes precision ma- introduce significant angular error. The Voyager missions neuvering. Visual navigation for all mission phases will to Jupiter, Saturn and beyond used optical measurements along with radio to Earth for navigation. Images of the ’s natural against a star background were used, with knowledge of ephemerides to update a naviga- tion filter run on Earth [CSB83].

Significant work has been done on camera-based terrain relative navigation. While this technique has proved to be quite successful in simulation and sounding rocket test- ing [TMR+06, TMR+07, PBC+10], the focus has mostly been on the final stages of descent to a planetary surface, not on higher altitude trajectories. Singh and Lim imple- ment an Extended Kalman Filter (EKF) to track space- craft position and velocity in orbit; they use vision-based measurements, but they also assume that altitude can be obtained from an altimeter with only 12.5m (1σ) error. Such high-end radar is programmatically costly. They use crater-based feature tracking and thus they limit their “experiments to segments of the trajectory that span the Figure 1: TROD matches images obtained in orbit to higher latitudes where the craters are more clearly visi- maps and then applies Kepler’s laws to determine orbital ble” [SL08]. parameters. Given time and estimated latitude and longi- tude at several locations, the orbit is fully determined. In addition to planetary applications, work has also been done on autonmous navigation for landing on asteroids. The Near Earth Asteroid Rendezvous (NEAR) mission 2.2. Orbit Determination to the asteroid Eros was the first to use optical tracking of craters for navigation, but these craters were manually Kepler’s laws of orbital motion state that the area swept chosen [MC03]. The Hayabusa spacecraft, which con- by the line between a body and its orbit center in a given ducted a sample return mission to the asteroid Itokawa, amount of time is equal throughout an orbit [Sid01]. Ke- used manual tracking of landmarks for localization dur- plerian are elliptical in shape with a focal point at ing descent [KHK+09]. Hayabusa also used a long range the barycenter of the system. Consequently, orbits are (50 m to 50 km) LIDAR and a short range laser range uniquely determined by several measurements of latitude, finder to determine its altitude [KHK+06]. Li presents longitude, over time as depicted in Fig. 1. a feature-based navigation routine for asteroid landing [Li08]. This method provides position and orientation Elliptical orbit of a spacecraft about a planetary body is state, although this is also defined relative to the land- described by the six classical : marks, not with respect to a global map.

A proposed method for autonomous orbit determination • a: semi-major axis for the NEAR is described in [MC03]. The reliance of • e: eccentricity this approach on the detection on circular crater features • i: inclination is somewhat limiting. As noted in [SL08], craters are • ω: argument of periapsis hard to detect when the angle is high, since there are no shadows to define the edges of the crater rim. In ad- • Ω: right ascension of the ascending node (RAAN) dition, craters appear different at different altitudes, mak- • M: mean anomaly ing them unsuitable for use over the range of altitudes at which a spacecraft localization is needed in planetary The parameters a and e describe the size and shape of the landing missions. ellipse. The parameters i, ω and Ω describe the orienta- tion of the ellipse in space, (See Fig. 2). M describes where the spacecraft is in the orbit, although the related parameter θ, or true anomaly, is often used. 2. METHOD Orbit determination is performed in two stages. First, inclination and RAAN are determined by fitting a plane to unit vectors that extend from the orbit center towards 2.1. Overview the spacecraft. Once the plane has been determined, the noisy unit vectors are projected onto the plane to deter- mine spacecraft angular motion over time. Kepler’s laws TROD works by matching imagery obtained in orbit with describing the relationship between angular motion over orthorectified maps of the planetary surface to determine time are inverted using non-linear least squares to deter- latitude and longitude over time. Kepler’s laws are then mine a and e. The argument of periapsis is then deter- applied to determine orbital parameters. mined from the other five parameters and the measure- Z nˆ is chosen to agree with the average normalized cross product of adjacent unit vectors. RANSAC is used to re- i ject spurious measurements. θ The measurement coordinate system is defined by setting the zˆm axis equal to nˆ and aligning the yˆm axis with the cross product of nˆ and rˆ0. The xˆm axis completes the ω right-handed coordinate system. Y Ω zˆm =n ˆ (6) yˆm =n ˆ × rˆ0 (7)   xˆm = nˆ × rˆ0 × zˆ (8)

X The inclination of the orbit, i, is defined as the angle be- tween the orbital and equatorial planes:

Figure 2: Classical orbital elements: i, the inclination, T zˆ = [0, 0, 1] (9) is the angle between the normal of the orbital plane and e T the z-axis; Ω, the RAAN, is the angle between the x-axis i = arccos(ˆzmzˆe) (10) and the line of nodes, or the intersection between the xy- plane and the orbital plane; ω, the argument of periapsis, Ω is calculated by taking the cross product of zˆe and zˆm is the angle between the line of nodes and the periapsis; to get the ascending node line vector, l. The ascending θ, the true anomaly, is the angle between a vector to the node line vector is then projected onto both the xˆ and periapsis and a vector to the spacecraft’s current position. m yˆm axes to determine Ω.

l =z ˆe × zˆm (11) ment times. Spurious measurements are rejected using Ω = atan2 yˆT l, xˆT l (12) RANSAC [FB81]. m m

2.2.2. Fitting the Keplerian Parameters 2.2.1. Fitting the Orbital Plane

Kepler’s laws state that the vector between a As the spacecraft orbits, it images the surface below to and the body which it is orbiting sweeps equal areas in determines its latitude, φ, and longitude, λ. The latitude 3 equal time. The period of an orbit is proportional to a 2 , and longitude coordinates are transformed into unit vec- where a is the semi-major axis. Combining these laws tors and rotated into the J2000 frame: and knowledge of the gravitational constant of the central body, µ, the angle traveled by the spacecraft in a given rˆf = [cos(φ) cos(λ), cos(φ) sin(λ), sin(φ)]T (1) time interval can be determined. The equation relating rˆ = R(t)ˆrf (2) time and angle for an elliptical orbit is [Sid01]:

Where rˆf is the unit vector in the moon-fixed frame, R(t) t(a, e, θ) = is the rotation between the moon-fixed latitude and lon- 3 " "r # √ # a 2 1 − e θ  e 1 − e2 sin θ gitude measurements and the J2000 reference frame at √ 2 arctan tan − the time of the first measurement, and rˆ is the unit vector µ 1 + e 2 1 + e cos θ represented in the J2000 frame. (13)

In the J2000 frame, the unit vectors serve as noisy mea- Where t(a, e, θ) is time since periapsis and θ is the angle surements of the orbital plane. The smallest eigenvalue from the periapsis. of the covariance matrix of the unit vectors corresponds to the eigenvector representing the normal of the plane. The measurement coordinate system is not aligned with Singular Value Decomposition is used to find the eigen- the periapsis, so the offset in time and angle between the vector and the normal: periapsis and the first measurement must be recovered. Define α˜i as the measurement angle in the measurement P T Σ = i rˆirˆi (3) coordinate frame and αp as the offset between the orbital [U, S, V ∗] = svd(Σ) (4) coordinate system and the measurement coordinate sys- ∗ tem (Figure 1): nˆ =v ˆmin (5) T T α˜i = atan2(ˆymrˆi, xˆmrˆi) (14) ˜ The sign of nˆ is arbitrary and noise in the points can cause θi =α ˜i + αp (15) the normal to point in either direction. The direction of tp = t(a, e, αp) (16) Equation 13 can now be used to define an objective (Equation 17) for optimization. The objective is opti- mized using non-linear least squares.

 2 J(e, a, αp) = ti −t(e, a, αp)−t(e, a, α˜i +αp) (17)

The remaining parameters, ω and M, are computed di- rectly as follows [Sid01]: Figure 3: Initial errors in latitude and longitude are cor-   rected by correlating the orthorectified image (center) r0z ω = atan2 sin(i) , r0x cos(Ω) + r0y sin(Ω) + αp with the map (left). The resulting correlation peak (right) p µ is used as a rough estimate of the location of the craft. Mi = (ti − tp) a3

2.3. Terrain Matching

To determine latitude and longitude of the spacecraft, im- ages are taken in flight and are then registered to prior ter- rain maps. Terrain matching occurs in three phases: im- age rectification, coarse correlation, and fine adjustment. Rectification scales and transforms the image to roughly match the scale and orientation of the map. Coarse cor- relation finds a low-fidelity correspondence between the terrain and the rectified image and accounts for gross er- rors in initial latitude, longitude, and altitude. Fine ad- justment accounts for local variation in terrain within the map and refines the coarse fit. Figure 4: The initial location determined by correlation is refined by finding Harris corners in the rectified image, Rectification is performed using a prior estimate of the projecting these locations into the map, and correlating spacecraft altitude and orientation. The corners of the each patch with a constrained area of the map. Final lo- image are projected to 2D points on the map using a flat cation is determined using RANSAC. ground assumption. These four point correspondences define a homography that roughly maps camera points to map points. Using the estimated homography, the image near the expected location of the feature. This correlation is warped to match the orthorectified map. The resulting is performed in the spatial domain and the peak of the warped image has the same scale and orientation as the correlation determines the location of the feature within map, and can now be correlated. This process is similar + the map. The set of feature correspondences are then pro- to that used by Trawny, et al. [MTR 09]. cessed using RANSAC to filter spurious measurements and determine the registration between the camera and The rectified image is downsampled and correlated with map (Fig. 4). a region of interest (ROI) from the map. The ROI is fo- cused on the estimated image center as determined dur- ing rectification and is sized to be three times larger than rectified image in map coordinates. This allows for er- 3. RESULTS ror in the prior location estimate. Due to the size of the maps, correlation is performed in the frequency domain. Fourier transforms of the maps are precomputed to limit TROD performance was evaluated in two stages, first on-line computation time, which is essential for running with simulated orbit latitude/longitude measurements numerous iterations of the routine. The peak of the rough generated with AGI’s satellite toolkit (STK) [Ana11] correlation is used to determine an ROI for a refined esti- and then with latitude/longitude measurements generated mate of location (Fig. 3). from the output of a Lunar rendering engine. With the simulated measurements, the sensitivity of the orbit fit Given a coarse estimate of alignment between the image was tested by varying each of the six parameters individ- and the map, a fit is performed to correct for local terrain ually. Then, normally distributed noise was added to each shape and attitude error between the camera and the map. of the simulated orbits to determine the effect of imper- The 50 strongest Harris corners [HS88] in the rectified fect data. Lastly, the technique was validated by running image are projected into the map using the inverse camera the visual terrain-matching simulation and then using its matrix and the pose estimate from the coarse registration. output latitude/longitude data as the input for the orbit fit. A small template from the rectified image around the fea- ture is then correlated with a region of interest in the map All results were analyzed using Circular Error Probabil- ity (CEP) as the error metric. The CEP is the radius of 3.2. Performance with Terrain Matching the sphere centered on the true position which contains a given percentage the predicted values. The CEP95, for Orbit determination performance with terrain matching instance, is the spherical radius containing 95% of the was evaluated on 15 orbits. The orbits were generated by predicted results. For all orbits, CEPs of max and mean varying the inclination, periapsis, and mean anomaly of error were computed by sampling positions along the true the basis orbit. This produces varied ground tracks over and measured orbits at ten second intervals. The distance the planetary surface and accounts for variation in match- between the predicted and actual locations was computed ing performance as a function of terrain appearance. and the mean distances were recorded. The CEP was then calculated for the collection of orbits under consideration. The terrain matching dataset differs from the orbits in section 3.1 in two important ways. First, half of each orbit is in shadow and therefore only half of the mea- surements from each orbit can be used. Second, due to 3.1. Performance with Normally Distributed Noise lengthy rendering times the duration of each orbit is lim- ited to a single full orbit. These two effects significantly reduce the number of measurements available during or- Orbit determination performance was characterized by bit determination. Figure 12 shows the effect of decreas- generating a set of orbits with a wide range of orbital ing the number of measurements available to fit the orbit. parameters. Each orbit was sampled regularly in time Note that although error increases, as more points are col- to determine latitude and longitude relative to the plan- lected this noise will decrease and approach the results in etary surface. Latitude and longitude were perturbed by Figure 11. adding normally distributed noise, and the fitting algo- rithm was applied. Because the noise was normally dis- Despite these challenges, orbit determination with visual tributed, RANSAC was disabled. Each noise level was matching achieves error only twice as high as in the ex- evaluated 100 times per orbit. CEP was measured as a periments from section 3.1. Typical mean position errors function of the six parameters. are below 6 km and almost all errors are below 10 km (Table 2). All experiments except those with high eccentricity use the parameters in Table 1 as the basis for the orbit and Table 2: CEPs with Terrain Matching (km) vary one parameter. Experiments with high eccentricity use the basis orbit parameters, except a = 3550 km to CEP50 CEP75 CEP80 CEP90 avoid impacting the surface of the moon at higher eccen- tricities. 5.6 6.1 9.9 18.1

Table 1: Basis Orbit Parameters 4. CONCLUSIONS AND FUTURE WORK a e i ω Ω M0 noise (σ) 2250 km 0.01 45◦ 45◦ 45◦ 45◦ 0.1◦ This paper has presented a method for determining orbits by correlating on-orbit imagery with a map. The tech- nique fits the six orbital parameters required to define a Figure 5 shows the variation in CEP as a is varied from Keplerian orbit. Because the technique uses only camera from 1800 km to 3600 km. Noise is held constant at 0.1 data, it is appropriate for autonomous spacecraft. Results degree. At low altitudes, error in a is consistently less from 500km Lunar orbits demonstrate that this technique than three meters with a CEP95 of 2.6 km with a equal to is viable. 1800km. CEPs increase with a and e. This is expected, since the fit relies on accurate angular measurements. As Better than 1 km accuracy can be achieved by improving the distance from the planet increases, sensitivity to error the performance of terrain matching. Increasing map res- correspondingly increases. Inclination and RAAN have olution and incorporating digital elevation data will sig- essentially no effect on position error, as they are deter- nificantly enhance matching capability and accomplish mined entirely by the plane fit (Figures 7 and 8). Because this goal. ω and M cause variation in the portion of the orbit that is observed by the fitter, error increases slightly and period- Kepler’s laws assume point masses, but real planets have ically as ω and M vary (Figures 9 and 10). lumpy mass distributions. Low orbits are affected by gravity anomolies and high orbits are perturbed by third Terrain matching performance is expected to vary as bodies. An important next step is to incorporate more a function of altitude, camera configuration, and off- comprehensive gravity models into the orbit determina- nominal lighting effects (e.g., lens flare). To characterize tion algorithm. the effect of different levels of noise on fit performance, normal distribution noise was varied from 0.0◦ to 0.5◦ Finally, adaptation of TROD for use with Kalman Fil- and CEP was measured. Figure 11 shows that increasing tering techniques will enable real-time low-latency orbit noise causes linearly increasing error in the fit. determination. This will close the autonomy loop and in

20 CEP50 10 CEP50 CEP80 15 CEP80 CEP90 CEP90 5 CEP95 10 CEP95

5 Mean Distance (km) 0 Mean Distance (km) 1800 2000 2200 2400 2600 2800 3000 3200 3400 3600 0 0.05 0.1 0.15 0.2 0.25 0.3 0.35 0.4 0.45 0.5 Semi−major axis(km) Eccentricity Figure 5: CEPs as a function of a, in km. Figure 6: CEPs as a function of eccentricity, e. 5 CEP50 4 CEP80 3 CEP50 CEP90 CEP80 3 CEP90 CEP95 2 CEP95 2

1 1 Mean Distance (km) Mean Distance (km) 0 20 40 60 80 100 120 140 160 180 0 50 100 150 200 250 300 350 Inclination (deg) RAAN (deg)

Figure 7: CEPs as a function of inclination, i, in degrees. Figure 8: CEPs as a function of argument of RAAN, Ω, in degrees. 10 CEP50 8 CEP50 CEP80 CEP80 CEP90 6 CEP90 5 CEP95 CEP95 4

2 Mean Distance (km) 0 Mean Distance (km) 0 50 100 150 200 250 300 350 0 50 100 150 200 250 300 350 Argument of Periapsis (deg) Initial Mean Anomaly (deg)

Figure 9: CEPs as a function of argument of periapsis, ω, Figure 10: CEPs as a function of argument of mean in degrees. anomaly, M, in degrees.

50 CEP50 30 CEP50 40 CEP80 CEP80 30 20 CEP90 CEP90 CEP95 20 CEP95 10 10 Mean Distance (km) Mean Distance (km) 0 0 0 0.05 0.1 0.15 0.2 0.25 0.3 0.35 0.4 0.45 0.5 0.04 0.06 0.08 0.1 0.12 0.14 0.16 0.18 0.2 Noise Noise

Figure 11: CEPs as a function of added noise. Figure 12: CEPs as a function of added noise for short estimation periods as in terrain matching experiments. turn enable spacecraft that can capture, orbit, and descend [HS88] C. Harris and M. Stephens. A Combined without human intervention. Corner and Edge Detection. In Proceed- ings of The Fourth Alvey Vision Conference, pages 147–151, 1988. REFERENCES [KHK+06] T. Kubota, T. Hashimoto, J. Kawaguchi, M. Uo, and K. Shirakawa. Guidance and www. [Ana11] Analytical Graphics Inc. STK 9.2.2. navigation of hayabusa spacecraft for aster- agi.com , 1989–2011. oid exploration and sample return mission. + [BRK 02] S. Bhaskaran, J. E. Riedel, B. Kennedy, T.C. In SICE-ICASE International Joint Confer- Wang, and R.A. Werner. Navigation of the ence, Bexco, Busan, Korea, 2006. Deep Space 1 spacecraft at Borrelly. Techni- cal report, NASA, 2002. [KHK+09] T. Kubota, T. Hasimoto, J. Kawaguchi, [CSB83] J. K. Campbell, S. P. Synnott, and G. J. Bier- K. Shirakawa, H. Morita, and M. Uo. Vision man. Voyager orbit determination at jupiter. based navigation by landmark for robotic ex- IEEE Transactions on Automatic Control, plorer. In Proceedings of the 2008 IEEE AC-28(3), 1983. International Conference on Robotics and Biomimetics, Bangkok, Thailand, 2009. [FB81] M. A. Fischler and R. C. Bolles. Random sample consensus: A paradigm for model fit- [Li08] S. Li. Computer vision based autonomous ting with applications to image analysis and navigation for pin-point landing robotic automated cartography. Comm. of the ACM, spacecraft on asteroids. In Intelligent 24:381–395, 1981. Robotics and Applications, Lecture Notes landmark tracking orbit determination strat- egy. In Proceedings of AAS/AIAA Astrody- namics Specialist Conference, Big Sky, MO, 2003. [MTR+09] A. Mourikis, N. Trawny, R. Roumeliotis, A. Johnson, A. Ansar, and A. Matthies. Vision-aided inertial navigation for space- craft entry, descent, and landing. In IEEE Transactions on Robotics, volume 25, April 2009. [PBC+10] R. S. Park, S. Bhaskaran, Y. Cheng, A. John- son, N. E. Lisano, and A. A. Wolf. Tra- jectory reconstruction of sound rocket us- ing inertial measurement unit and landmark data. Journal of Spacecraft and Rockets, 47(6):1003–1009, 2010. [RBS+97] J.E. Riedel, S. Bhaskaran, S.P. Synnot, S.D. Desai, W.E. Bollman, P.J. Dumont, C.A. Halsell, D. Han, B.M. Kennedy, G.W. Null, Jr. Owen, W.M., R.A. Werner, and B.G Williams. Navigation for the new millen- nium: Autonomous navigation for Deep- Space 1. In Proc. Int. Symposium Space Flight Dynamics, 1997. [Sid01] M. J. Sidi. Spacecraft Dynamics & Control: A Practical Engineering Approach. Cam- bridge University Press, 2001. [SL08] L. Singh and S. Lim. On Lunar on-orbit vision-based navigation: Terrain mapping, feature tracking driven EKF. In AIAA Guid- ance, Navigation and Control Conference, Figure 13: Three example orbit fits using terrain match- Honolulu, HI, 2008. ing. Green circles show locations where measurements + were taken. Red circles show the match location. Ter- [TMR 06] N. Trawny, A. Mourikis, S. Roumeliotis, rain matching performs well in some locations (top, mid- A. Johnson, and J. Montgomery. Vision- dle) and poorly in others. Significant error is handled by aided inertial navigation for pin-point land- RANSAC enabling orbit determination despite spurious ing using observations of mapped land- measurements. marks. Journal of Field Robotics, 2006. [TMR+07] N. Trawny, A. Mourikis, S. Roumeliotis, A. Johnson, J. Montgomery, A. Ansar, and in Computer Science, volume 5315, pages L. Matthies. Coupled vision and inertial nav- 1115–1126, 2008. igation for pin-point landing. In NASA Sci- [MC03] J. K. Miller and Y. Cheng. Autonomous ence and Technology Conference, 2007.