Skip to content

Commit b3e93a0

Browse files
committed
trajectory of the footprint in evaluation (fixed for rellis3d evaluation)
1 parent 3e9c467 commit b3e93a0

File tree

4 files changed

+12
-5
lines changed

4 files changed

+12
-5
lines changed

scripts/eval

+9-5
Original file line numberDiff line numberDiff line change
@@ -333,11 +333,14 @@ class EvaluatorGeom:
333333

334334
return loss_trans_sum, loss_rot_sum
335335

336-
def evaluate(self, vis=False, verbose=False):
336+
def evaluate(self, vis=False, verbose=False, random_order=False):
337337
for path in self.data_paths:
338338
print(f'Evaluation on {os.path.basename(path)}...')
339339
ds = self.DataClass(path, is_train=False, data_aug_conf=self.data_aug_conf, dphys_cfg=self.dphys_cfg)
340-
for i in tqdm(range(len(ds))):
340+
sample_range = np.arange(0, len(ds))
341+
if random_order:
342+
np.random.shuffle(sample_range)
343+
for i in tqdm(sample_range):
341344
states_true, height = self.get_data(i, ds)
342345
trans_diff, rot_diff = self.eval_diff_physics(height, states_true, vis=vis)
343346
if rot_diff is not None:
@@ -374,7 +377,8 @@ class EvaluatorGeom:
374377
class EvaluatorLSS(EvaluatorGeom):
375378
def __init__(self, dphys_config_path, terrain_encoder_config_path, dataset,
376379
# model_path='../config/tb_runs/lss_2024_03_04_09_42_47/train_lss.pt'):
377-
model_path='../config/tb_runs/lss_rellis3d_robingas_dphysics_terrain/train_lss.pt'):
380+
# model_path='../config/tb_runs/lss_rellis3d_robingas_dphysics_terrain/train_lss.pt'):
381+
model_path='../config/tb_runs/lss_rellis3d_2024_03_06_16_07_52/train_lss.pt'):
378382
super().__init__(dphys_config_path, terrain_encoder_config_path, dataset, model_path)
379383

380384
def load_model(self):
@@ -576,8 +580,8 @@ def evaluate(dataset):
576580

577581

578582
def main():
579-
dataset = 'robingas'
580-
# dataset = 'rellis3d'
583+
# dataset = 'robingas'
584+
dataset = 'rellis3d'
581585

582586
# vis_data(dataset)
583587
evaluate(dataset)

src/monoforce/datasets/rellis3d.py

+1
Original file line numberDiff line numberDiff line change
@@ -302,6 +302,7 @@ def get_states_traj(self, id, start_from_zero=False):
302302
# transform poses to the same coordinate frame as the height map
303303
Tr = np.linalg.inv(poses[0])
304304
poses = np.asarray([np.matmul(Tr, p) for p in poses])
305+
poses[:, 2, 3] -= self.calib['clearance']
305306
# count time from 0
306307
tstamps = traj['stamps']
307308
tstamps = tstamps - tstamps[0]

src/monoforce/datasets/robingas.py

+1
Original file line numberDiff line numberDiff line change
@@ -203,6 +203,7 @@ def get_states_traj(self, i, start_from_zero=False):
203203
# transform poses to the same coordinate frame as the height map
204204
Tr = np.linalg.inv(poses[0])
205205
poses = np.asarray([np.matmul(Tr, p) for p in poses])
206+
poses[:, 2, 3] -= self.calib['clearance']
206207
# count time from 0
207208
tstamps = traj['stamps']
208209
tstamps = tstamps - tstamps[0]

src/monoforce/datasets/utils.py

+1
Original file line numberDiff line numberDiff line change
@@ -152,6 +152,7 @@ def load_cam_calib(calib_path):
152152
transforms = yaml.load(f, Loader=yaml.FullLoader)
153153
f.close()
154154
calib['transformations'] = transforms
155+
calib['clearance'] = np.abs(np.asarray(calib['transformations']['T_base_link__base_footprint']['data'], dtype=np.float32).reshape((4, 4))[2, 3])
155156

156157
return calib
157158

0 commit comments

Comments
 (0)