|
1 | 1 | #!/usr/bin/python
|
2 |
| -import time, subprocess, os |
| 2 | +import time, subprocess, os, rospy |
3 | 3 | from sys import argv
|
4 | 4 | from run_test_utils import runCommandClient, run_test
|
| 5 | +import rospkg |
5 | 6 |
|
6 | 7 | try:
|
7 | 8 | # Python 2
|
8 | 9 | input = raw_input # noqa
|
9 | 10 | except NameError:
|
10 | 11 | pass
|
11 | 12 |
|
12 |
| -folder = str(os.path.dirname(os.path.abspath(__file__))) |
13 |
| -folder = folder + "/../traj_multicontact_api/dat/" |
| 13 | +PKG_NAME='talos-torque-control' |
| 14 | + |
| 15 | +rospack = rospkg.RosPack() |
| 16 | +pkg_path = rospack.get_path(PKG_NAME) |
| 17 | +folder= pkg_path+ "/traj_multicontact_api/dat/" |
14 | 18 | walk_type = "on_spot"
|
15 | 19 | pattern_generator = False
|
16 | 20 |
|
17 |
| -if len(argv) == 2 and argv[1] == "on_spot": |
| 21 | +if len(argv) == 4 and argv[1] == "on_spot": |
18 | 22 | print("Starting script with folder " + folder + " walking on spot.")
|
19 |
| -elif len(argv) == 2 and argv[1] == "walk_20": |
| 23 | +elif len(argv) == 4 and argv[1] == "walk_20": |
20 | 24 | print("Starting script with folder " + folder + " walking with 20cm step.")
|
21 | 25 | walk_type = "walk_20"
|
22 |
| -elif len(argv) == 3 and argv[1] == "on_spot" and argv[2] == "pattern_generator": |
| 26 | +elif len(argv) == 5 and argv[1] == "on_spot" and argv[2] == "pattern_generator": |
23 | 27 | pattern_generator = True
|
24 | 28 | print("Starting script with pattern_generator walking on spot.")
|
25 |
| -elif len(argv) == 3 and argv[1] == "walk_20" and argv[2] == "pattern_generator": |
| 29 | +elif len(argv) == 5 and argv[1] == "walk_20" and argv[2] == "pattern_generator": |
26 | 30 | pattern_generator = True
|
27 | 31 | walk_type = "walk_20"
|
28 | 32 | print("Starting script with pattern_generator walking with 20cm step.")
|
29 |
| -elif len(argv) == 3 and argv[1] == "on_spot": |
| 33 | +elif len(argv) == 5 and argv[1] == "on_spot": |
30 | 34 | folder = argv[2]
|
31 | 35 | print("Starting script with folder " + folder + " walking on spot.")
|
32 |
| -elif len(argv) == 3 and argv[1] == "walk_20": |
| 36 | +elif len(argv) == 5 and argv[1] == "walk_20": |
33 | 37 | folder = argv[2]
|
34 | 38 | print("Starting script with folder " + folder + " walking with 20cm step.")
|
35 | 39 | walk_type = "walk_20"
|
| 40 | +# Default option: on_spot, without pattern generator |
| 41 | +elif len(argv) == 3: |
| 42 | + print("Starting script with folder " + folder + " walking on spot.") |
| 43 | + |
36 | 44 | else:
|
37 | 45 | print("Usage: python sim_walk_torque.py walk_type:=[on_spot|walk_20] {pattern_generator|path_folder_of_the_reference_trajectories}")
|
38 | 46 | print("By giving only the walk_type the script starts using the default file trajectories")
|
|
42 | 50 | runCommandClient('folder = "' + folder + '"')
|
43 | 51 | runCommandClient('walk_type = "' + walk_type + '"')
|
44 | 52 | print("Starting script whith inverse_dyn_balance_controller main_sim_walk_torque.py")
|
45 |
| - run_test('../python/dynamic_graph/sot/torque_control/talos/main_sim_walk_torque.py') |
| 53 | + run_test(pkg_path + '/../../lib/'+PKG_NAME+'/main_sim_walk_torque.py') |
46 | 54 | else:
|
47 | 55 | runCommandClient('walk_type = "' + walk_type + '"')
|
48 | 56 | print("Starting script whith inverse_dyn_balance_controller main_sim_walk_torque_online.py")
|
49 |
| - run_test('../python/dynamic_graph/sot/torque_control/talos/main_sim_walk_torque_online.py') |
| 57 | + run_test(pkg_path + '/../../lib/'+PKG_NAME+'/main_sim_walk_torque_online.py') |
| 58 | + |
| 59 | +#initializing node to read ros time |
| 60 | +rospy.init_node('test_torque_walking', anonymous=True) |
50 | 61 |
|
51 |
| -input("Waiting before writing the graph") |
| 62 | +#input("Waiting before writing the graph") |
| 63 | +time.sleep(5) |
52 | 64 | runCommandClient("from dynamic_graph import writeGraph")
|
53 | 65 |
|
54 | 66 | print("WriteGraph in /tmp/sot_talos_tsid.dot")
|
|
57 | 69 | proc3 = subprocess.Popen(["dot", "-Tpdf", "/tmp/sot_talos_tsid_walk.dot", "-o", "/tmp/sot_talos_tsid_walk_torque.pdf"])
|
58 | 70 |
|
59 | 71 | if pattern_generator:
|
60 |
| - input("Waiting before setting gains") |
| 72 | + #input("Waiting before setting gains") |
| 73 | + time.sleep(3) |
61 | 74 | print("Setting gains")
|
62 | 75 | runCommandClient("robot.inv_dyn.kp_feet.value = 6*(250,)")
|
63 |
| - runCommandClient("robot.inv_dyn.kp_com.value = 3*(400,)") |
| 76 | + #runCommandClient("robot.inv_dyn.kp_com.value = 3*(400,)") |
64 | 77 | runCommandClient("robot.inv_dyn.kd_feet.value = 6*(12,)")
|
65 |
| - runCommandClient("robot.inv_dyn.kd_com.value = 3*(12,)") |
66 |
| - input("Waiting before playing trajectories") |
| 78 | + #runCommandClient("robot.inv_dyn.kd_com.value = 3*(12,)") |
| 79 | + #input("Waiting before playing trajectories") |
| 80 | + time.sleep(2) |
67 | 81 | runCommandClient('robot.triggerPG.sin.value = 1')
|
68 |
| - input("Wait before stopping the trajectory") |
| 82 | + rospy.sleep(70) #arbitrary value |
| 83 | + #input("Wait before stopping the trajectory") |
69 | 84 | runCommandClient('robot.pg.velocitydes.value=(0.0,0.0,0.0)')
|
70 | 85 | else:
|
71 |
| - input("Waiting before setting gains") |
| 86 | + #input("Waiting before setting gains") |
| 87 | + time.sleep(3) |
72 | 88 | print("Setting gains")
|
73 | 89 | runCommandClient("robot.inv_dyn.kp_feet.value = 6*(200,)")
|
74 |
| - runCommandClient("robot.inv_dyn.kp_com.value = 3*(250,)") |
| 90 | + # runCommandClient("robot.inv_dyn.kp_com.value = 3*(250,)") |
75 | 91 | runCommandClient("robot.inv_dyn.kd_feet.value = 6*(12,)")
|
76 |
| - runCommandClient("robot.inv_dyn.kd_com.value = 3*(12,)") |
77 |
| - input("Waiting before playing trajectories") |
| 92 | + # runCommandClient("robot.inv_dyn.kd_com.value = 3*(12,)") |
| 93 | + #input("Waiting before playing trajectories") |
| 94 | + time.sleep(2) |
78 | 95 | print("Playing trajectories")
|
79 | 96 | runCommandClient("robot.traj_sync.turnOn()")
|
80 |
| - input("Waiting before stopping the trajectories") |
| 97 | + rospy.sleep(64) #64 seconds is the time necessary for the on_spot trajectory (the longest one) |
| 98 | + #input("Waiting before stopping the trajectories") |
81 | 99 | print("Stop trajectories")
|
82 | 100 | runCommandClient("robot.traj_sync.turnOff()")
|
83 | 101 |
|
84 | 102 | time.sleep(2.0)
|
85 |
| -input("Wait before going to halfSitting") |
| 103 | +#input("Wait before going to halfSitting") |
86 | 104 | runCommandClient("go_to_position(robot.traj_gen, robot.halfSitting[6:], 5.0)")
|
87 | 105 | time.sleep(5.0)
|
88 | 106 | print("The robot is back in position!")
|
|
0 commit comments