diff --git a/python/examples/crocoddyl_ocp_clik.py b/python/examples/crocoddyl_ocp_clik.py index b8e3940cbf38901fe5f7baa9633da7f8f4a26da7..84d2a1cea22016e8810f8796c449ace62f6f2b8e 100644 --- a/python/examples/crocoddyl_ocp_clik.py +++ b/python/examples/crocoddyl_ocp_clik.py @@ -29,6 +29,8 @@ if __name__ == "__main__": # both because there can be disturbances, # and because it is sampled at a much lower frequency jointTrajFollowingPD(args, robot, reference) + #reference.pop('dt') + #plotFromDict(reference, args.n_knots + 1, args) print("final position:") print(robot.getT_w_e()) diff --git a/python/examples/heron_pls.py b/python/examples/heron_pls.py new file mode 100644 index 0000000000000000000000000000000000000000..346ff92fe46f84f3190c2710a0860472e3920ad9 --- /dev/null +++ b/python/examples/heron_pls.py @@ -0,0 +1,50 @@ +import numpy as np +import argparse +from functools import partial +from ur_simple_control.managers import getMinimalArgParser, ControlLoopManager, RobotManager +from ur_simple_control.clik.clik import getClikArgs, getClikController, controlLoopClik, moveL, compliantMoveL +from ur_simple_control.util.get_model import heron_approximation +import time +from pinocchio.visualize import MeshcatVisualizer +import pinocchio as pin + +def get_args(): + parser = getMinimalArgParser() + parser.description = 'mpc for heron path following' + parser = get_OCP_args(parser) + args = parser.parse_args() + return args + +if __name__ == "__main__": + args = get_args() + + model, collision_model, visual_model, data = heron_approximation(args) + print(model) + viz = MeshcatVisualizer(model, collision_model, visual_model) + viz.initViewer(open=True) + viz.loadViewerModel() + q = np.zeros(model.nq) + theta = np.random.random() * 2*np.pi + q[2] = np.cos(theta) + q[3] = np.sin(theta) + v = np.random.random(model.nv) + #q = np.random.random(model.nq) * 0.5 + for i in range(10000): + q = pin.integrate(model, q, v * 0.001) + viz.display(q) + +# robot = RobotManager(args) +# Mgoal = robot.defineGoalPointCLI() +# compliantMoveL(args, robot, Mgoal) +# robot.closeGripper() +# robot.openGripper() +# if not args.pinocchio_only: +# robot.stopRobot() +# +# if args.visualize_manipulator: +# robot.killManipulatorVisualizer() +# +# if args.save_log: +# robot.log_manager.saveLog() +# #loop_manager.stopHandler(None, None) +#