diff --git a/README.md b/README.md index 388dfea43830ee227d5117225cab934d3e8cd579..bda1a27168f246453577c7dc1454943eb6b8c202 100644 --- a/README.md +++ b/README.md @@ -60,4 +60,15 @@ Here is a checklist of what to do together with the key remarks. the only TODO is to add the gripper to the simulator somehow, but you can also just skip using it when simulating. -TODO:: explain hom transf mat +#TODO for students +- explain hom transf mat +- make this documentation prettier + +# TODO for profit +- writing documentation, making text and video tutorials to the point where this can be used as teaching material + +#TODO for fun. general point: get a collection of control algorithms for the arm +- implement and test other inverse kinematics algorithms +- rewrite finalized dmp (and other) code into C++ +- learn pybind, create python bindings for that code +- create a DMP from multiple trajectories (actually learn a DMP from multiple examples) diff --git a/dmp/.notes.md.swp b/dmp/.notes.md.swp new file mode 100644 index 0000000000000000000000000000000000000000..af62b6937c3771714f9fe8dd420469879cfe0038 Binary files /dev/null and b/dmp/.notes.md.swp differ diff --git a/dmp/my_sol/.create_dmp.py.swp b/dmp/my_sol/.create_dmp.py.swp new file mode 100644 index 0000000000000000000000000000000000000000..ccf79eb987906d4a922574488965cf0993317338 Binary files /dev/null and b/dmp/my_sol/.create_dmp.py.swp differ diff --git a/dmp/my_sol/.run_dmp.py.swp b/dmp/my_sol/.run_dmp.py.swp new file mode 100644 index 0000000000000000000000000000000000000000..9e41aba318dc810933ed1d8655a411c2590406d2 Binary files /dev/null and b/dmp/my_sol/.run_dmp.py.swp differ diff --git a/dmp/my_sol/.temporal_coupling.py.swp b/dmp/my_sol/.temporal_coupling.py.swp new file mode 100644 index 0000000000000000000000000000000000000000..8c4f6bb34f5adee1ba3b007865778db26f988418 Binary files /dev/null and b/dmp/my_sol/.temporal_coupling.py.swp differ diff --git a/dmp/my_sol/create_dmp.py b/dmp/my_sol/create_dmp.py index 066e64fb84c9901883fc1d4ffc4c15c772431a58..b9d7a6dd4b517fe9f367018129cb2b7b357d620c 100644 --- a/dmp/my_sol/create_dmp.py +++ b/dmp/my_sol/create_dmp.py @@ -1,31 +1,50 @@ import numpy as np - +# TODO: +# 1. change the dimensions so that they make sense, +# i.e. shape = (N_points, dimension_of_points) +# 2. change hand-written numerical differentiation +# to numpy calls (for code style more than anything) +# 3. separate x into z and s variables, this is unnecessarily complicated + +# k,d are constanst which determine the baseline uncostrained dynamics +# these work fine, but it could be good to play around with them just to +# see their effect. normally people set them so that you get critical damping +# as the uncostrained system class DMP: def __init__(self, k=100, d=20, a_s=1, n_bfs=100): + # TODO load the trajectory here + # and then allocate all these with zeros of appopriate length + # as this way they're basically declared twice + # parameters + # for whatever reason, k, d and a_s don't match the , + # OG formulation: tau * z_dot = alpha_z * (beta_z * (g - y) - z) + f(x) + # this formulation: tau * z_dot = k * (g - y) - d * z + f(x) = h (z, y, s) + # i.e. k = beta_z * alpha_z + # d = alpha_z self.k = k self.d = d self.a_s = a_s self.n_bfs = n_bfs # trajectory parameters - self.n = 0 - self.y0 = None - self.tau0 = None - self.g = None - self.tau = None + self.n = 0 # n of dofs + self.y0 = None # initial position + self.tau0 = None # final time + self.g = None # goal positions + self.tau = None # scaling factor, updated online to ensure traj is followed # initialize basis functions for LWR - self.w = None - self.centers = None - self.widths = None + self.w = None # weights of basis functions + self.centers = None # centers of basis functions + self.widths = None # widths of basis functions # state self.x = None self.theta = None - self.pos = None - self.vel = None - self.acc = None + self.pos = None # position + self.vel = None # velocity + self.acc = None # acceleration # desired path self.path = None @@ -38,13 +57,9 @@ class DMP: # TODO pass other trajectories as arguments and etc to make this nice def load_trajectory(self): - # load trajectory. the current one is something on ur10, but apart from scale it's the same robot - # and this is just joint positions - #trajectory_loadpath = './ur10_omega_trajectory.csv' + # load trajectory. this is just joint positions. trajectory_loadpath = './new_traj.csv' data = np.genfromtxt(trajectory_loadpath, delimiter=',') - # this one is slow enough - #self.time = data[:, 0] * 1.5 self.time = data[:, 0] self.time = self.time.reshape(1, len(self.time)) self.y = np.array(data[:, 1:]).T diff --git a/dmp/my_sol/drawing_gen/.cliking_the_path.py.swp b/dmp/my_sol/drawing_gen/.cliking_the_path.py.swp new file mode 100644 index 0000000000000000000000000000000000000000..d1cca6873b6fb0050ee28d2f71905ab50bcdb369 Binary files /dev/null and b/dmp/my_sol/drawing_gen/.cliking_the_path.py.swp differ diff --git a/dmp/my_sol/drawing_gen/.draw_path.py.swp b/dmp/my_sol/drawing_gen/.draw_path.py.swp new file mode 100644 index 0000000000000000000000000000000000000000..9ea5eca545c56746695523ee25b68fca2bfe33c5 Binary files /dev/null and b/dmp/my_sol/drawing_gen/.draw_path.py.swp differ diff --git a/dmp/my_sol/drawing_gen/draw_path.py b/dmp/my_sol/drawing_gen/draw_path.py index 1c6bd814033b7a1fc4a6b043dfcb6a7e5d12b6ef..c192a4e12185177b8306672dc7553e3e9bfc2a1f 100644 --- a/dmp/my_sol/drawing_gen/draw_path.py +++ b/dmp/my_sol/drawing_gen/draw_path.py @@ -1,13 +1,26 @@ +# TODO: possible improvement: +# - draw multiple lines +# - then you would just generate multiple dmps for each trajectory +# and do movel's + movej's to provide the connections +# TODO: possible improvement: make it all bezier curves +# https://matplotlib.org/stable/users/explain/artists/paths.html +# look at the example for path handling if that's what you'll need + import numpy as np import matplotlib.pyplot as plt -# used for drawing -# it's hacked from lasso where there's drawing -from matplotlib.path import Path +# LassoSelector is used for drawing. +# The class actually just does the drawing with mouse input, +# and the rest of processing is done on the obtained path. +# Thus it is the correct tool for the job and there's no need +# to reimplement it from mouse events. from matplotlib.widgets import LassoSelector - +# Path is the most generic matplotlib class. +# It has some convenient functions to handle the draw line, +# i.e. collection of points, but just refer to matplotlib +# documentation and examples on Lasso and Path to see more. +#from matplotlib.path import Path class DrawPath: - def __init__(self, ax): self.canvas = ax.figure.canvas self.lasso = LassoSelector(ax, onselect=self.onselect) @@ -15,6 +28,7 @@ class DrawPath: def onselect(self, verts): # verts is a list of tuples self.path = np.array( [ [i[0], i[1]] for i in verts ] ) + # this would refresh the canvas and remove the drawing #self.canvas.draw_idle() def disconnect(self): @@ -27,9 +41,8 @@ if __name__ == '__main__': # we can multiply however we want later # idk about the number of points, but it's large enough to draw # a smooth curve on the screen, so it's enough for the robot to draw as well i assume - # NOTE: possible improvement: make it all bezier curves - # https://matplotlib.org/stable/users/explain/artists/paths.html - # look at the example for path handling if that's what you'll need + # --> it is, and the system operates well + # depending on the curve the number of points is in the 50-200 range subplot_kw = dict(xlim=(0, 1), ylim=(0, 1), autoscale_on=False) fig, ax = plt.subplots(subplot_kw=subplot_kw) @@ -41,11 +54,12 @@ if __name__ == '__main__': print(selector.path) selector.disconnect() ax.set_title("") + # TODO: ensure this runs fine after packaging np.savetxt("./path_in_pixels.csv", selector.path, delimiter=',', fmt='%.5f') - print("TODO: run clik on me") + print("TODO: run clik on the pixel path to make it a trajectory") exit() fig.canvas.mpl_connect("key_press_event", accept) - ax.set_title("Press 'Enter' to accept drawn path.") + ax.set_title("The drawing has to be 1 continuous line. Press 'Enter' to accept the drawn path. ") plt.show() diff --git a/dmp/my_sol/path_in_pixels.csv b/dmp/my_sol/path_in_pixels.csv new file mode 100644 index 0000000000000000000000000000000000000000..c25397419b0f784eaa433da12452680e10063cce --- /dev/null +++ b/dmp/my_sol/path_in_pixels.csv @@ -0,0 +1,346 @@ +0.28565,0.60847 +0.28416,0.60847 +0.28416,0.60997 +0.28416,0.61147 +0.28268,0.61297 +0.27971,0.61747 +0.27377,0.62347 +0.27377,0.62497 +0.26634,0.63696 +0.26486,0.63996 +0.26486,0.64146 +0.26486,0.64296 +0.26634,0.64446 +0.26634,0.64596 +0.27228,0.65496 +0.28119,0.67745 +0.28268,0.68345 +0.28565,0.69095 +0.28862,0.69695 +0.30198,0.71944 +0.30495,0.72844 +0.30792,0.73444 +0.31683,0.75544 +0.32277,0.76443 +0.32425,0.76893 +0.32722,0.77943 +0.34058,0.80043 +0.35098,0.82592 +0.35692,0.83192 +0.35989,0.84242 +0.36583,0.84841 +0.38067,0.87241 +0.38364,0.87841 +0.38513,0.88291 +0.38661,0.88441 +0.39404,0.89041 +0.39552,0.89041 +0.39701,0.89041 +0.39849,0.89041 +0.39998,0.88891 +0.40295,0.88741 +0.41186,0.88441 +0.43264,0.86341 +0.43858,0.85741 +0.44452,0.85141 +0.45789,0.82742 +0.46086,0.82292 +0.46383,0.81692 +0.47422,0.78543 +0.48164,0.77343 +0.49055,0.74794 +0.49352,0.73894 +0.49649,0.73294 +0.49946,0.72394 +0.50689,0.71345 +0.50837,0.70895 +0.50837,0.70745 +0.51134,0.70295 +0.51431,0.69695 +0.51431,0.69545 +0.51431,0.69395 +0.51431,0.69245 +0.51283,0.69095 +0.51134,0.68645 +0.50243,0.67895 +0.50095,0.67895 +0.49946,0.67895 +0.50095,0.68045 +0.50689,0.68345 +0.51431,0.68945 +0.53064,0.69845 +0.57519,0.71794 +0.58558,0.72544 +0.59004,0.72694 +0.62567,0.74494 +0.63161,0.75094 +0.64052,0.75394 +0.65092,0.76143 +0.65537,0.76443 +0.68804,0.77493 +0.69398,0.78093 +0.69991,0.78243 +0.72516,0.79743 +0.72961,0.80043 +0.73852,0.80343 +0.74001,0.80343 +0.74001,0.80193 +0.74001,0.80043 +0.74001,0.79893 +0.74001,0.79443 +0.74001,0.78993 +0.74001,0.78543 +0.74001,0.76893 +0.74001,0.76593 +0.74001,0.76143 +0.74446,0.74494 +0.74446,0.74044 +0.74446,0.73594 +0.74446,0.72094 +0.74446,0.71944 +0.74001,0.70295 +0.73852,0.69845 +0.73555,0.68195 +0.73258,0.67595 +0.72516,0.66546 +0.71179,0.64296 +0.71179,0.64146 +0.70585,0.63696 +0.70437,0.63546 +0.69991,0.62947 +0.67913,0.60847 +0.67467,0.60697 +0.66873,0.59947 +0.66725,0.59947 +0.66131,0.59647 +0.65685,0.59347 +0.65388,0.59197 +0.64795,0.58897 +0.64646,0.58897 +0.63161,0.58598 +0.63013,0.58448 +0.62567,0.58448 +0.62419,0.58298 +0.61825,0.58298 +0.61676,0.58298 +0.61825,0.58298 +0.61973,0.58298 +0.62122,0.58298 +0.66131,0.57698 +0.67022,0.57398 +0.67764,0.57248 +0.71179,0.56048 +0.72070,0.56048 +0.75337,0.54998 +0.75485,0.54998 +0.75782,0.54848 +0.76228,0.54848 +0.76376,0.54548 +0.76822,0.54398 +0.77416,0.54099 +0.77861,0.53949 +0.77861,0.53799 +0.77861,0.53649 +0.78010,0.53499 +0.78307,0.52899 +0.78307,0.52749 +0.78307,0.52599 +0.78307,0.52449 +0.78158,0.51999 +0.77713,0.51399 +0.77119,0.50799 +0.76525,0.50199 +0.74149,0.48250 +0.73407,0.47650 +0.72664,0.47350 +0.69991,0.45700 +0.69546,0.45401 +0.68507,0.44801 +0.65982,0.43751 +0.65388,0.43601 +0.64795,0.43001 +0.63013,0.42101 +0.62567,0.42101 +0.62419,0.41801 +0.61825,0.41651 +0.61676,0.41651 +0.61528,0.41651 +0.61528,0.41801 +0.61231,0.41951 +0.61082,0.42251 +0.61082,0.42401 +0.60934,0.42701 +0.60785,0.42701 +0.60637,0.43001 +0.60489,0.43001 +0.60489,0.43151 +0.60489,0.43301 +0.60192,0.43601 +0.60192,0.43751 +0.60043,0.43901 +0.60043,0.44051 +0.60043,0.44201 +0.59895,0.44201 +0.59895,0.44051 +0.59004,0.41351 +0.58558,0.40302 +0.57964,0.39702 +0.54401,0.34003 +0.53658,0.32803 +0.52322,0.31004 +0.51134,0.29804 +0.50392,0.28304 +0.48313,0.25905 +0.47570,0.24705 +0.45492,0.22606 +0.44898,0.21706 +0.44155,0.21106 +0.44007,0.20656 +0.42077,0.19157 +0.41631,0.18707 +0.41037,0.18107 +0.40443,0.17507 +0.40146,0.17507 +0.40146,0.17357 +0.40295,0.17357 +0.40295,0.17507 +0.39998,0.17657 +0.39998,0.17807 +0.39849,0.18257 +0.39849,0.18407 +0.39552,0.19307 +0.38364,0.22756 +0.38364,0.23955 +0.38067,0.24855 +0.38067,0.25755 +0.37474,0.29954 +0.37177,0.30854 +0.36731,0.34453 +0.36731,0.36103 +0.36434,0.37002 +0.35840,0.40452 +0.35840,0.41501 +0.35543,0.42551 +0.35098,0.45700 +0.35098,0.46150 +0.35098,0.46450 +0.35098,0.46600 +0.35098,0.46750 +0.35098,0.46900 +0.35098,0.46750 +0.35098,0.46600 +0.34801,0.46300 +0.34652,0.46150 +0.34504,0.45700 +0.34058,0.45251 +0.33464,0.44651 +0.31237,0.42401 +0.30792,0.41951 +0.28862,0.40452 +0.28416,0.40002 +0.27525,0.39702 +0.27228,0.39552 +0.26486,0.39252 +0.26337,0.39252 +0.24704,0.38952 +0.24259,0.38952 +0.24110,0.38652 +0.23219,0.38652 +0.23071,0.38652 +0.22922,0.38652 +0.22774,0.38652 +0.22625,0.38652 +0.22180,0.38952 +0.21734,0.38952 +0.21734,0.39102 +0.21289,0.39252 +0.21289,0.39402 +0.20992,0.39552 +0.20992,0.39702 +0.20992,0.39852 +0.20843,0.40002 +0.20843,0.41501 +0.20843,0.42101 +0.20843,0.43001 +0.21140,0.43901 +0.22180,0.46900 +0.22328,0.47500 +0.22774,0.48550 +0.24259,0.51249 +0.24555,0.52299 +0.25595,0.54698 +0.25892,0.55148 +0.26486,0.55748 +0.26783,0.56648 +0.27228,0.57098 +0.28862,0.59797 +0.29010,0.60247 +0.29307,0.60397 +0.29158,0.60247 +0.29010,0.60247 +0.28862,0.59947 +0.28713,0.59797 +0.28565,0.59647 +0.28119,0.59497 +0.27228,0.58897 +0.26783,0.58598 +0.24110,0.57098 +0.23071,0.56648 +0.19804,0.54998 +0.18765,0.54249 +0.17280,0.53649 +0.15498,0.52749 +0.12974,0.51399 +0.11934,0.51099 +0.10895,0.50649 +0.10301,0.50499 +0.10153,0.50499 +0.10153,0.50649 +0.10153,0.50799 +0.10450,0.51249 +0.11192,0.53349 +0.11934,0.54548 +0.12677,0.55598 +0.16240,0.61447 +0.16983,0.62947 +0.18022,0.64296 +0.18913,0.65796 +0.21586,0.70445 +0.23071,0.73594 +0.23368,0.74044 +0.24110,0.75244 +0.24259,0.76143 +0.25298,0.78693 +0.25595,0.79143 +0.25892,0.79593 +0.26040,0.79743 +0.26189,0.80642 +0.26189,0.80792 +0.26337,0.80792 +0.26337,0.80942 +0.26486,0.80942 +0.26634,0.80942 +0.26931,0.80942 +0.26931,0.80792 +0.27080,0.80642 +0.27080,0.80492 +0.27674,0.79893 +0.27971,0.79743 +0.28565,0.78693 +0.28565,0.78543 +0.28713,0.78543 +0.28862,0.78393 +0.28862,0.78243 +0.29010,0.78093 +0.29010,0.77943 +0.29158,0.77793 +0.29158,0.77643 +0.29307,0.77343 +0.29455,0.76893 +0.29455,0.76743 +0.29455,0.76293 +0.29901,0.75394 +0.29901,0.74794 +0.30198,0.74344 +0.30198,0.74194 +0.30198,0.74194 diff --git a/dmp/my_sol/run_dmp.py b/dmp/my_sol/run_dmp.py index 554104b7a0b0e1be5c274d8b934c6b89b23e46c2..e8096c486fc188008ae37f82febd3fccd49bbe8a 100644 --- a/dmp/my_sol/run_dmp.py +++ b/dmp/my_sol/run_dmp.py @@ -1,6 +1,6 @@ from create_dmp import DMP -from rtde_control import RTDEControlInterface as RTDEControl -from rtde_receive import RTDEReceiveInterface as RTDEReceive +from rtde_control import RTDEControlInterface +from rtde_receive import RTDEReceiveInterface from rtde_io import RTDEIOInterface from robotiq_gripper import RobotiqGripper from temporal_coupling import NoTC, TCVelAccConstrained @@ -15,18 +15,45 @@ import copy sys.path.insert(0, '../../util') from give_me_the_calibrated_model import get_model +# TODO: +# 1. clean up these instantiations in a separate util file +# and just do a line-liner importing -> need to make this a package to get rid +# of the relative-path imports +# 2. delete the unnecessary comments +# 3. figure out how to scale the dmp velocity when creating it -> DONE +# 4. parametrize everything, put argparse with defaults in a separate file +# like in tianshou examples. make magic numbers arguments! +# also add helpfull error messages based on this, ex. if interfaces couldn't connect +# with the simulation argument on, write out "check whether you started the simulator" +# 5. remove all unused code: +# - for stuff that could work, make a separate file +# - just remove stuff that's a remnant of past tries +# 6. put visualization into a separate file for visualization +# 7. put an actual low-pass filter over the force-torque sensor +# 8. add some code to pick up the marker from a prespecified location +# 9. add the (optional) decomposition of force feedback so that +# you get hybrid motion-force control +# 10. write documentation as you go along + +# create models +# TODO make a argument for loading/not loading and running gepetto visualization urdf_path_relative = "../../robot_descriptions/urdf/ur5e_with_robotiq_hande.urdf" urdf_path_absolute = os.path.abspath(urdf_path_relative) mesh_dir = "../../robot_descriptions/" mesh_dir_absolute = os.path.abspath(mesh_dir) model, data = get_model(urdf_path_absolute, mesh_dir_absolute) -rtde_control = RTDEControl("192.168.1.102") -rtde_receive = RTDEReceive("192.168.1.102") +# create and connect robot communication interfaces +rtde_control = RTDEControlInterface("192.168.1.102") +rtde_receive = RTDEReceiveInterface("192.168.1.102") rtde_io = RTDEIOInterface("192.168.1.102") -# on scale from 0 to 1 -rtde_io.setSpeedSlider(0.7) +# on scale from 0 to 1 set the maximum allowed speed on the robot. +# it's a global thing on the robot +# TODO make this an argument +speed_slider = 0.7 +rtde_io.setSpeedSlider(speed_slider) +# TODO add a use gripper argument # run if marker isn't gripped #gripper = RobotiqGripper() #gripper.connect("192.168.1.102", 63352) @@ -35,22 +62,27 @@ rtde_io.setSpeedSlider(0.7) #gripper.move(255,100,100) #time.sleep(3) +# TODO create a simulation argument! #rtde_control = RTDEControl("127.0.0.1") #rtde_receive = RTDEReceive("127.0.0.1") +# TODO make N_iter and argument N_ITER = 10000 +# TODO gather all vector memory allocation in one place +# allocate memory for vectors (use numpy arrays instead of default python linked lists) qs = np.zeros((N_ITER, 6)) dmp_poss = np.zeros((N_ITER, 6)) dqs = np.zeros((N_ITER, 6)) dmp_vels = np.zeros((N_ITER, 6)) - +# TODO move to util file +# catch SIGINT def handler(signum, frame): print('sending 100 speedjs full of zeros') for i in range(100): vel_cmd = np.zeros(6) rtde_control.speedJ(vel_cmd, 0.1, 1.0 / 500) - +# TODO make a separate visualization file and put this in a function there print('also plotting') t = np.arange(N_ITER) ax_q = plt.subplot(221) @@ -76,20 +108,34 @@ def handler(signum, frame): # if not rtde_control.isProgramRunning(): # exit() +# catch SIGINT signal.signal(signal.SIGINT, handler) + +####################################################################### +# initalization # +####################################################################### + +# load trajectory, create DMP based on it dmp = DMP() +# get up from the board current_pose = rtde_receive.getActualTCPPose() current_pose[2] = current_pose[2] + 0.03 rtde_control.moveL(current_pose) +# move to initial pose +# this is a blocking call rtde_control.moveJ(dmp.pos.reshape((6,))) -# TODO check that you're there instead of a sleep -#t.sleep(3) +# TODO make all these arguments TEMPORAL_COUPLING = True update_rate = 500 +# TODO calculate this when setting default arguments dt = 1.0 / update_rate JOINT_ID = 6 +# ======================================================================== +# TODO: either write a separate file where this is used +# ---> TODO write a separate file where you're testing this out +# or just delete it task_frame = [0, 0, 0, 0, 0, 0] # these are in {0,1} and select which task frame direction compliance is active in # just be soft everywhere @@ -105,8 +151,12 @@ ftype = 2 # and where is this set?) # why these values? limits = [2, 2, 2, 2, 2, 2] +# ======================================================================== + + # parameters from yaml config file in albin's repo +# TODO: make these arguments kp = 2 acceleration = 1.7 #acceleration = 0.5 @@ -115,15 +165,16 @@ if not TEMPORAL_COUPLING: tc = NoTC() else: # TODO learn the math already + # TODO MAKE THESE ARGUMENTS tau0 = 5 gamma_nominal = 1.0 gamma_a = 0.5 eps = 0.001 - v_max = np.ones(6) * 2 + v_max = np.ones(6) * 2 * speed_slider a_max = np.ones(6) * 1.7 tc = TCVelAccConstrained(gamma_nominal, gamma_a, v_max, a_max, eps) -# TODO: check sign! +# TODO make this an argument alpha = 0.003 # lame hack for the current orientation (which it doesn't change so it's ok) wrench_offset = np.array([-1.07988, -1.407225, -2.63069, 0.071115, -0.0487768, 0.089271]) @@ -138,7 +189,10 @@ for i in range(N_ITER): tau = dmp.tau + tc.update(dmp, dt) * dt dmp.set_tau(tau) q = rtde_receive.getActualQ() - # TODO this fucker feel the weight of the gripper, this causes bias -> fix it! + # TODO and NOTE the weight, TCP and inertial matrix needs to be set on the robot + # you already found an API in rtde_control for this, just put it in initialization + # under using/not-using gripper parameters + # TODO: document the mathematics with one-line comments wrench = np.array(rtde_receive.getActualTCPForce()) wrench_avg[i % 5] = wrench wrench = np.average(wrench_avg, axis=0) @@ -170,6 +224,9 @@ for i in range(N_ITER): dmp_poss[i] = dmp.pos.reshape((6,)) dqs[i] = dq.reshape((6,)) dmp_vels[i] = dmp.vel.reshape((6,)) + # TODO make start-end times a function wrapper or something, + # so that it is in every controller for-loop by default + # (or leave it here, whatever) end = time.time() diff = end - start if dt < diff: @@ -181,6 +238,7 @@ for i in range(N_ITER): if (np.linalg.norm(dmp.vel) < 0.0001) and (i > 5000): break +# call the handler to stop movement handler(None, None) #print(vel_cmd[0][0]) diff --git a/dmp/notes.md b/dmp/notes.md index aeb3bfa15ada961675be7cae16a97ab45dd51361..32224266b2a8c4cf28655aac16b758c0ba0ab6be 100644 --- a/dmp/notes.md +++ b/dmp/notes.md @@ -68,7 +68,12 @@ def compute_ctrl(self, target_state, robot_state): return vel_cmd ``` -# add some impedance to live with errors +# add some impedance to live with errors - DONE, but needs filtering -------------------------------------- - f/t readings are added and works fine for impedance -- TODO: cancel out the gripper weight +- TODO: cancel out the gripper weight -> DONE, but TODO put the payload + assignment into code to avoid surprises + +# make a main file that runs all of it at once +---------------------------------------- +- do it