Skip to content

Commit

Permalink
added comments
Browse files Browse the repository at this point in the history
  • Loading branch information
Samleo8 committed Apr 29, 2022
1 parent 79e67e3 commit 2e7a768
Showing 1 changed file with 28 additions and 6 deletions.
34 changes: 28 additions & 6 deletions Mapping.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,15 +7,22 @@
from getPointCloud import getPointCloudPolarInd

# Thresholds
ROT_THRESHOLD = 0.2 # radians
TRANS_THRESHOLD = 2.0 # meters
TRANS_THRESHOLD_SQ = TRANS_THRESHOLD * TRANS_THRESHOLD # meters^2
ROT_THRESHOLD = 0.2 # radians
TRANS_THRESHOLD = 2.0 # meters
TRANS_THRESHOLD_SQ = TRANS_THRESHOLD * TRANS_THRESHOLD # meters^2


# Keyframe class
class Keyframe():

def __init__(self, pose: np.ndarray, featurePoints: np.ndarray,
radarPolarImg: np.ndarray) -> None:
'''
@brief Keyframe class. Contains pose, feature points and point cloud information
@param[in] pose (3 x 1) Pose information [x, y, th] in (m, m, rad) # TODO: Confirm these units
@param[in] featurePoints (K x 2) Tracked feature points from previous keyframe
@param[in] radarPolarImg (M x N) Radar polar (range-azimuth) image
'''
self.pose = pose
self.featurePoints = featurePoints # set of (tracked) feature points
self.radarPolarImg = radarPolarImg # radar polar image
Expand All @@ -30,6 +37,7 @@ def __init__(self, pose: np.ndarray, featurePoints: np.ndarray,
# '''
# MAX_RANGE_CLIP_DEFAULT


# Map class
class Map():

Expand All @@ -46,7 +54,11 @@ def __init__(self, sequenceName: str, estTraj: Trajectory,
self.keyframes = []

# TODO: might not want to make keyframe before adding it
def isGoodKeyframe(self, keyframe: Keyframe):
def isGoodKeyframe(self, keyframe: Keyframe) -> bool:
'''
@brief Check if a keyframe is good for adding using information about relative rotation and translation
@return If keyframe passes checks
'''
# Get information of prev KF's pose
prevKF = self.keyframes[-1]
srcPose = prevKF.pose
Expand All @@ -62,14 +74,24 @@ def isGoodKeyframe(self, keyframe: Keyframe):
return True

# Check translation condition
deltaTrans = (srcPose[0:2] - targetPose[0:2]) ** 2
deltaTrans = (srcPose[0:2] - targetPose[0:2])**2
deltaTrans = deltaTrans.sum()

if (deltaTrans >= TRANS_THRESHOLD_SQ):
return True

return False

def addKeyframe(self, keyframe: Keyframe):
def addKeyframe(self, keyframe: Keyframe) -> None:
'''
@brief Add a keyframe to the running pose graph
@param[in] keyframe Keyframe to add
'''
self.keyframes.append(keyframe)

def bundleAdjustment(self) -> None:
'''
@brief Perform bundle adjustment on the last 2 keyframes
@return None
'''
pass

0 comments on commit 2e7a768

Please sign in to comment.