Skip to content

Commit 91ef58e

Browse files
committed
editorial changes
1 parent 004ed52 commit 91ef58e

File tree

13 files changed

+46
-410
lines changed

13 files changed

+46
-410
lines changed

README.md

+3-5
Original file line numberDiff line numberDiff line change
@@ -4,12 +4,12 @@
44

55

66
## Overview
7-
(TBD) Slip-aware Navigation Stop Planning for Autonomous Planetary Rover Applications
7+
Slip-Based Autonomous ZUPT through Gaussian Process to Improve Planetary Rover Proprioceptive Localization
88
...
99

1010
## Architecture
1111

12-
<img alt="architecture" src="docs/algorithm.png" width="700">
12+
<img alt="architecture" src="docs/framework.png" width="700">
1313

1414
**Keywords:** Mars Sample Return, planetary rovers, time series prediction, slip, zero velocity update, rover localization
1515

@@ -22,6 +22,4 @@ Maintainer: Cagri Kilic, [email protected]**
2222

2323
If you use this work in an academic context, please cite the following publication:
2424

25-
* Cagri Kilic, Jason N. Gross, Nicholas Ohi, Yu Gu: **Slip-aware Navigation Stop Planning for Autonomous Planetary Rover Applications**.
26-
27-
25+
* Cagri Kilic, Nicholas Ohi, Yu Gu, Jason N. Gross: **Slip-Based Autonomous ZUPT through Gaussian Process to Improve Planetary Rover Proprioceptive Localization**.
+13-23
Original file line numberDiff line numberDiff line change
@@ -1,30 +1,20 @@
11
mean_bias_a:
2-
x: 0.049725549309
3-
y: 0.280722422325
4-
z: -9.806383392926
2+
x: 0.269614133542350
3+
y: -0.262166124574161
4+
z: -9.804005623794065
55
mean_bias_g:
6-
x: -0.000007296495
7-
y: -0.000147732137
8-
z: 0.000591663048
6+
x: 0.000268715437386711
7+
y: -0.000161452230267971
8+
z: 0.000678693501054130
99
init_ecef:
10-
x: 859112.684900000
11-
y: -4836240.899300000
12-
z: 4055467.61860000 #t9raw
13-
# x: 856203.4886
14-
# y: -4841345.9946
15-
# z: 4049896.7715 #Outtest
10+
x: 859153.015300000
11+
y: -4836303.72660000
12+
z: 4055378.50100000
1613
init_llh:
17-
x: 0.6934756603499
18-
y: -1.3949896896546
19-
z: 338.9617659955771 #t9raw
20-
# x: 0.69234816834
21-
# y: -1.39575390508
22-
# z: 257.30 #Outtest
14+
x: 0.693457963620326
15+
y: -1.39498384275845
16+
z: 334.993517334743
2317
init_att:
2418
x: 0.0
2519
y: 0.0
26-
# z: 5.48
27-
z: 3.220132469929538 #t9raw
28-
# z: 5.25344 #outtest
29-
# z: 3.6
30-
# z: 3.3
20+
z: -0.733038286

core_navigation/src/CoreNav.cpp

+6
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,9 @@
1+
/* @file CoreNav.cpp
2+
* @brief Core Navigation ES-EKF Node
3+
* @author Cagri Kilic
4+
* @author Jason Gross
5+
*/
6+
17
#include <core_navigation/CoreNav.h>
28
#include <core_navigation/InsConst.h>
39
#include <core_navigation/InsUtils.h>

docs/algorithm.png

-79.5 KB
Binary file not shown.

docs/framework.png

308 KB
Loading

gp_predictor/src/gp_predictor.cpp

+6-3
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,8 @@
1+
/* @file gp_predictor.cpp
2+
* @brief Gaussian Prediction Node
3+
* @author Cagri Kilic
4+
*/
5+
16
#include <ros/ros.h>
27
#include <gp_predictor/gp_predictor.h>
38

@@ -94,7 +99,7 @@ void GpPredictor::GPCallBack(const core_nav::GP_Output::ConstPtr& gp_data_in_){
9499
xy_errSlip = sqrt((ins_enu_slip3p(0)-ins_enu_slip(0))*(ins_enu_slip3p(0)-ins_enu_slip(0)) + (ins_enu_slip3p(1)-ins_enu_slip(1))*(ins_enu_slip3p(1)-ins_enu_slip(1)));
95100
ROS_ERROR_THROTTLE(0.5,"XYerror %.6f meters", xy_errSlip);
96101

97-
if (xy_errSlip > 2.00)
102+
if (xy_errSlip > 3.00) //Threshold can be set in here
98103
{
99104

100105
ROS_INFO("Stop Command Required, error is more than %.2f meters", xy_errSlip);
@@ -138,8 +143,6 @@ bool GpPredictor::LoadParameters(const ros::NodeHandle& nh_){
138143

139144
GpPredictor::Vector3 GpPredictor::llh_to_enu(double lat, double lon, double height){
140145

141-
// countLLH2ENU++;
142-
// ROS_INFO_STREAM("countLLH2ENU: " << countLLH2ENU);
143146
double phi = lat;
144147
double lambda = lon;
145148
double h = height;

gps_core_navigation/src/gps_CoreNav.cpp

+5
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,8 @@
1+
/* @file gps_CoreNav.cpp
2+
* @brief Loosely Coupled GPS-IMU algorithm
3+
* @author Cagri Kilic
4+
* @author Jason Gross
5+
*/
16
#include <gps_core_navigation/gps_CoreNav.h>
27
#include <gps_core_navigation/InsConst.h>
38
#include <gps_core_navigation/InsUtils.h>

gps_data_log/scripts/gps_log_node.py

+5
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,8 @@
1+
# /* @file gps_log_node.py
2+
# * @brief Novatel GPS Logger
3+
# * @author Nicholas Ohi
4+
# * @author Cagri Kilic
5+
# */
16
#!/usr/bin/env python
27
import rospy
38
import serial

hw_interface/CMakeLists.txt.user

-189
This file was deleted.

0 commit comments

Comments
 (0)