Academia.eduAcademia.edu

Mobile Robot Rough-Terrain Control (RTC) for Planetary Exploration

2000, Volume 7B: 26th Biennial Mechanisms and Robotics Conference

Mobile robots are increasingly being developed for high-risk missions in rough terrain situations, such as planetary exploration. Here a rough-terrain control (RTC) methodology is presented that exploits the actuator redundancy found in multi-wheeled mobile robot systems to improve ground traction and reduce power consumption. The methodology “chooses” an optimization criterion based on the local terrain profile. A key element of the method is to be able to estimate the wheel-ground contact angles. A method using an extended Kalman filter is presented for estimating these angles using simple on-board sensors. Simulation results for a wheeled micro-rover traversing Mars-like terrain demonstrate the effectiveness of the algorithms.

MOBILE ROBOT ROUGH-TERRAIN CONTROL (RTC) FOR PLANETARY EXPLORATION Karl Iagnemma Massachusetts Institute of Technology Department of Mechanical Engineering Cambridge, MA 02139 USA Steven Dubowsky* Massachusetts Institute of Technology Department of Mechanical Engineering Cambridge, MA 02139 USA ABSTRACT Mobile robots are increasingly being developed for highrisk missions in rough terrain situations, such as planetary exploration. Here a rough-terrain control (RTC) methodology is presented that exploits the actuator redundancy found in multi-wheeled mobile robot systems to improve ground traction and reduce power consumption. The methodology “chooses” an optimization criterion based on the local terrain profile. A key element of the method is to be able to estimate the wheelground contact angles. A method using an extended Kalman filter is presented for estimating these angles using simple onboard sensors. Simulation results for a wheeled micro-rover traversing Mars-like terrain demonstrate the effectiveness of the algorithms. INTRODUCTION Mobile robots are increasingly being developed for highrisk missions in rough terrain environments. One successful example is the NASA/JPL Sojourner Martian rover (Golombek, 1998). Future planetary missions will require mobile robots to perform difficult tasks in more challenging terrain than encountered by Sojourner (Hayati et al., 1996; Schenker, et al. 1997). Other examples of rough terrain applications for robotic systems can be found in the forestry and mining industries, and in hazardous material handling applications, such as the Chernobyl disaster site clean-up (Cunningham et. al., 1998; Gonthier and Papadopolous,1998; Osborn, 1989). In rough terrain, it is critical for mobile robots to maintain good wheel traction. Wheel slip could cause the rover to lose control and become trapped. Substantial work has been done on traction control of passenger vehicles on flat roads (Kawabe et al., 1997). This work is not applicable to low-speed, rough terrain rovers because in these vehicles wheel slip is caused primarily by kinematic incompatibility or loose soil conditions, rather than “breakaway” wheel acceleration. Traction control for low-speed mobile robots on flat terrain has been studied (Reister and Unseren, 1993). Later work has considered the important effects of terrain unevenness on traction control * ASME Fellow 1 (Sreenivasan and Wilcox, 1996). This work assumes knowledge of terrain geometry and soil characteristics. However, in such applications as planetary exploration this information is usually unknown. A fuzzy-logic traction control algorithm for a rocker-bogie rover that did not assume knowledge of terrain geometry has been developed (Hacot, 1998). This approach is based on heuristic rules related to vehicle mechanics. Knowledge of terrain information is critical to the traction control problem. An key variable for traction algorithms is the contact angles between the vehicle wheels and the ground (Sreenivasan and Wilcox, 1994; Farritor et al., 1998). Measuring this angle physically is difficult. Researchers have proposed installing multi-axis force sensors at each wheel to measure the contact force direction, and inferring the groundcontact angle from the force data (Sreenivasan and Wilcox, 1994). However, wheel-hub mounted multi-axis force sensors would be costly and complex. Complexity reduces reliability and adds weight, two factors that carry severe penalties for planetary exploration applications. This paper presents a control methodology for vehicles with redundant drive wheels for improved traction or reduced power consumption. In highly uneven terrain, traction is optimized. In relatively flat terrain, power consumption is minimized. A method is presented for estimating wheelground contact angles of mobile robots using simple on-board sensors. The algorithm is based on rigid-body kinematic equations and uses sensors such as vehicle inclinometers and wheel tachometers. It does not require the use of force sensors. The method uses an extended Kalman filter to fuse noisy sensor signals. Simulation results are presented for a planar two-wheeled rover on uneven Mars-like soil. It is shown that the wheelground contact angle estimation method can accurately estimate contact angles in the presence of sensor noise and wheel slip. It is also shown that the rough-terrain control (RTC) method leads to increased traction and improved power consumption as compared to traditional individual-wheel velocity control. MOBILE ROBOT ROUGH-TERRAIN CONTROL (RTC) Theoretical Background Consider an n-wheeled vehicle on uneven terrain, as shown in Figure 1. The vehicle is assumed to be skid-steered, so only forces in the axial plane of the vehicle are considered. It is also assumed that each wheel makes contact with the terrain at a single point, denoted Pi, i=1,…,n. This is a reasonable assumption for vehicles with rigid wheels (such as Sojourner) moving on firm terrain. Vectors from the points Pi to the vehicle center of mass are denoted Vi=[Vix Viy]T, i=1,…,n and are expressed in the corresponding local frame {xyzi} fixed at Pi. The 3x1 vector F is expressed in the inertial frame {xyzo} and represents the summed effects of vehicle gravitational forces, inertial forces, forces due to manipulation, and forces due to interaction with the environment or other robots. Figure 1– N Wheeled Vehicle on Uneven Terrain A wheel-ground contact force exists at each point Pi and is denoted fi=[Ti N i] T (see Figure 2). The vector is expressed in the local frame {xyzi} and can be decomposed into a tractive force Ti tangent to the wheel-ground contact plane and a normal force Ni normal to the wheel-ground contact plane. It is assumed that there are no moments acting at the wheel-ground interface. The angles γi, i=1,…,n represent the angle between the horizontal and the wheel-ground contact plane. where i R j represents a 2x2 matrix transforming a vector expressed in frame j to one in frame i. Equation (1) represents the quasi-static force balance on the vehicle and is often referred to as the force distribution equations (Hung et al., 1999). It neglects dynamic effects. These will be small in low-speed planetary exploration vehicles. Force distribution has been studied for general kinematic chains and legged vehicles (Kumar and Waldron, 1988; Kumar and Waldron, 1990). Efficient formulation of the force distribution equations for more general vehicles has been addressed (Hung et al., 1999) Equation (1) can be written in a general matrix form as: Gx = F (2) where the matrix G is a function the vehicle geometry, the wheel-ground contact locations Pi and the wheel-ground contact angles γi, x=[T1 N1 … Tn Nn]T, and F=[Fx Fy Mz]T. The system of equations represents an underconstrained problem. There are an infinite number of wheel-ground contact forces Ti and Ni that balance the vector F. In general, a planar system with n contact points possesses (2n-3) degrees of redundancy. The purpose of rough terrain control is to choose a set of wheel-ground contact forces (which are modified by means of independently controlled motor torques) that satisfy the force distribution equations and the problem constraints while optimizing an aspect of system performance. Wheel-Ground Contact Force Optimization To enable planetary exploration mobile robots to operate in highly challenging terrain while maintaining traction and traversing long stretches of benign terrain with good power efficiency, the optimization of the wheel-ground contact forces is performed using two criteria: maximum traction or minimum power consumption. These criteria are discussed below. Optimization Criteria The optimization criteria for maximum traction at the wheel-ground interface is developed based on the general observation that for most soils the maximum tractive force a soil can support increases with increasing normal force (Bekker, 1969). Thus to avoid soil failure and wheel slip the control algorithm should minimize the ratio of the tractive force to the normal force. A function R representing this ratio can be used an objective function for optimization of the force distribution equations: R = max Figure 2– Wheel-Ground Interface on Uneven Terrain i For the planar system above the quasi-static force balance equations can be written as: 0 V1y R1 - V1x V2y 0 R2 L - V2x L Vny 0 Rn - Vnx f1 Fx M = Fy fn (1) Mz 2 Ti ? Ni ? (3) Similar criteria has been developed in (Sreenivasan and Wilcox, 1994) and an analytical solution to the optimization problem has been developed for a two-wheeled vehicle. For the general problem the optimal force distribution (Equation (1)) can be solved by standard optimization techniques yielding the optimal actuator torques (Chung and Waldron, 1993). We can formally state the optimization problem as follows: Minimize R subject to the equality constraint Gx = F . An optimization criteria for minimum power consumption can be developed based on the fact that the power consumed by a DC motor-driven wheeled vehicle using PWM amplifiers can be estimated by the power dissipation in the motor resistances (Dubowsky et al., 1995). Power consumption of the vehicle is related to the motor torques as: P= Rn 2 n K t2 i =1 τ i2 (4) where R is the motor resistance, Kt is the motor torque constant, n is the motor gear ratio, and τi is the torque applied by the ith motor. The power consumption can then be related to the tractive force Ti by: P = Rn 2 n K t2 r 2 i =1 T i2 (5) where r is the wheel radius. The function P can be used as an objective function for power minimization. Based on Equations (3) and (5) a dual-criteria objective function that optimizes for maximum traction or minimum power consumption depending on the terrain profile can be developed. In highly uneven terrain it would maximize traction. In relatively flat terrain it would minimize power consumption. A measure of terrain unevenness can be formulated based on the values of the wheel-ground contact angles. Consider the function S: S= 1 if max {γ i i 0 }> C otherwise (6) τ imin ≤ (Ti ?r ) ≤ τ imax ∀i, i = 1K n (9) The third is that the tractive force exerted on the ground must not exceed the maximum force that the ground can bear. The simplest approximation of this constraint is a Coulomb friction model: T i ≤ µN i ∀i , i = 1K n (10) This approach fits conveniently into an optimization framework. However, it is too simplistic a model for roughterrain. Substantial work has been done to characterize offroad wheel-ground interactions (Bekker, 1966). In general, it is claimed that the maximum tractive force a wheel-ground interface can bear is a function of the normal force, terrain properties, and wheel slip condition. Incorporating a realistic model of the wheel-ground interaction constraint is a challenging and current area of research. In the simulations presented later, a realistic off-road terrain model is used. WHEEL-GROUND CONTACT ANGLE ESTIMATION To properly formulate the force-distribution equations for wheeled robotics, the wheel-ground contact angles γ1,…γn must be known. As discussed earlier, direct measurement of these angles is difficult. Below, a method is presented for estimating these contact angles using on-board sensors. Consider the planar skid-steered two-wheeled system on uneven terrain, shown in Figure 3. As before, each wheel makes contact with the ground at a single point. The vehicle pitch, α, is defined with respect to the horizon, X. The wheel centers have velocities ν1 and ν2 parallel to the local wheelground tangent plane due to the rigid wheel-ground assumption. The distance between the wheel centers is l. where C is an arbitrary threshold level. This function distinguishes between benign and challenging terrain. Of course, there are numerous other methods to assess terrain difficulty. For example, a vehicle equipped with a threedimensional vision system could characterize unevenness by considering local terrain elevation data. An objective function which combines Equations (3), (5), and 6) can then be expressed as: Q = RS + T (1 − S ) (7) Thus the vehicle force distribution will be optimized for either maximum traction or minimum power consumption, depending on the local terrain profile. Problem Constraints Optimization of the force distribution problem must consider physical constraints of the system. The first is based on the goal of keeping all wheels in contact with the ground, or: N i > 0 ∀i , i = 1K n (8) The second constraint is that the joint torques must remain within the saturation limits of the actuator, or: 3 Figure 3 – Planar two-wheeled system on uneven terrain For this system, the following kinematic equations can be written: ν 1 cos (γ 1 − α ) = ν 2 cos (γ 2 − α ) ν 2 sin (γ 2 − α )− ν 1 sin (γ 1 − α )= l α& (11) (12) Equation (11) represents the constraint that the wheel center distance l does not change. The validity of this assumption will be examined later. Equation (12) is a rigid- body kinematic relation between the velocities of the wheel centers and the vehicle pitch rate α& . Combining Equations (11) and (12) results in: sin (γ 2 − α − (γ 2 − α ) ) = l α& cos (γ 2 − α ) ν1 (13) where: θ …γ 2 − α , β …α − γ 1 , a …l α& ν1 , b …ν 2 ν1 With the above definitions Equations (13) and (11) become: (b sin θ + sin β )cos θ = a cos θ (14) cos β = b cos θ (15) In most cases Equations (14) and (15) can be solved for the ground contact angles γ1 and γ2 providing that the pitch, pitch rate, and wheel center velocities can be measured. Then the angles are given by: γ 1 = α − a cos ( h ) (16) γ 2 = a cos ( h ) + α b (17) where: 1 h… 2a 2 + 2b 2 + 2a 2b 2 − a 4 − b 4 − 1 2a The above solution is for vehicles with a rigidly-connected wheel pair. The approach can be directly extended to vehicles with greater than two wheels. There are three special cases that must be considered. The first special case occurs when the vehicle is stationary. Equations (16) and (17) do not yield a solution. This results from the fact that a robot in a fixed configuration can have an infinite set of possible contact angles at each wheel. The second special case occurs when cosθ is equal to zero. This occurs when the front wheel contact angle is offset by ±π/2 radians from the pitch angle, such as when a vehicle on flat terrain encounters a vertical obstacle. In this case, the motion of the vehicle can be viewed as pure rotation about a fixed rear wheel center (see Figure 4). Equation (14) then degenerates, and the system is unsolvable. However, Equations (11) and (12) can be simplified by the observation that ν1 is zero, and the kinematic equations can be written as: v 2 cos (γ 2 −α ) = 0 (18) v 2 sin (γ 2 − α )= l α& (19) The variable γ1 is undefined in Equations (18) and (19) since wheel one is stationary, and: γ2 =α + π sgn (α& ) 2 (20) 4 Figure 4 - Kinematic description of case where cosθ=0 The third special case occurs on terrain where the front and rear wheel-ground contact angles are identical (see Figure 5ac). In this case the pitch rate α& is zero and the ratio of ν2 and ν1 is unity. This implies that the quantity h in Equations (15) and (16) is undefined and the system of equations has no solution. However, it should be noted that the ground contact angle equations are expressed as functions of the vehicle pitch and pitch rate, α and α& , and the wheel center speeds, ν1 and ν2. The pitch and pitch rate can be easily measured with rate gyroscopes or inclinometers. The wheel center speeds can be estimated with knowledge of the wheel angular rate, assuming small wheel slip. Thus it is easy to detect the flat terrain (Figure 5a) from a constant pitch angle. Then the contact angles are equal to the pitch angle. In cases such as in Figure 5b and Figure 5c the pitch angle rate is zero momentarily. If the terrain profile varies slowly with respect to the data sampling rate, the ground contact angles will change slowly from the previously computed ground contact angles. Thus, previously estimated ground contact angles can be used in situations where a solution to the estimation equations does not exist. (a) (b) (c) Figure 5 - Terrain profiles with α& =0 and ν2/ν1=1 The above results suggest that wheel-ground contact angles can be estimated with common, low-cost sensors. However, this estimate can be corrupted by sensor noise and wheel slip. Here an Extended Kalman Filter (EKF) is developed to compensate for these effects. EXTENDED KALMAN FILTER IMPLEMENTATION EKF Background An Extended Kalman Filter is an effective framework for fusing data from multiple noisy sensor measurements to estimate the state of a nonlinear system (Brown and Hwang, 1997). In the EKF framework the process and sensor signal noise are assumed to be unbiased Gaussian white-noise with known covariance. These are reasonable assumptions for the signals considered in this research. Consider a given system with dynamic equations: x& = f (x , w , v , t ) (21) where w and v represent measurement and process noise vectors. A linearized continuous-time state transition matrix can be defined as: F= ƒf ˆ (x ) ƒx (22) ˆ where x is the current state estimate. The system measurement vector z is defined as: z = h( x , v ) (23) with measurements acquired at each time step k. In general, computation of the EKF involves the following steps: ˆ 1. Initialization of the state estimate x and a covariance matrix, P. ˆ 2. Propagation of the current state estimate x (from a discrete-time representation of Equation (22)) and covariance matrix P at every time step. The matrix P is computed as: Pk = Fk Pk FkT + Qk Measurements are taken at every time step during vehicle motion. The measurement error covariance matrix R is assumed to be diagonal. The elements of R corresponding to sensed quantities, such as the pitch and wheel center speeds, can be estimated by off-line measurement of the sensor noise. The elements of R corresponding to unmeasured quantities, such as the ground contact angles, can be computed by linearizing Equations (15) and (16) and summing the contributions of the measured noise terms. Computation of the EKF (i.e. Equations (24) through (26)) involves several matrix inverse operations. However, it should be noted that the matrices involved are generally near-diagonal. Efficient inversion techniques can be used to reduce computational burden. Thus, EKF computation remains relatively efficient and suitable for on-board mobile robot implementation. SIMULATION RESULTS The performance of the multi-criterion rough-terrain control (RTC) algorithm and traditional velocity control were compared in simulation. The simulated system is a planar, twowheeled 10 kg. vehicle traveling over undulating terrain, see Figure 6. The wheel radius r is 10 cm and its wheel width w is 15 cm. Measured quantities are vehicle pitch and wheel angular velocities. Sensor noise was modeled by white noise of standard deviation approximately equal to 5% of the full-range values. (24) where Q is the system process noise matrix and is assigned based on the physical model of the system. 3. Updating the state estimate and covariance matrix as: ˆ ˆ ˆ x k = x k + K k z k − h(x k ) (25) Pk = [I − Kk Hk ]Pk (26) and Figure 6 – Two-wheeled planar rover where the Kalman gain matrix K is given by: [ Kk = Pk HTk Hk Pk HTk + R k ] −1 (27) where R is the measurement error covariance matrix and H is a matrix relating the state x to the measurement z. EKF Implementation For vehicle wheel-ground contact angle estimation, the EKF computes a minimum mean square estimate of the state vector x = [α α& ν 1 ν 2 γ 1 γ 2 ]T . Since vehicle pitch can be measured and the wheel center speeds can be approximated from knowledge of the wheel angular velocities and radii, the EKF measurement vector is defined by z = [α ν 1 ν 2 ]T . 5 The force distribution equations for the simulated system can be written as: cos (γ 1 ) − sin (γ 1 ) cos (γ 2 ) − sin (γ 2 ) sin (γ 1 ) V1 y cos (γ 1 ) −V 1x sin (γ 2 ) V2 y cos (γ 2 ) −V 2x T1 Fx N1 = Fy T2 Mz N2 (28) This system of equations possesses (2n-3)=1 degree of redundancy. Thus, a tractive force can be viewed as a free variable that can be selected based on the dual-criteria optimization method discussed above. The terrain was modeled as a moderately dense soil similar to that which has been observed on Mars (NASA 1988; Rover Team, 1997). The following parameters were used: − Cohesion c=1.0 kPa − Soil internal slip angle θ=35° − Soil bulk density ρ=1500 kg/m3 − Sinkage coefficient ns=1 − Frictional mod. of deformation Kφ=850 kN/mn+2 − Coefficient of soil slip k=0.03 m At each simulation time increment the wheel sinkage, motion resistance, and wheel thrust was computed as a function of the soil parameters and the applied wheel torque. Wheel sinkage was computed in order to determine the motion resistance due to soil compaction. Sinkage was computed for each wheel i as (Bekker, 1969): zi = 3N i Both the velocity-controlled system and the RTC system successfully traversed the benign terrain. However, the average power consumed by the RTC system was 2.9 W compared to 4.7 W by the velocity-controlled system, an improvement of 38.3%. This power savings is due to reduced wheel slip, see Figure 8. The RTC system has an average slip ratio of 5.3% during the traverse while the velocity controlled system has an average slip of 9.4%. The dual-criteria optimization was in energy-minimization mode during most of the traverse. Thus, even in relatively gentle terrain RTC can be beneficial. 2 2 n s +1 (29) (3 − n s )wK φ 2 r The motion resistance due to soil compaction was determined by (Bekker, 1969): R ci = wz i n s +1 K c + Kφ √ w ↵ ns +1 (30) The wheel thrust was computed as (Bekker, 1969): 1− K s TH i = (cAw + N i tan(θ ) ) ( − S ( A /K s ) ) 1− e (31) SAw √ ↵ Note that Equation (31) is a relation for the thrust of a rigid wheel traveling through soft soil. This relationship was adopted in an attempt to emulate planned planetary rovers, which generally possess rigid metal wheels. Two sets of simulation results are presented below. The first simulation was the traverse of gently rolling terrain, as seen in Figure 7. The velocity-controlled system was commanded by an individual-wheel PID control scheme with a desired angular velocity of 2.5 rad/sec. The RTC system was commanded by a horizontal inertial force vector of a magnitude equal to the difference between the desired body velocity of 25 cm/sec and the actual body velocity, divided by the vehicle mass. The dual-criteria optimization threshold C was set equal to 15°, since terrain with ground-contact angles less than 15° can generally be considered benign. Figure 8 – Average slip ratio of front and rear wheels for RTC system (dashed) vs. velocity controlled system (solid) Figure 9 shows the performance of the wheel-ground contact angle estimation algorithm. The estimated ground contact angles remain very near the actual ground contact angles for the duration of the simulation. (a) (b) Figure 9– Ground-contact angle estimation of front (9a) and rear (9b) wheels during benign terrain traverse Figure 7 – Simulated benign terrain profile 6 The second simulation was the traverse of highly challenging terrain, seen in Figure 10. The maximum slopes in this terrain are near the friction angle of the soil. Control parameters were the same as the previous simulation. Figure 12 – Average slip ratio of front and rear wheels of RTC system (dashed) vs. velocity-controlled system (solid) Figure 10 – Simulated challenging terrain In this simulation the RTC system is able to complete the traverse while the velocity-controlled system is not. This is due to the additional thrust force generated by the RTC algorithm, see Figure 11. The total wheel thrust generated by the RTC system remains higher than the thrust generated by the velocity-controlled system during most of the traverse. In this case the RTC system commands increased torque to the rear wheel, which has a much higher load than the front wheel, resulting in increased net thrust. The dual-criteria optimization remained in traction maximization mode for the majority of the traverse. CONCLUSIONS AND FUTURE WORK In this paper a rough-terrain control method has been presented that optimizes force distribution for improved traction or reduced power consumption, depending on the local profile. A wheel-ground contact angle estimation algorithm has also been presented. The algorithm is based on rigid-body kinematic equations and utilizes an extended Kalman filter to fuse noisy sensor signals. Simulation results for a two-wheeled planar rover system operating on soil have shown that the control algorithm is able to consume less power and provide greater mobility than traditional individual-wheel velocity control. The RTC and angle estimation algorithms are currently being integrated into a traction control system on a six-wheeled laboratory microrover. ACKNOWLEDGMENTS This work is supported by the NASA Jet Propulsion Laboratory under contract number 960456. The authors would like to acknowledge the support of Dr. Paul Schenker and Dr. Eric Baumgartner at JPL. Figure 11 – Total wheel thrust of RTC system (dashed) vs. velocity-controlled system (solid) The average wheel slip in the RTC system remained lower than the velocity-controlled system during most of the traverse, as seen in Figure 12. Note that although significant slip remained in the RTC system, this is due to the highly rough terrain. 7 REFERENCES Bekker, G., 1969, Introduction to Terrain-Vehicle Systems, University of Michigan Press. Brown, R., and Hwang, P., 1997, Introduction to Random Signals and Applied Kalman Filtering, John Wiley and Sons. Chung, W., and Waldron, K., 1993, “Force Distribution by Optimizing Angles for Multifinger Systems,” Proceedings of the IEEE International Conference on Robotics and Automation, 3: 717-722. Cunningham, J., Roberts, J., Corke, P., and DurrantWhyte, H., 1998, “Automation of Underground LHD and Truck Haulage,” Proceedings of Australian IMM Annual Conference: 241-246. Dubowsky, S., Moore, C., and Sunada, C., 1995, “On the Design and Task Planning of Power-Efficient Field Robotic Systems,” Proceedings of the Sixth ANS Robotics and Remote Systems Conference, Monterey. Farritor, S., Hacot, H., and Dubowsky, S., 1998, “PhysicsBased Planning for Planetary Exploration,” Proceedings of the IEEE International Conference on Robotics and Automation: 278-83. Golombek, M. P., 1998, “Mars Pathfinder Mission and Science Results,” Proceedings of the 29th Lunar and Planetary Science Conference. Gonthier, Y. and Papadopoulos, E., “On the Development of a Real-time Simulator for an Electro-Hydraulic Forestry Machine,” 1998, Proceedings of IEEE International Conference on Robotics and Automation. Hacot, H., 1998, Analysis and Traction Control of a Rocker-Bogie Planetary Rover, M.S. Thesis, Massachusetts Institute of Technology, Cambridge, MA. Hayati, S., Volpe, R., Backes, P., Balaram, J., and Welch, W., 1996, “Microrover Research for Exploration of Mars,” AIAA Forum on Advanced Developments in Space Robotics. Hung, M., Orin., D., and Waldron, K., 1999, “Force Distribution Equations for General Tree-Structured Robotic Mechanisms with a Mobile Base,” Proceedings of IEEE Internatl. Conference on Robotics and Automation: 2711-2716. Iagnemma, K., Burn, R., Wilhelm, E., and Dubowsky, S., 1999, “Experimental Validation of Physics-Based Planning and Control Algorithms for Planetary Robotic Rovers,” Proceedings of the Sixth International Symposium on Experimental Robotics, ISER '99. Iagnemma, K., and Dubowsky, S., 2000, “Vehicle WheelGround Contact Angle Estimation: with Application to Mobile Robot Traction Control,” submitted to 7th International Symposium on Advances in Robot Kinematics, ARK ’00. Kawabe, T., Nakazawa, M., Notsu, I., Watanabe, Y., 1997, “Sliding Mode Controller for Wheel Slip Ratio Control System,” Vehicle System Dynamics, 27 (5-6): 393-408. Kumar, V., and Waldron, K., 1988, “Force Distribution in Closed Kinematic Chains,” IEEE Transactions on Robotics and Automation, 4 (6): 657-644. Kumar, V., and Waldron, K., 1990, “Force Distribution in Walking Vehicles,” ASME Journal of Mechanical Design, 112: 90-99. 8 Mishkin, A., Morrison, J., Nguyen, T., Stone, H., Cooper, B., and Wilcox, B., 1998, “Experiences with Operations and Autonomy of the Mars Pathfinder Microrover,” 1998 IEEE Aerospace Conference: 337-51. NASA Technical Memorandum 100470, 1988, “Environment of Mars, 1988,” Lyndon B. Johnson Space Center. Osborn, J.F., 1989, “Applications of Robotics in Hazardous Waste Management,” Proceedings of the SME 1989 World Conference on Robotics Research, Gaithersburg, MD. Reister, D., Unseren, M., 1993, “Position and Constraint Force Control of a Vehicle with Two or More Steerable Drive Wheels,” IEEE Transactions on Robotics and Automation, 9: 723-731. Rover Team (Matijevic, J., et. al.), 1997, “Characterization of the Martian Surface Deposits by the Mars Pathfinder Rover, Sojourner,” Science, 278: 1765,1768. Sarkar, N, and Yun, X., (1998), “Traction Control of Wheeled Vehicles Using Dynamic Feedback Approach,” Proceedings of the 1998 IEEE International Conference on Intelligent Robots and Systems Conference, 1: 413-418. Schenker, P., Sword, L., Ganino, A., Bickler, D., Hickey, G., Brown, D., Baumgartner, E., Matthies, L., Wilcox, B., Balch, T., Aghazarian, H., and Garrett, M., 1997, “Lightweight Rovers for Mars Science Exploration and Sample Return,” Proceedings of SPIE XVI Intelligent Robots and Computer Vision Conference, 3208: 24-36. Sreenivasan, S., and Wilcox, B., 1994, “Stability and Traction Control of an Actively Actuated Micro-Rover,” Journal of Robotic Systems, 11 (6): 487-502. Sreenivasan, S., and Waldron, K., 1996, “Displacement Analysis of an Actively Articulated Wheeled Vehicle Configuration with Extensions to Motion Planning on Uneven Terrain,” Transactions of the ASME Journal of Mechanical Design, 118: 312-317.