renamed myData to scene_data, and explained BAL parameterization

release/4.3a0
John Lambert 2020-10-19 09:08:54 -04:00
parent b4bbad32df
commit 0d88438a2a
1 changed files with 21 additions and 12 deletions

View File

@ -37,8 +37,8 @@ def run(args):
input_file = gtsam.findExampleDataFile(args.input_file) input_file = gtsam.findExampleDataFile(args.input_file)
# # Load the SfM data from file # # Load the SfM data from file
mydata = readBal(input_file) scene_data = readBal(input_file)
logging.info(f"read {mydata.number_tracks()} tracks on {mydata.number_cameras()} cameras\n") logging.info(f"read {scene_data.number_tracks()} tracks on {scene_data.number_cameras()} cameras\n")
# # Create a factor graph # # Create a factor graph
graph = gtsam.NonlinearFactorGraph() graph = gtsam.NonlinearFactorGraph()
@ -48,8 +48,8 @@ def run(args):
# Add measurements to the factor graph # Add measurements to the factor graph
j = 0 j = 0
for t_idx in range(mydata.number_tracks()): for t_idx in range(scene_data.number_tracks()):
track = mydata.track(t_idx) # SfmTrack track = scene_data.track(t_idx) # SfmTrack
# retrieve the SfmMeasurement objects # retrieve the SfmMeasurement objects
for m_idx in range(track.number_measurements()): for m_idx in range(track.number_measurements()):
# i represents the camera index, and uv is the 2d measurement # i represents the camera index, and uv is the 2d measurement
@ -61,13 +61,13 @@ def run(args):
# Add a prior on pose x1. This indirectly specifies where the origin is. # Add a prior on pose x1. This indirectly specifies where the origin is.
graph.push_back( graph.push_back(
gtsam.PriorFactorPinholeCameraCal3Bundler( gtsam.PriorFactorPinholeCameraCal3Bundler(
C(0), mydata.camera(0), gtsam.noiseModel.Isotropic.Sigma(9, 0.1) C(0), scene_data.camera(0), gtsam.noiseModel.Isotropic.Sigma(9, 0.1)
) )
) )
# Also add a prior on the position of the first landmark to fix the scale # Also add a prior on the position of the first landmark to fix the scale
graph.push_back( graph.push_back(
gtsam.PriorFactorPoint3( gtsam.PriorFactorPoint3(
P(0), mydata.track(0).point3(), gtsam.noiseModel.Isotropic.Sigma(3, 0.1) P(0), scene_data.track(0).point3(), gtsam.noiseModel.Isotropic.Sigma(3, 0.1)
) )
) )
@ -76,15 +76,15 @@ def run(args):
i = 0 i = 0
# add each PinholeCameraCal3Bundler # add each PinholeCameraCal3Bundler
for cam_idx in range(mydata.number_cameras()): for cam_idx in range(scene_data.number_cameras()):
camera = mydata.camera(cam_idx) camera = scene_data.camera(cam_idx)
initial.insert(C(i), camera) initial.insert(C(i), camera)
i += 1 i += 1
j = 0 j = 0
# add each SfmTrack # add each SfmTrack
for t_idx in range(mydata.number_tracks()): for t_idx in range(scene_data.number_tracks()):
track = mydata.track(t_idx) track = scene_data.track(t_idx)
initial.insert(P(j), track.point3()) initial.insert(P(j), track.point3())
j += 1 j += 1
@ -103,8 +103,17 @@ def run(args):
if __name__ == "__main__": if __name__ == "__main__":
parser = argparse.ArgumentParser() parser = argparse.ArgumentParser()
parser.add_argument('-i', '--input_file', type=str, default="dubrovnik-3-7-pre", parser.add_argument(
help='Read SFM data from the specified BAL file') '-i',
'--input_file',
type=str,
default="dubrovnik-3-7-pre",
help='Read SFM data from the specified BAL file'
'The data format is described here: https://grail.cs.washington.edu/projects/bal/.'
'BAL files contain (nrPoses, nrPoints, nrObservations), followed by (i,j,u,v) tuples, '
'then (wx,wy,wz,tx,ty,tz,f,k1,k1) as Bundler camera calibrations w/ Rodrigues vector'
'and (x,y,z) 3d point initializations.'
)
run(parser.parse_args()) run(parser.parse_args())