by Cagri Kilic, WVU Navigation Lab
Fast traversing is a challenging problem for planetary rovers due to safety reasons, limited energy resources and computational power. For these reasons, planetary exploration rovers traverse slow. They are slow like that we can compare them to snails at some cases. An average speed of a snail is 46 m/h and Curiosity’s driving speed when the visual sensors used is 45m/h. It is indeed there is only one driving mode for curiosity rover when it is faster than a snail and this mode is Blind Driving mode.
Image credit: Wolfgang Hasselmann on Unsplash
Image credit: NASA/JPL-Caltech/MSSS
Usually a planetary rover is driven by different modes. This shows the example of Curiosity rover average speeds for 3 different driving modes.
- Blind Drive ~140 m/h
- Visual Odometry ~ 45 m/h
- Fully Autonomous ~ 20 m/h
Blind driving, the fastest mode, is based on IMU and wheel encoders. but not reliable due to drifting and slippage. The vision-based methods are reliable for navigation but make the rover significantly slow due to additional computational power requirements. However, In the case of exploring Mars, speed isn't the most relevant quality. It's about the journey and the destinations along the way.
The speed won’t be a big problem for Mars 2020 mission, too. That’s why it will have a similar traversal rates as previous Mars exploration rovers. However, in the case of future sample return mission, which will collect the samples on the Martian surface that left by Mars 2020, the rover should speed up significantly due to mission requirements, like the high possibility of travelling up to 800 m per day. This rover won’t make excessive explorations like previous rovers and only needs to pick up the samples from known locations and return them back before the Martian winter.
Image credit: NASA and A.Witze / Nature Magazine
Problems with the sensors
There is no single sensor that provides the sufficient information for rover navigations. For this reason, the information gathered by sensors are fused.
Visual Sensors
Computer vision-based approaches are generally used whenever there is a high possibility of positioning error; however, these strategies require additional computational power, energy resources, enough features in the environment, and significantly slow down the rover traverse speed.
- Additional computational power
- Additional energy resources
- Adequate features in the environment
- Slows down the rover traverse speed
Image credits: NASA/JPL-Caltech/MSSS
Inertial Measurement Unit
Inertial sensors work like vestibular system. Acceleration and angular rate information are vital for almost all the navigational methods. IMU is mostly used as an aiding sensor. Direct integration of positioning from the IMU information without external aiding inherently exhibit error growth with the current technology for most of the applications.
- Accumulation of errors
- Misalignment errors
- Modeling errors
Reproduced from State Estimation for Legged Robots - Kinematics, Inertial Sensing, and Computer Vision, M. Bloesch
Wheel Encoders
Counting wheel revolutions (or wheel odometry) is one of the oldest methods that leverages with wheel encoders. For planetary rovers that are traversing diverse types of terrain, wheel odometry is often unreliable for use in localization, due to wheel slippage.
Muscle Memory Image credit: S. Daniluk on Hackernoon
We faced with the slippage frequently during traversing on deformable terrains, due to wheel-terrain interactions.
What is our method?
In this study, we focus on improving the navigational performance of the blind-driving mode. In other means, if the blind driving mode can be improved, computationally expensive visual-based methods will be used less often, and the rover can travel more and faster. We attempted to improve it by leveraging the use of zero-type constraint equations in the navigation filter. In order to use the zero-updates the rover needs to stop. But fortunately, the planetary rovers are often in the stopping conditions for several reasons. When the rover stops, or commanded to stop, the IMU can sense this action and can be used as a pseudo-measurement. This measurement update enhances the navigation solution.
The architecture
Our navigation approach compensates for the high likelihood of odometry errors by providing a reliable navigation solution which make use of non-holonomic vehicle constraints as well as state-aware pseudomeasurements during stops (e.g., zero velocity and zero angular rate). This can be achieved by without any hardware changes and without significant alterations in rover operations. During stationary conditions, IMU sensor outputs are governed by the planet’s rotation and sensor errors. This information can be used to maintain INS alignment. In order to detect the stationary conditions, we used two different indicators, wheel odometry velocity and standard deviation of the IMU measurements since the rover typically experience less vibration whenever it is stationary. Zero updates bound the velocity error and calibrate the IMU sensor noises. To improve inertial navigation and provide uncertainty bounds, an errorstate extended Kalman filter (EKF) is implemented. In the filter, wheel odometry based wheel velocities and heading rate calculations are treated as an aiding sensor for the INS. In addition, zero-type updates and non-holonomic motion constraints are utilized as additional pseudo-measurement updates whenever they are available. Slip is estimated by using a threshold on the difference between the estimated INS solution and estimated wheel odometry velocity vectors.
Non-Holonomic Constraints
A rover is a non-holonomic system if its number of controllable degrees of freedom is less than its total degrees of freedom. A skid-steer rover is subject to two motion constraints if the rover is not experiencing side slip and motion normal to the road surface:
- The velocity of the vehicle is zero along the rotation axis of any of its wheels.
- Velocity is zero in the direction perpendicular to the traversal surface.
Zero updates
Zero updates are well known methods for aiding pedestrian navigation. Even they do not provide any position information, the error state model properly accounts for the correlation between the velocity and position errors in the off-diagonal elements of the error covariance matrix, then INS positioning error growth is significantly reduced. This enables zero-updates to not only limit the error growth and help determine biases to reduce error growth, but also mitigate most of the position drift since the last navigation stop.
Experiments
In order to evaluate the method, we used two different test-bed rovers, 1) Clearpath Husky, 2) WVU pathfinder test platform. We perform several tests on different terrain types like concrete grass gravel and sand.
As mentioned before, without using zero-type updates, the rover navigation performance is not sufficient due to accumulated error of the INS integration and the wheel slippage. Wheel odometry helps to reduce drift along with non-holonomic constraints within the INS solution. But this is not a adequate solution for navigational perspective. However, if the zero-type updates are applied, most of the error is mitigated. After the application of zero velocity and angular rate updates, non-holonomic constraints further enhance the solution. And finally, if the wheel odometry is used along with the other methods the error is further decreased.
And you can see the corresponding 3D view of the rover traversal for Rough-Terrain in Latitude, Longitude, Height (LLH) coordinates. The GPS solution and filter estimation are plotted on USGS Digital Elevation Model (DEM) data of the traversed region. We achieved the 3D position error at the end amounts to less than 1.5% of the traveled distance.
Conclusion
The main aim for this research is improving the blind driving mode which is required computationally less power and correspondingly makes the rover traversal faster. We do not undermine the visual based navigation, instead we are aiming to give a better input for these methods. For example, with a better dead-reckoning solution, less correction may be needed after a visual check. When the energy consumption is a big deal like the planetary missions, it is preferable to use less energy consumed methods and use the high-level computations less often. We leveraged the fact that the planetary rovers need to stop for several reasons. And demonstrated the zero-updates can be used for planetary rovers too. Again, this method can be implemented into current blind-driving methods, and when the visual sensors are not available (like shadowed, dusty environments with low feature terrains) to have an improved navigation solution by using an IMU and wheel encoders.
We used periodic stopping for this study. For example, rover stops after a predetermined driving time, and in our future study, we will show when to actively estimating the stops to apply zero-updates. For instance, there were some places, there is no need to stop to acquire good navigation solution like flat concrete paths, and on the other hand, there are some places we should stop more often to have a sufficient solution like non flat gravel paths. In summary, the study provides these contributions:
- Fast traverse for planetary rovers.
- Improved blind-driving mode.
- Helps to maintain reliable navigation with IMU and wheel encoders.
- Not affected by low-feature terrains.
We made our software open public through a GitHub repo. The software can be used real time with ROS and can be used as a post-processing tool in MATLAB. ( https://github.com/wvu-navLab/CLN)
For more details, see our paper:
Cagri Kilic, Jason N. Gross, Nicholas Ohi, Ryan Watson, Jared Strader, Thomas Swiger, Scott Harper, Yu Gu IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS 2019)