-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathfunction_call.py
185 lines (147 loc) · 7.74 KB
/
function_call.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
import os
import sys
import time
import math
try:
from coppeliasim_zmqremoteapi_client import RemoteAPIClient
except ImportError:
print(' -- ERROR: Set up CoppeliaSim ZeroMQ client as described here: '\
'https://manual.coppeliarobotics.com/en/zmqRemoteApiOverview.htm')
sys.exit()
client = RemoteAPIClient(host='localhost')
sim = client.require('sim')
# status = sim.loadScene(os.path.abspath('./panda_uibk_ffrob_problem32_close_blocks_ompl_david_bounds.ttt'))
status = sim.loadScene(os.path.abspath('./panda_blocks_simple.ttt'))
# -- loading required modules for simulation:
simIK = client.require('simIK')
simOMPL = client.require('simOMPL')
def ompl_path_planning(
goal_pose: list[float],
robot_name: str = "Panda",
num_ompl_attempts: int = 6,
max_compute: int = 10,
max_simplify: int = -1,
len_path: int = 0,
) -> bool:
# -- create a dummy object that will represent the target goal:
target_goal = sim.createDummy(0.025)
sim.setObjectPose(target_goal, goal_pose, sim.getObject(f'/{robot_name}'))
sim.setObjectColor(target_goal, 0, sim.colorcomponent_ambient_diffuse, [0.0, 1.0, 1.0])
sim.setObjectColor(target_goal, 0, sim.colorcomponent_emission, [0.6, 0.6, 0.6])
sim.setObjectAlias(target_goal, 'OMPL_target')
# -- we sleep for a bit so we can see this object appear in the sim:
time.sleep(0.0001)
ompl_script = sim.getScript(sim.scripttype_simulation, sim.getObject('/OMPLement'))
path = sim.callScriptFunction(
"ompl_path_planning",
ompl_script,
{
"robot": robot_name,
"goal": target_goal,
"algorithm": simOMPL.Algorithm.RRTConnect,
"num_attempts": num_ompl_attempts,
"max_compute": max_compute,
"max_simplify": max_simplify,
"len_path": len_path,
"state_resolution": float("5.0e-2"),
"use_lua": False,
"use_state_validation": True,
},
)
if path:
sim.addLog(sim.verbosity_default, f'[OMPLement]: plan found!')
# -- we need to disable the IK following done by the "target" dummy of the robot:
# sim.setModelProperty(target, sim.modelproperty_scripts_inactive)
ik_script = sim.getScript(sim.scripttype_simulation, sim.getObject(f"/{robot_name}"))
if ik_script == -1:
ik_script = sim.getScript(sim.scripttype_customization, sim.getObject(f"/{robot_name}"))
sim.setObjectInt32Param(ik_script, sim.scriptintparam_enabled, 0)
# -- with the computed path, we will gradually change the configuration of the robot:
for P in range(len(path)):
sim.callScriptFunction('setConfig_python', ompl_script, path[P])
time.sleep(float('2.5e-3'))
time.sleep(0.01)
# -- we need to re-enable the IK following done by the "target" dummy of the robot:
sim.setObjectPosition(sim.getObject(f'/{robot_name}/target'), sim.getObjectPosition(sim.getObject(f'/{robot_name}/tip')), -1)
sim.setObjectOrientation(sim.getObject(f'/{robot_name}/target'), sim.getObjectOrientation(sim.getObject(f'/{robot_name}/tip')), -1)
sim.setObjectInt32Param(ik_script, sim.scriptintparam_enabled, 1)
else:
sim.addLog(sim.verbosity_default, f'[OMPLement]: plan not found!')
# -- remove the OMPL target object:
sim.removeObjects([sim.getObject('/OMPL_target')])
return bool(path)
def find_pose_for_ompl(
robot_name: str,
target_object: str,
) -> list[float]:
robot = sim.getObject(f"/{robot_name}")
target = sim.getObject(f"/{robot_name}/target")
index = 0
# # -- check if the target object refers to the table, as we will have to find an empty spot:
# if target_object in ["table", "worksurface"]:
# empty_spot = choice(find_empty_spots())
# index, target_object = empty_spot['index'], sim.getObjectAlias(empty_spot['handle'])
# sim.addLog(sim.verbosity_default, f"table grounding: found empty spot: /{target_object}[{empty_spot['index']}]")
# if verbose:
# print(f"table grounding: found empty spot: /{target_object}[{empty_spot['index']}]")
goal = sim.getObject(f"/{target_object}", {"index": index})
candidate_goal_poses = []
for rotate in [0.0, (math.pi)]:
# -- Find a collision-free config that matches a specific pose:
goal_pose = sim.getObjectPose(goal, robot)
# -- get the object handles for the gripper's attach point:
gripper_attachPoint = -1
children = sim.getObjectsInTree(sim.getObject(f"/{robot_name}"))
for C in children:
if "attachPoint" in sim.getObjectAlias(C):
gripper_attachPoint = C
if gripper_attachPoint == -1:
sys.exit("ERROR: robot gripper attach point was not found!")
# -- determine the height based on whether there is an object in hand or not:
obj_in_hand = sim.getObjectChild(gripper_attachPoint, 0)
if obj_in_hand != -1:
# -- first, we find a spot that sits RIGHT ON TOP of the surface...
goal_pose[2] += sim.getObjectFloatParam(goal, sim.objfloatparam_objbbox_max_z)
# ... then we will find a spot that considers the height of the object:
goal_pose[2] += sim.getObjectFloatParam(obj_in_hand, sim.objfloatparam_objbbox_max_z) * (1.5 if target_object not in ["table", "worksurface"] else 1.25)
# -- we also want to consider the orientation of the object
orientation = sim.getObjectOrientation(goal, target)
goal_pose[3:] = sim.buildPose(goal_pose[:3], [orientation[0], orientation[1], math.pi + rotate])[3:]
else:
# -- account for fingertip placement on object:
goal_pose[2] += sim.getObjectFloatParam(goal, sim.objfloatparam_objbbox_max_z) * 3.0
# -- try to match the orientation of the surface object:
orientation = sim.getObjectOrientation(goal, robot)
goal_pose[3:] = sim.buildPose(goal_pose[:3], [-(math.pi), orientation[1], orientation[2] + rotate])[3:]
# NOTE: these are the ideal poses that Alejandro would use for picking from the side:
# if obj_in_hand != -1:
# # -- first, we find a spot that sits RIGHT ON TOP of the surface...
# goal_pose[0] += sim.getObjectFloatParam(goal, sim.objfloatparam_objbbox_max_x)
# # ... then we will find a spot that considers the height of the object:
# goal_pose[0] += sim.getObjectFloatParam(obj_in_hand, sim.objfloatparam_objbbox_max_x) * (1.5 if target_object not in ["table", "worksurface"] else 1.25)
# # -- we also want to consider the orientation of the object
# orientation = sim.getObjectOrientation(goal, target)
# goal_pose[3:] = sim.buildPose(goal_pose[:3], [orientation[0], orientation[1], math.pi + rotate])[3:]
# else:
# # -- account for fingertip placement on object:
# goal_pose[0] -= sim.getObjectFloatParam(goal, sim.objfloatparam_objbbox_max_x) * 3
# # -- try to match the orientation of the surface object:
# orientation = sim.getObjectOrientation(goal, robot)
# goal_pose[3:] = sim.buildPose(goal_pose[:3], [orientation[0], math.pi/2, orientation[2] + rotate])[3:]
candidate_goal_poses.append(goal_pose)
return candidate_goal_poses
sim.startSimulation()
try:
for target_object in ["B_block_1", "D_block_3", "C_block_3"]:
goal_poses = find_pose_for_ompl(
robot_name="Panda",
target_object=target_object)
for _ in range(1):
for G in goal_poses:
success = ompl_path_planning(
goal_pose=G,
)
except Exception:
pass
sim.stopSimulation()
pass