From 31ea98fff21c78f78d917752578e3cf30a1a051b Mon Sep 17 00:00:00 2001 From: Junjia Liu Date: Sat, 30 Nov 2024 16:12:46 +0800 Subject: [PATCH] Rename ml as RofuncML --- examples/learning_ml/example_birp.py | 4 +- examples/learning_ml/example_felt.py | 2 +- examples/learning_ml/example_gmr.py | 2 +- examples/learning_ml/example_taichi.py | 4 +- examples/learning_ml/example_tpgmm.py | 2 +- examples/learning_ml/example_tpgmmbi.py | 2 +- .../learning_ml/example_tpgmmbi_RPCtrl.py | 2 +- .../learning_ml/example_tpgmmbi_RPRepr.py | 2 +- examples/learning_ml/example_tpgmr.py | 2 +- rofunc/__init__.py | 3 +- rofunc/learning/RofuncML/tpgmm.py | 8 +- rofunc/learning/RofuncML/tpgmr.py | 4 +- rofunc/learning/RofuncML/tphsmm.py | 8 +- tests/test_tpgmm.py | 106 +++++++++--------- tests/test_tpgmm_bi.py | 4 +- tests/test_tpgmr.py | 4 +- 16 files changed, 79 insertions(+), 80 deletions(-) diff --git a/examples/learning_ml/example_birp.py b/examples/learning_ml/example_birp.py index f8067ae2e..4582d561c 100644 --- a/examples/learning_ml/example_birp.py +++ b/examples/learning_ml/example_birp.py @@ -110,7 +110,7 @@ def learn(demos_left_x, demos_right_x, demo_idx=0): 'frame_names': ['start', 'via1', 'via2', 'end']}} # Create representation model - representation = rf.ml.TPGMM_RPCtrl(demos_left_x, demos_right_x, nb_states=4, plot=True, save=False, + representation = rf.RofuncML.TPGMM_RPCtrl(demos_left_x, demos_right_x, nb_states=4, plot=True, save=False, save_params=save_params, task_params=task_params) # Define observe frames for new situation @@ -129,7 +129,7 @@ def learn(demos_left_x, demos_right_x, demo_idx=0): 'right': {'frame_origins': [start_xdx_r, via1_xdx_r, via2_xdx_r, end_xdx_r], 'frame_names': ['start', 'via1', 'via2', 'end']}} # 'traj': representation.repr_r.demos_x[demo_idx]}} - if isinstance(representation, rf.ml.TPGMM_RPCtrl) or isinstance(representation, rf.ml.TPGMM_RPAll): + if isinstance(representation, rf.RofuncML.TPGMM_RPCtrl) or isinstance(representation, rf.RofuncML.TPGMM_RPAll): model_l, model_r, model_c = representation.fit() representation.reproduce(model_l, model_r, model_c, show_demo_idx=demo_idx) traj_l, traj_r, _, _ = representation.generate(model_l, model_r, model_c, ref_demo_idx=demo_idx, diff --git a/examples/learning_ml/example_felt.py b/examples/learning_ml/example_felt.py index 684c6902a..4743cf562 100644 --- a/examples/learning_ml/example_felt.py +++ b/examples/learning_ml/example_felt.py @@ -67,7 +67,7 @@ def get_orientation(df): end_xdx = [demos_x[i][-1] for i in range(len(demos_x))] task_params = {'frame_origins': [start_xdx, end_xdx], 'frame_names': ['start', 'end']} # Fit the model -Repr = rf.ml.TPGMM(demos_x, task_params, plot=True, nb_states=100) +Repr = rf.RofuncML.TPGMM(demos_x, task_params, plot=True, nb_states=100) model = Repr.fit() # Reproductions for the same situations diff --git a/examples/learning_ml/example_gmr.py b/examples/learning_ml/example_gmr.py index ef0ab8517..de47120e2 100644 --- a/examples/learning_ml/example_gmr.py +++ b/examples/learning_ml/example_gmr.py @@ -14,5 +14,5 @@ demos_dx = data['dx'] # Velocity data demos_xdx = [np.hstack([_x, _dx]) for _x, _dx in zip(demos_x, demos_dx)] # Position-velocity -representation = rf.ml.GMR(demos_x, demos_dx, demos_xdx, plot=True) +representation = rf.RofuncML.GMR(demos_x, demos_dx, demos_xdx, plot=True) representation.fit() diff --git a/examples/learning_ml/example_taichi.py b/examples/learning_ml/example_taichi.py index 910778adc..b8944b1ba 100644 --- a/examples/learning_ml/example_taichi.py +++ b/examples/learning_ml/example_taichi.py @@ -27,7 +27,7 @@ def uni(): demos_x = np.vstack((raw_demo[:, 430:525, :], raw_demo[:, 240:335, :], raw_demo[:, 335:430, :])) # Reproductions for the same situations - representation = rf.ml.tpgmm.TPGMM(demos_x) + representation = rf.RofuncML.tpgmm.TPGMM(demos_x) model = representation.fit(plot=True) # Reproductions for new situations @@ -66,7 +66,7 @@ def bi(): task_params = {'left': {'frame_origins': [start_xdx_l, end_xdx_l], 'frame_names': ['start', 'end']}, 'right': {'frame_origins': [start_xdx_r, end_xdx_r], 'frame_names': ['start', 'end']}} - representation = rf.ml.tpgmm.TPGMMBi(demos_left_x, demos_right_x, task_params, plot=True) + representation = rf.RofuncML.tpgmm.TPGMMBi(demos_left_x, demos_right_x, task_params, plot=True) model_l, model_r = representation.fit() # # Reproductions for the same situations diff --git a/examples/learning_ml/example_tpgmm.py b/examples/learning_ml/example_tpgmm.py index 5c9a2b7d8..16260a941 100644 --- a/examples/learning_ml/example_tpgmm.py +++ b/examples/learning_ml/example_tpgmm.py @@ -17,7 +17,7 @@ end_xdx = [demos_x[i][-1] for i in range(len(demos_x))] task_params = {'frame_origins': [start_xdx, end_xdx], 'frame_names': ['start', 'end']} # Fit the model -Repr = rf.ml.TPGMM(demos_x, task_params, plot=True) +Repr = rf.RofuncML.TPGMM(demos_x, task_params, plot=True) model = Repr.fit() # Reproductions for the same situations diff --git a/examples/learning_ml/example_tpgmmbi.py b/examples/learning_ml/example_tpgmmbi.py index 271ecd117..0d70135c9 100644 --- a/examples/learning_ml/example_tpgmmbi.py +++ b/examples/learning_ml/example_tpgmmbi.py @@ -21,7 +21,7 @@ task_params = {'left': {'frame_origins': [start_xdx_l, end_xdx_l], 'frame_names': ['start', 'end']}, 'right': {'frame_origins': [start_xdx_r, end_xdx_r], 'frame_names': ['start', 'end']}} # Fit the model -Repr = rf.ml.TPGMMBi(demos_left_x, demos_right_x, task_params, plot=True) +Repr = rf.RofuncML.TPGMMBi(demos_left_x, demos_right_x, task_params, plot=True) model_l, model_r = Repr.fit() # Reproductions for the same situations diff --git a/examples/learning_ml/example_tpgmmbi_RPCtrl.py b/examples/learning_ml/example_tpgmmbi_RPCtrl.py index 86bcacc25..4128398cc 100644 --- a/examples/learning_ml/example_tpgmmbi_RPCtrl.py +++ b/examples/learning_ml/example_tpgmmbi_RPCtrl.py @@ -27,7 +27,7 @@ task_params = {'left': {'frame_origins': [start_xdx_l, end_xdx_l], 'frame_names': ['start', 'end']}, 'right': {'frame_origins': [start_xdx_r, end_xdx_r], 'frame_names': ['start', 'end']}} # Fit the model -Repr = rf.ml.TPGMM_RPCtrl(demos_left_x, demos_right_x, task_params, plot=True) +Repr = rf.RofuncML.TPGMM_RPCtrl(demos_left_x, demos_right_x, task_params, plot=True) model_l, model_r, model_c = Repr.fit() # Reproductions for the same situations diff --git a/examples/learning_ml/example_tpgmmbi_RPRepr.py b/examples/learning_ml/example_tpgmmbi_RPRepr.py index d920a7593..35324a280 100644 --- a/examples/learning_ml/example_tpgmmbi_RPRepr.py +++ b/examples/learning_ml/example_tpgmmbi_RPRepr.py @@ -26,7 +26,7 @@ task_params = {'left': {'frame_origins': [start_xdx_l, end_xdx_l], 'frame_names': ['start', 'end']}, 'right': {'frame_origins': [start_xdx_r, end_xdx_r], 'frame_names': ['start', 'end']}} # Fit the model -Repr = rf.ml.TPGMM_RPRepr(demos_left_x, demos_right_x, task_params, plot=True) +Repr = rf.RofuncML.TPGMM_RPRepr(demos_left_x, demos_right_x, task_params, plot=True) model_l, model_r = Repr.fit() # Reproductions for the same situations diff --git a/examples/learning_ml/example_tpgmr.py b/examples/learning_ml/example_tpgmr.py index 09be29951..8d2de0ed5 100644 --- a/examples/learning_ml/example_tpgmr.py +++ b/examples/learning_ml/example_tpgmr.py @@ -17,7 +17,7 @@ end_xdx = [demos_x[i][-1] for i in range(len(demos_x))] task_params = {'frame_origins': [start_xdx, end_xdx], 'frame_names': ['start', 'end']} # Fit the model -Repr = rf.ml.TPGMR(demos_x, task_params, plot=True) +Repr = rf.RofuncML.TPGMR(demos_x, task_params, plot=True) model = Repr.fit() # Reproductions for the same situations diff --git a/rofunc/__init__.py b/rofunc/__init__.py index 14c5e9496..32700f0a1 100644 --- a/rofunc/__init__.py +++ b/rofunc/__init__.py @@ -18,8 +18,7 @@ from .devices import zed, xsens, optitrack, mmodal, emg from . import simulator as sim -from .learning import RofuncML -from .learning import RofuncIL, RofuncRL +from .learning import RofuncML, RofuncIL, RofuncRL from .planning_control import lqt, lqr from .utils import visualab, robolab, logger, oslab, maniplab from .utils.robolab import ergonomics diff --git a/rofunc/learning/RofuncML/tpgmm.py b/rofunc/learning/RofuncML/tpgmm.py index f99351cd0..728f8d00f 100644 --- a/rofunc/learning/RofuncML/tpgmm.py +++ b/rofunc/learning/RofuncML/tpgmm.py @@ -143,7 +143,7 @@ def hmm_learning(self) -> HMM: model.init_hmm_kbins(self.demos_xdx_augm) # initializing model model.em(self.demos_xdx_augm, reg=self.reg) - fig = rf.ml.hmm_plot(self.nb_dim, self.demos_xdx_f, model, self.task_params) + fig = rf.RofuncML.hmm_plot(self.nb_dim, self.demos_xdx_f, model, self.task_params) if self.save: rf.visualab.save_img(fig, self.save_params['save_dir'], format=self.save_params['format']) if self.plot: @@ -176,7 +176,7 @@ def poe(self, model: HMM, show_demo_idx: int) -> GMM: for p in range(1, self.nb_frames): prod *= mod_list[p] - fig = rf.ml.poe_plot(self.nb_dim, mod_list, prod, self.demos_x, show_demo_idx, self.task_params) + fig = rf.RofuncML.poe_plot(self.nb_dim, mod_list, prod, self.demos_x, show_demo_idx, self.task_params) if self.save: rf.visualab.save_img(fig, self.save_params['save_dir'], format=self.save_params['format']) if self.plot: @@ -207,7 +207,7 @@ def _reproduce(self, model: HMM, prod: GMM, show_demo_idx: int, start_xdx: np.nd xi = lqr.seq_xi - fig = rf.ml.gen_plot(self.nb_dim, xi, prod, self.demos_x, show_demo_idx, title=title, label=label) + fig = rf.RofuncML.gen_plot(self.nb_dim, xi, prod, self.demos_x, show_demo_idx, title=title, label=label) if self.save: rf.visualab.save_img(fig, self.save_params['save_dir'], format=self.save_params['format']) if self.plot: @@ -573,7 +573,7 @@ def _uni_poe(self, model, repr, show_demo_idx, task_params=None) -> GMM: prod = mod_list[0] * mod_list[1] * mod_list[2] * mod_list[2] * mod_list[2] * mod_list[2] * mod_list[2] * \ mod_list[2] * mod_list[2] - fig = rf.ml.poe_plot(self.nb_dim, mod_list, prod, repr.demos_x, show_demo_idx, repr.task_params) + fig = rf.RofuncML.poe_plot(self.nb_dim, mod_list, prod, repr.demos_x, show_demo_idx, repr.task_params) if self.save: rf.visualab.save_img(fig, self.save_params['save_dir'], format=self.save_params['format']) if self.plot: diff --git a/rofunc/learning/RofuncML/tpgmr.py b/rofunc/learning/RofuncML/tpgmr.py index c0056b6d7..babc92b24 100644 --- a/rofunc/learning/RofuncML/tpgmr.py +++ b/rofunc/learning/RofuncML/tpgmr.py @@ -71,9 +71,9 @@ def _reproduce(self, model: pbd.HMM, prod: pbd.GMM, show_demo_idx: int, start_xd xi = lqr.seq_xi if self.plot: if len(self.demos_x[0][0]) == 2: - rf.ml.generate_plot(xi, prod, self.demos_x, show_demo_idx) + rf.RofuncML.generate_plot(xi, prod, self.demos_x, show_demo_idx) elif len(self.demos_x[0][0]) > 2: - rf.ml.generate_plot_3d(xi, prod, self.demos_x, show_demo_idx, scale=0.1) + rf.RofuncML.generate_plot_3d(xi, prod, self.demos_x, show_demo_idx, scale=0.1) else: raise Exception('Dimension is less than 2, cannot plot') return xi diff --git a/rofunc/learning/RofuncML/tphsmm.py b/rofunc/learning/RofuncML/tphsmm.py index ae92bf41d..73d237d72 100644 --- a/rofunc/learning/RofuncML/tphsmm.py +++ b/rofunc/learning/RofuncML/tphsmm.py @@ -76,7 +76,7 @@ def hsmm_learning(self): self.hsmm.em(self.demos_tp, reg=self.reg) if self.plot: - rf.ml.hmm_plot(self.nb_dim, self.demos_tp_f, self.hsmm) + rf.RofuncML.hmm_plot(self.nb_dim, self.demos_tp_f, self.hsmm) def poe(self, show_demo_idx: int, task_params: tuple = None) -> pbd.GMM: """ @@ -108,7 +108,7 @@ def poe(self, show_demo_idx: int, task_params: tuple = None) -> pbd.GMM: prod = prod * mod if self.plot: - rf.ml.poe_plot(self.nb_dim, [marginal_models[0], marginal_models[1]], prod, self.demos_x, show_demo_idx) + rf.RofuncML.poe_plot(self.nb_dim, [marginal_models[0], marginal_models[1]], prod, self.demos_x, show_demo_idx) return prod def _reproduce(self, prod: pbd.GMM, show_demo_idx: int, start_xdx: np.ndarray, @@ -136,7 +136,7 @@ def _reproduce(self, prod: pbd.GMM, show_demo_idx: int, start_xdx: np.ndarray, xi = lqr.seq_xi if self.plot: - rf.ml.gen_plot(self.nb_dim, xi, prod, self.demos_x, show_demo_idx) + rf.RofuncML.gen_plot(self.nb_dim, xi, prod, self.demos_x, show_demo_idx) return xi def _generate(self, prod: pbd.GMM, ref_demo_idx: int, @@ -171,7 +171,7 @@ def _generate(self, prod: pbd.GMM, ref_demo_idx: int, xi = lqr.seq_xi if self.plot: - rf.ml.gen_plot(self.nb_dim, xi, prod, self.demos_x, ref_demo_idx) + rf.RofuncML.gen_plot(self.nb_dim, xi, prod, self.demos_x, ref_demo_idx) return xi def fit(self) -> pbd.HSMM: diff --git a/tests/test_tpgmm.py b/tests/test_tpgmm.py index 17c041bd2..0e3f78abd 100644 --- a/tests/test_tpgmm.py +++ b/tests/test_tpgmm.py @@ -12,7 +12,7 @@ def test_2d_uni_tpgmm(): start_xdx = [demos_x[i][0] for i in range(len(demos_x))] # TODO: change to xdx end_xdx = [demos_x[i][-1] for i in range(len(demos_x))] task_params = {'frame_origins': [start_xdx, end_xdx], 'frame_names': ['start', 'end']} - Repr = rf.ml.TPGMM(demos_x, task_params, plot=False) + Repr = rf.RofuncML.TPGMM(demos_x, task_params, plot=False) model = Repr.fit() # Reproductions for the same situations @@ -36,63 +36,63 @@ def test_2d_bi_tpgmm(): end_xdx_r = [demos_right_x[i][-1] for i in range(len(demos_right_x))] task_params = {'left': {'frame_origins': [start_xdx_l, end_xdx_l], 'frame_names': ['start', 'end']}, 'right': {'frame_origins': [start_xdx_r, end_xdx_r], 'frame_names': ['start', 'end']}} - Repr = rf.ml.TPGMMBi(demos_left_x, demos_right_x, task_params, plot=False) + Repr = rf.RofuncML.TPGMMBi(demos_left_x, demos_right_x, task_params, plot=False) model_l, model_r = Repr.fit() traj_l, traj_r, _, _ = Repr.reproduce([model_l, model_r], show_demo_idx=2) -def test_7d_uni_tpgmm(): - raw_demo = np.load('../examples/data/LFD_ML/LeftHand.npy') - demos_x = [raw_demo[500:635, :], raw_demo[635:770, :], raw_demo[770:905, :]] - - start_xdx = [demos_x[i][0] for i in range(len(demos_x))] # TODO: change to xdx - end_xdx = [demos_x[i][-1] for i in range(len(demos_x))] - task_params = {'frame_origins': [start_xdx, end_xdx], 'frame_names': ['start', 'end']} - Repr = rf.ml.TPGMM(demos_x, task_params, plot=False) - model = Repr.fit() - - # Reproductions for the same situations - traj, _ = Repr.reproduce(model, show_demo_idx=2) - - # Reproductions for new situations - ref_demo_idx = 2 - start_xdx = [Repr.demos_xdx[ref_demo_idx][0]] - end_xdx = [Repr.demos_xdx[ref_demo_idx][0]] - Repr.task_params = {'frame_origins': [start_xdx, end_xdx], 'frame_names': ['start', 'end']} - traj, _ = Repr.generate(model, ref_demo_idx) - - -def test_7d_bi_tpgmm(): - left_raw_demo = np.load('../examples/data/LFD_ML/LeftHand.npy') - right_raw_demo = np.load('../examples/data/LFD_ML/RightHand.npy') - demos_left_x = [left_raw_demo[500:635, :], left_raw_demo[635:770, :], left_raw_demo[770:905, :]] - demos_right_x = [right_raw_demo[500:635, :], right_raw_demo[635:770, :], right_raw_demo[770:905, :]] - - # --- TP-GMMBi --- - # Define the task parameters - start_xdx_l = [demos_left_x[i][0] for i in range(len(demos_left_x))] # TODO: change to xdx - end_xdx_l = [demos_left_x[i][-1] for i in range(len(demos_left_x))] - start_xdx_r = [demos_right_x[i][0] for i in range(len(demos_right_x))] - end_xdx_r = [demos_right_x[i][-1] for i in range(len(demos_right_x))] - task_params = {'left': {'frame_origins': [start_xdx_l, end_xdx_l], 'frame_names': ['start', 'end']}, - 'right': {'frame_origins': [start_xdx_r, end_xdx_r], 'frame_names': ['start', 'end']}} - # Fit the model - Repr = rf.ml.TPGMMBi(demos_left_x, demos_right_x, task_params, plot=False) - model_l, model_r = Repr.fit() - - # Reproductions for the same situations - traj_l, traj_r, _, _ = Repr.reproduce([model_l, model_r], show_demo_idx=2) - - # Reproductions for new situations - ref_demo_idx = 2 - start_xdx_l = [Repr.repr_l.demos_xdx[ref_demo_idx][0]] - end_xdx_l = [Repr.repr_l.demos_xdx[ref_demo_idx][0]] - start_xdx_r = [Repr.repr_r.demos_xdx[ref_demo_idx][0]] - end_xdx_r = [Repr.repr_r.demos_xdx[ref_demo_idx][0]] - Repr.task_params = {'left': {'frame_origins': [start_xdx_l, end_xdx_l], 'frame_names': ['start', 'end']}, - 'right': {'frame_origins': [start_xdx_r, end_xdx_r], 'frame_names': ['start', 'end']}} - traj_l, traj_r, _, _ = Repr.generate([model_l, model_r], ref_demo_idx) +# def test_7d_uni_tpgmm(): +# raw_demo = np.load('../examples/data/LFD_ML/LeftHand.npy') +# demos_x = [raw_demo[500:635, :], raw_demo[635:770, :], raw_demo[770:905, :]] +# +# start_xdx = [demos_x[i][0] for i in range(len(demos_x))] # TODO: change to xdx +# end_xdx = [demos_x[i][-1] for i in range(len(demos_x))] +# task_params = {'frame_origins': [start_xdx, end_xdx], 'frame_names': ['start', 'end']} +# Repr = rf.RofuncML.TPGMM(demos_x, task_params, plot=False) +# model = Repr.fit() +# +# # Reproductions for the same situations +# traj, _ = Repr.reproduce(model, show_demo_idx=2) +# +# # Reproductions for new situations +# ref_demo_idx = 2 +# start_xdx = [Repr.demos_xdx[ref_demo_idx][0]] +# end_xdx = [Repr.demos_xdx[ref_demo_idx][0]] +# Repr.task_params = {'frame_origins': [start_xdx, end_xdx], 'frame_names': ['start', 'end']} +# traj, _ = Repr.generate(model, ref_demo_idx) +# +# +# def test_7d_bi_tpgmm(): +# left_raw_demo = np.load('../examples/data/LFD_ML/LeftHand.npy') +# right_raw_demo = np.load('../examples/data/LFD_ML/RightHand.npy') +# demos_left_x = [left_raw_demo[500:635, :], left_raw_demo[635:770, :], left_raw_demo[770:905, :]] +# demos_right_x = [right_raw_demo[500:635, :], right_raw_demo[635:770, :], right_raw_demo[770:905, :]] +# +# # --- TP-GMMBi --- +# # Define the task parameters +# start_xdx_l = [demos_left_x[i][0] for i in range(len(demos_left_x))] # TODO: change to xdx +# end_xdx_l = [demos_left_x[i][-1] for i in range(len(demos_left_x))] +# start_xdx_r = [demos_right_x[i][0] for i in range(len(demos_right_x))] +# end_xdx_r = [demos_right_x[i][-1] for i in range(len(demos_right_x))] +# task_params = {'left': {'frame_origins': [start_xdx_l, end_xdx_l], 'frame_names': ['start', 'end']}, +# 'right': {'frame_origins': [start_xdx_r, end_xdx_r], 'frame_names': ['start', 'end']}} +# # Fit the model +# Repr = rf.RofuncML.TPGMMBi(demos_left_x, demos_right_x, task_params, plot=False) +# model_l, model_r = Repr.fit() +# +# # Reproductions for the same situations +# traj_l, traj_r, _, _ = Repr.reproduce([model_l, model_r], show_demo_idx=2) +# +# # Reproductions for new situations +# ref_demo_idx = 2 +# start_xdx_l = [Repr.repr_l.demos_xdx[ref_demo_idx][0]] +# end_xdx_l = [Repr.repr_l.demos_xdx[ref_demo_idx][0]] +# start_xdx_r = [Repr.repr_r.demos_xdx[ref_demo_idx][0]] +# end_xdx_r = [Repr.repr_r.demos_xdx[ref_demo_idx][0]] +# Repr.task_params = {'left': {'frame_origins': [start_xdx_l, end_xdx_l], 'frame_names': ['start', 'end']}, +# 'right': {'frame_origins': [start_xdx_r, end_xdx_r], 'frame_names': ['start', 'end']}} +# traj_l, traj_r, _, _ = Repr.generate([model_l, model_r], ref_demo_idx) if __name__ == '__main__': diff --git a/tests/test_tpgmm_bi.py b/tests/test_tpgmm_bi.py index 52b745275..c10031639 100644 --- a/tests/test_tpgmm_bi.py +++ b/tests/test_tpgmm_bi.py @@ -23,7 +23,7 @@ def test_bi_spatial_data(): task_params = {'left': {'frame_origins': [start_xdx_l, end_xdx_l], 'frame_names': ['start', 'end']}, 'right': {'frame_origins': [start_xdx_r, end_xdx_r], 'frame_names': ['start', 'end']}} - Repr = rf.ml.TPGMM_RPCtrl(demos_left_x, demos_right_x, task_params, plot=False) + Repr = rf.RofuncML.TPGMM_RPCtrl(demos_left_x, demos_right_x, task_params, plot=False) model_l, model_r, model_c = Repr.fit() Repr.reproduce([model_l, model_r, model_c], show_demo_idx=2) @@ -54,7 +54,7 @@ def test_bi_temporal_data(): task_params = {'left': {'frame_origins': [start_xdx_l, end_xdx_l], 'frame_names': ['start', 'end']}, 'right': {'frame_origins': [start_xdx_r, end_xdx_r], 'frame_names': ['start', 'end']}} - Repr = rf.ml.TPGMM_RPCtrl(demos_left_x, demos_right_x, task_params, plot=False) + Repr = rf.RofuncML.TPGMM_RPCtrl(demos_left_x, demos_right_x, task_params, plot=False) model_l, model_r, model_c = Repr.fit() Repr.reproduce([model_l, model_r, model_c], show_demo_idx=2) diff --git a/tests/test_tpgmr.py b/tests/test_tpgmr.py index 890083b92..2582af144 100644 --- a/tests/test_tpgmr.py +++ b/tests/test_tpgmr.py @@ -12,7 +12,7 @@ def test_2d_uni_tpgmr(): start_xdx = [demos_x[i][0] for i in range(len(demos_x))] # TODO: change to xdx end_xdx = [demos_x[i][-1] for i in range(len(demos_x))] task_params = {'frame_origins': [start_xdx, end_xdx], 'frame_names': ['start', 'end']} - Repr = rf.ml.TPGMR(demos_x, task_params, plot=False) + Repr = rf.RofuncML.TPGMR(demos_x, task_params, plot=False) model = Repr.fit() traj, _ = Repr.reproduce(model, show_demo_idx=2) @@ -27,7 +27,7 @@ def test_7d_uni_tpgmr(): start_xdx = [demos_x[i][0] for i in range(len(demos_x))] # TODO: change to xdx end_xdx = [demos_x[i][-1] for i in range(len(demos_x))] task_params = {'frame_origins': [start_xdx, end_xdx], 'frame_names': ['start', 'end']} - Repr = rf.ml.TPGMR(demos_x, task_params, plot=False) + Repr = rf.RofuncML.TPGMR(demos_x, task_params, plot=False) model = Repr.fit() # Reproductions for the same situations