Skip to content

Commit df4bcd9

Browse files
author
Jacob Gloudemans
committed
WIP #10: Fixed a bug in EKF code, a few slight changes to test script
1 parent 471eba8 commit df4bcd9

File tree

3 files changed

+22
-11
lines changed

3 files changed

+22
-11
lines changed

slam/launch/test_ekf.launch

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,14 @@
11
<launch>
22

33
<!-- Parameters to define true pose for reference in error calculations-->
4-
<param name="true_x" type="double" value="-1"/>
5-
<param name="true_y" type="double" value="-1"/>
6-
<param name="true_z" type="double" value="-1"/>
7-
<param name="true_orientation_x" type="double" value="-1"/>
8-
<param name="true_orientation_y" type="double" value="-1"/>
9-
<param name="true_orientation_z" type="double" value="-1"/>
10-
<param name="true_orientation_w" type="double" value="-1"/>
11-
<param name="total_data_points" type="int" value="20"/>
4+
<param name="true_x" type="double" value="0"/>
5+
<param name="true_y" type="double" value="0"/>
6+
<param name="true_z" type="double" value="1"/>
7+
<param name="true_orientation_x" type="double" value="0"/>
8+
<param name="true_orientation_y" type="double" value="0"/>
9+
<param name="true_orientation_z" type="double" value="0"/>
10+
<param name="true_orientation_w" type="double" value="1"/>
11+
<param name="total_data_points" type="int" value="500"/>
1212

1313
<!-- parameters for image_publisher node -->
1414
<param name="device_id" value="0"/>

slam/scripts/ArucoEKF.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,7 @@ def getPose(self):
7171
pose.orientation.z = self.arucoEKF.x[5][0]
7272
pose.orientation.w = self.arucoEKF.x[6][0]
7373

74-
return Pose()
74+
return pose
7575

7676
def getPoseCovStamped(self):
7777
poseCovStamped = PoseWithCovarianceStamped()

slam/scripts/testEKF.py

Lines changed: 13 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
# import ros packages
77
import rospy
88
from geometry_msgs.msg import Pose, PoseWithCovarianceStamped
9+
from std_msgs.msg import Bool
910

1011
# Import other required packages
1112
import numpy as np
@@ -26,6 +27,9 @@ def __init__(self,trueX,trueY,trueZ,
2627
self.trueOrientationW = trueOrientationW
2728
self.totalDataPoints = totalDataPoints
2829

30+
# Only store data if board is detected
31+
self.isBoardDetected = False
32+
2933
# Indices to track how many data points we have read in out of the total
3034
self.indexRaw = 0
3135
self.indexEKF = 0
@@ -39,11 +43,15 @@ def __init__(self,trueX,trueY,trueZ,
3943
self.arucoRawMeanAndStd = np.zeros((7,2))
4044
self.arucoEKFMeanAndStd = np.zeros((7,2))
4145

46+
# Update whether marker is detected or not
47+
def updateMarkerDetected(self, msg):
48+
self.isBoardDetected = msg.data
49+
4250
# Record raw aruco error
4351
def exportRaw(self,pose):
4452

4553
# Collect up to specified number of data points
46-
if self.indexRaw < self.totalDataPoints:
54+
if self.indexRaw < self.totalDataPoints and self.isBoardDetected:
4755

4856
# Store raw error in the next open array index
4957
self.arucoRaw[0][self.indexRaw] = pose.position.x - self.trueX
@@ -61,7 +69,7 @@ def exportRaw(self,pose):
6169
def exportFiltered(self,pose):
6270

6371
# Collect up to specified number of data points
64-
if self.indexEKF < self.totalDataPoints:
72+
if self.indexEKF < self.totalDataPoints and self.isBoardDetected:
6573

6674
# Store ekf pose error in the next open array index
6775
self.arucoEKF[0][self.indexEKF] = pose.position.x - self.trueX
@@ -78,6 +86,8 @@ def exportFiltered(self,pose):
7886
# Calculate mean and standard deviation
7987
def calculateMeanAndStd(self):
8088

89+
rospy.loginfo(self.arucoRaw[2])
90+
8191
# Calculates the raw and ekf mean and standard deviation in all dimensions
8292
for x in range(7):
8393
self.arucoRawMeanAndStd[x][0] = np.mean(self.arucoRaw[x])
@@ -111,6 +121,7 @@ def calculateMeanAndStd(self):
111121
# Create subscribers to raw and filtered pose topics
112122
poseSubscriber_raw = rospy.Subscriber('aruco/pose_raw', Pose, aruco_pose_tracker.exportRaw)
113123
poseSubscriber_filter_cov = rospy.Subscriber('ekf/pose_filtered', Pose, aruco_pose_tracker.exportFiltered)
124+
markerDetectedSub = rospy.Subscriber('aruco/marker_detected', Bool, aruco_pose_tracker.updateMarkerDetected)
114125

115126
# Wait until enough data points have been collected
116127
while aruco_pose_tracker.indexRaw < totalDataPoints and \

0 commit comments

Comments
 (0)