Skip to content

Commit c36118e

Browse files
Levi ArmstrongLevi-Armstrong
authored andcommitted
Switch get_tesseract() to get_environment() in python tests
1 parent 0b2a3be commit c36118e

File tree

6 files changed

+85
-90
lines changed

6 files changed

+85
-90
lines changed

tesseract_python/tesseract_python/tests/tesseract_motion_planning/test_descartes_planner.py

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -27,27 +27,27 @@ def _locate_resource(url):
2727
except:
2828
traceback.print_exc()
2929

30-
def get_tesseract():
30+
def get_environment():
3131
locate_resource_fn = SimpleResourceLocatorFn(_locate_resource)
3232
locator = SimpleResourceLocator(locate_resource_fn)
33-
tesseract = Environment()
33+
env = Environment()
3434
tesseract_support = os.environ["TESSERACT_SUPPORT_DIR"]
3535
urdf_path = FilesystemPath(os.path.join(tesseract_support, "urdf/lbr_iiwa_14_r820.urdf"))
3636
srdf_path = FilesystemPath(os.path.join(tesseract_support, "urdf/lbr_iiwa_14_r820.srdf"))
37-
assert tesseract.init(urdf_path, srdf_path, locator)
37+
assert env.init(urdf_path, srdf_path, locator)
3838
manip_info = ManipulatorInfo()
3939
manip_info.manipulator = "manipulator"
4040

41-
return tesseract, manip_info
41+
return env, manip_info
4242

4343
def test_ompl_freespace_joint_cart():
4444

45-
tesseract, manip = get_tesseract()
45+
env, manip = get_environment()
4646

47-
fwd_kin = tesseract.getManipulatorManager().getFwdKinematicSolver(manip.manipulator)
48-
inv_kin = tesseract.getManipulatorManager().getInvKinematicSolver(manip.manipulator)
47+
fwd_kin = env.getManipulatorManager().getFwdKinematicSolver(manip.manipulator)
48+
inv_kin = env.getManipulatorManager().getInvKinematicSolver(manip.manipulator)
4949
joint_names = fwd_kin.getJointNames()
50-
cur_state = tesseract.getCurrentState()
50+
cur_state = env.getCurrentState()
5151

5252
wp1 = JointWaypoint(joint_names, np.array([0,0,0,-1.57,0,0,0],dtype=np.float64))
5353
wp2 = CartesianWaypoint(Isometry3d.Identity() * Translation3d(-.2,.4,0.2) * Quaterniond(0,0,1.0,0))
@@ -60,7 +60,7 @@ def test_ompl_freespace_joint_cart():
6060
program.setManipulatorInfo(manip)
6161
program.append(Instruction(plan_f1))
6262

63-
seed = generateSeed(program, cur_state, tesseract, 3.14, 1.0, 3.14, 10)
63+
seed = generateSeed(program, cur_state, env, 3.14, 1.0, 3.14, 10)
6464

6565
plan_profile = DescartesDefaultPlanProfileD()
6666

@@ -72,8 +72,8 @@ def test_ompl_freespace_joint_cart():
7272
request = PlannerRequest()
7373
request.seed = seed
7474
request.instructions = program
75-
request.env = tesseract
76-
request.env_state = tesseract.getCurrentState()
75+
request.env = env
76+
request.env_state = env.getCurrentState()
7777

7878
response = PlannerResponse()
7979

tesseract_python/tesseract_python/tests/tesseract_motion_planning/test_ompl_planner.py

Lines changed: 18 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -27,27 +27,27 @@ def _locate_resource(url):
2727
except:
2828
traceback.print_exc()
2929

30-
def get_tesseract():
30+
def get_environment():
3131
locate_resource_fn = SimpleResourceLocatorFn(_locate_resource)
3232
locator = SimpleResourceLocator(locate_resource_fn)
33-
tesseract = Environment()
33+
env = Environment()
3434
tesseract_support = os.environ["TESSERACT_SUPPORT_DIR"]
3535
urdf_path = FilesystemPath(os.path.join(tesseract_support, "urdf/lbr_iiwa_14_r820.urdf"))
3636
srdf_path = FilesystemPath(os.path.join(tesseract_support, "urdf/lbr_iiwa_14_r820.srdf"))
37-
assert tesseract.init(urdf_path, srdf_path, locator)
37+
assert env.init(urdf_path, srdf_path, locator)
3838
manip_info = ManipulatorInfo()
3939
manip_info.manipulator = "manipulator"
4040

41-
return tesseract, manip_info
41+
return env, manip_info
4242

4343
def test_ompl_freespace_joint_cart():
4444

45-
tesseract, manip = get_tesseract()
45+
env, manip = get_environment()
4646

47-
fwd_kin = tesseract.getManipulatorManager().getFwdKinematicSolver(manip.manipulator)
48-
inv_kin = tesseract.getManipulatorManager().getInvKinematicSolver(manip.manipulator)
47+
fwd_kin = env.getManipulatorManager().getFwdKinematicSolver(manip.manipulator)
48+
inv_kin = env.getManipulatorManager().getInvKinematicSolver(manip.manipulator)
4949
joint_names = fwd_kin.getJointNames()
50-
cur_state = tesseract.getCurrentState()
50+
cur_state = env.getCurrentState()
5151

5252
wp1 = JointWaypoint(joint_names, np.array([0,0,0,-1.57,0,0,0],dtype=np.float64))
5353
wp2 = CartesianWaypoint(Isometry3d.Identity() * Translation3d(-.2,.4,0.2) * Quaterniond(0,0,1.0,0))
@@ -60,7 +60,7 @@ def test_ompl_freespace_joint_cart():
6060
program.setManipulatorInfo(manip)
6161
program.append(Instruction(plan_f1))
6262

63-
seed = generateSeed(program, cur_state, tesseract, 3.14, 1.0, 3.14, 10)
63+
seed = generateSeed(program, cur_state, env, 3.14, 1.0, 3.14, 10)
6464

6565
plan_profile = OMPLDefaultPlanProfile()
6666

@@ -72,8 +72,8 @@ def test_ompl_freespace_joint_cart():
7272
request = PlannerRequest()
7373
request.seed = seed
7474
request.instructions = program
75-
request.env = tesseract
76-
request.env_state = tesseract.getCurrentState()
75+
request.env = env
76+
request.env_state = env.getCurrentState()
7777

7878
response = PlannerResponse()
7979

@@ -94,12 +94,12 @@ def test_ompl_freespace_joint_cart():
9494

9595
def test_ompl_freespace_joint_cart_rrtstar():
9696

97-
tesseract, manip = get_tesseract()
97+
env, manip = get_environment()
9898

99-
fwd_kin = tesseract.getManipulatorManager().getFwdKinematicSolver(manip.manipulator)
100-
inv_kin = tesseract.getManipulatorManager().getInvKinematicSolver(manip.manipulator)
99+
fwd_kin = env.getManipulatorManager().getFwdKinematicSolver(manip.manipulator)
100+
inv_kin = env.getManipulatorManager().getInvKinematicSolver(manip.manipulator)
101101
joint_names = fwd_kin.getJointNames()
102-
cur_state = tesseract.getCurrentState()
102+
cur_state = env.getCurrentState()
103103

104104
wp1 = JointWaypoint(joint_names, np.array([0,0,0,-1.57,0,0,0],dtype=np.float64))
105105
wp2 = CartesianWaypoint(Isometry3d.Identity() * Translation3d(-.2,.4,0.2) * Quaterniond(0,0,1.0,0))
@@ -112,7 +112,7 @@ def test_ompl_freespace_joint_cart_rrtstar():
112112
program.setManipulatorInfo(manip)
113113
program.append(Instruction(plan_f1))
114114

115-
seed = generateSeed(program, cur_state, tesseract, 3.14, 1.0, 3.14, 10)
115+
seed = generateSeed(program, cur_state, env, 3.14, 1.0, 3.14, 10)
116116

117117
plan_profile = OMPLDefaultPlanProfile()
118118
plan_profile.planners.clear()
@@ -126,8 +126,8 @@ def test_ompl_freespace_joint_cart_rrtstar():
126126
request = PlannerRequest()
127127
request.seed = seed
128128
request.instructions = program
129-
request.env = tesseract
130-
request.env_state = tesseract.getCurrentState()
129+
request.env = env
130+
request.env_state = env.getCurrentState()
131131

132132
response = PlannerResponse()
133133

tesseract_python/tesseract_python/tests/tesseract_motion_planning/test_simple_planner.py

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -23,30 +23,30 @@ def _locate_resource(url):
2323
except:
2424
traceback.print_exc()
2525

26-
def get_tesseract():
26+
def get_environment():
2727
locate_resource_fn = SimpleResourceLocatorFn(_locate_resource)
2828
locator = SimpleResourceLocator(locate_resource_fn)
29-
tesseract = Environment()
29+
env = Environment()
3030
tesseract_support = os.environ["TESSERACT_SUPPORT_DIR"]
3131
urdf_path = FilesystemPath(os.path.join(tesseract_support, "urdf/lbr_iiwa_14_r820.urdf"))
3232
srdf_path = FilesystemPath(os.path.join(tesseract_support, "urdf/lbr_iiwa_14_r820.srdf"))
33-
assert tesseract.init(urdf_path, srdf_path, locator)
33+
assert env.init(urdf_path, srdf_path, locator)
3434
manip_info = ManipulatorInfo()
3535
manip_info.manipulator = "manipulator"
36-
joint_names = tesseract.getManipulatorManager().getFwdKinematicSolver("manipulator").getJointNames()
36+
joint_names = env.getManipulatorManager().getFwdKinematicSolver("manipulator").getJointNames()
3737

38-
return tesseract, manip_info, joint_names
38+
return env, manip_info, joint_names
3939

40-
def test_get_tesseract():
41-
get_tesseract()
40+
def test_get_environment():
41+
get_environment()
4242

4343
def test_interpolatestatewaypoint_jointcart_freespace():
44-
tesseract, manip_info, joint_names = get_tesseract()
44+
env, manip_info, joint_names = get_environment()
4545

4646
request = PlannerRequest()
47-
request.env = tesseract
48-
request.env_state = tesseract.getCurrentState()
49-
fwd_kin = tesseract.getManipulatorManager().getFwdKinematicSolver(manip_info.manipulator)
47+
request.env = env
48+
request.env_state = env.getCurrentState()
49+
fwd_kin = env.getManipulatorManager().getFwdKinematicSolver(manip_info.manipulator)
5050
wp1 = JointWaypoint(joint_names, np.zeros((7,),dtype=np.float64))
5151
wp2 = CartesianWaypoint(fwd_kin.calcFwdKin(np.ones((7,),dtype=np.float64))[1])
5252
instr = PlanInstruction(Waypoint(wp1), PlanInstructionType_FREESPACE, "TEST_PROFILE", manip_info)
@@ -61,4 +61,4 @@ def test_interpolatestatewaypoint_jointcart_freespace():
6161
mi = composite[-1].cast_const_MoveInstruction()
6262
last_position = mi.getWaypoint().cast_const_StateWaypoint().position
6363
_, final_pose = fwd_kin.calcFwdKin(last_position)
64-
assert wp2.isApprox(final_pose, 1e-3)
64+
assert wp2.isApprox(final_pose, 1e-3)

tesseract_python/tesseract_python/tests/tesseract_motion_planning/test_trajopt_planner.py

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -27,28 +27,28 @@ def _locate_resource(url):
2727
except:
2828
traceback.print_exc()
2929

30-
def get_tesseract():
30+
def get_environment():
3131
locate_resource_fn = SimpleResourceLocatorFn(_locate_resource)
3232
locator = SimpleResourceLocator(locate_resource_fn)
33-
tesseract = Environment()
33+
env = Environment()
3434
tesseract_support = os.environ["TESSERACT_SUPPORT_DIR"]
3535
urdf_path = FilesystemPath(os.path.join(tesseract_support, "urdf/lbr_iiwa_14_r820.urdf"))
3636
srdf_path = FilesystemPath(os.path.join(tesseract_support, "urdf/lbr_iiwa_14_r820.srdf"))
37-
assert tesseract.init(urdf_path, srdf_path, locator)
37+
assert env.init(urdf_path, srdf_path, locator)
3838
manip_info = ManipulatorInfo()
3939
manip_info.manipulator = "manipulator"
4040
manip_info.manipulator_ik_solver = "OPWInvKin"
4141

42-
return tesseract, manip_info
42+
return env, manip_info
4343

4444
def test_trajopt_freespace_joint_cart():
4545

46-
tesseract, manip = get_tesseract()
46+
env, manip = get_environment()
4747

48-
fwd_kin = tesseract.getManipulatorManager().getFwdKinematicSolver(manip.manipulator)
49-
inv_kin = tesseract.getManipulatorManager().getInvKinematicSolver(manip.manipulator)
48+
fwd_kin = env.getManipulatorManager().getFwdKinematicSolver(manip.manipulator)
49+
inv_kin = env.getManipulatorManager().getInvKinematicSolver(manip.manipulator)
5050
joint_names = fwd_kin.getJointNames()
51-
cur_state = tesseract.getCurrentState()
51+
cur_state = env.getCurrentState()
5252

5353
wp1 = JointWaypoint(joint_names, np.array([0,0,0,-1.57,0,0,0],dtype=np.float64))
5454
wp2 = CartesianWaypoint(Isometry3d.Identity() * Translation3d(-.2,.4,0.2) * Quaterniond(0,0,1.0,0))
@@ -61,7 +61,7 @@ def test_trajopt_freespace_joint_cart():
6161
program.setManipulatorInfo(manip)
6262
program.append(Instruction(plan_f1))
6363

64-
seed = generateSeed(program, cur_state, tesseract, 3.14, 1.0, 3.14, 10)
64+
seed = generateSeed(program, cur_state, env, 3.14, 1.0, 3.14, 10)
6565

6666
plan_profile = TrajOptDefaultPlanProfile()
6767
composite_profile = TrajOptDefaultCompositeProfile()
@@ -75,8 +75,8 @@ def test_trajopt_freespace_joint_cart():
7575
request = PlannerRequest()
7676
request.seed = seed
7777
request.instructions = program
78-
request.env = tesseract
79-
request.env_state = tesseract.getCurrentState()
78+
request.env = env
79+
request.env_state = env.getCurrentState()
8080

8181
problem = DefaultTrajoptProblemGenerator(test_planner.getName(), request, test_planner.plan_profiles, test_planner.composite_profiles, test_planner.solver_profiles)
8282

tesseract_python/tesseract_python/tests/tesseract_process_managers/test_planning_server.py

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -26,22 +26,22 @@ def _locate_resource(url):
2626
except:
2727
traceback.print_exc()
2828

29-
def get_tesseract():
29+
def get_environment():
3030
locate_resource_fn = SimpleResourceLocatorFn(_locate_resource)
3131
locator = SimpleResourceLocator(locate_resource_fn)
32-
tesseract = Environment()
32+
env = Environment()
3333
tesseract_support = os.environ["TESSERACT_SUPPORT_DIR"]
3434
urdf_path = FilesystemPath(os.path.join(tesseract_support, "urdf/lbr_iiwa_14_r820.urdf"))
3535
srdf_path = FilesystemPath(os.path.join(tesseract_support, "urdf/lbr_iiwa_14_r820.srdf"))
36-
assert tesseract.init(urdf_path, srdf_path, locator)
36+
assert env.init(urdf_path, srdf_path, locator)
3737
manip_info = ManipulatorInfo()
3838
manip_info.manipulator = "manipulator"
3939

40-
return tesseract, manip_info
40+
return env, manip_info
4141

4242
def test_planning_server_freespace():
4343

44-
tesseract, manip = get_tesseract()
44+
env, manip = get_environment()
4545

4646
joint_names = ["joint_a1", "joint_a2", "joint_a3", "joint_a4", "joint_a5", "joint_a6", "joint_a7"]
4747

@@ -56,7 +56,7 @@ def test_planning_server_freespace():
5656
program.setManipulatorInfo(manip)
5757
program.append(Instruction(plan_f1))
5858

59-
planning_server = ProcessPlanningServer(tesseract, 1)
59+
planning_server = ProcessPlanningServer(env, 1)
6060
planning_server.loadDefaultProcessPlanners()
6161
request = ProcessPlanningRequest()
6262
request.name = FREESPACE_PLANNER_NAME

tesseract_python/tesseract_python/tests/tesseract_scene_graph/test_tesseract_scene_graph.py

Lines changed: 27 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -158,53 +158,53 @@ def test_load_srdf_unit():
158158
g.addLink(sg.Link("link_7"))
159159
g.addLink(sg.Link("tool0"))
160160

161-
base_joint = sg.Joint("base_joint")
162-
base_joint.parent_link_name = "base_link"
163-
base_joint.child_link_name = "link_1"
164-
base_joint.type = sg.JointType_FIXED
165-
g.addJoint(base_joint)
166-
167-
joint_1 = sg.Joint("joint_1")
168-
joint_1.parent_link_name = "link_1"
169-
joint_1.child_link_name = "link_2"
170-
joint_1.type = sg.JointType_REVOLUTE
161+
joint_1 = sg.Joint("joint_a1")
162+
joint_1.parent_link_name = "base_link"
163+
joint_1.child_link_name = "link_1"
164+
joint_1.type = sg.JointType_FIXED
171165
g.addJoint(joint_1)
172166

173-
joint_2 = sg.Joint("joint_2")
174-
joint_2.parent_to_joint_origin_transform = _translation([1.25,0,0])
175-
joint_2.parent_link_name = "link_2"
176-
joint_2.child_link_name = "link_3"
167+
joint_2 = sg.Joint("joint_a2")
168+
joint_2.parent_link_name = "link_1"
169+
joint_2.child_link_name = "link_2"
177170
joint_2.type = sg.JointType_REVOLUTE
178171
g.addJoint(joint_2)
179172

180-
joint_3 = sg.Joint("joint_3")
173+
joint_3 = sg.Joint("joint_a3")
181174
joint_3.parent_to_joint_origin_transform = _translation([1.25,0,0])
182-
joint_3.parent_link_name = "link_3"
183-
joint_3.child_link_name = "link_4"
175+
joint_3.parent_link_name = "link_2"
176+
joint_3.child_link_name = "link_3"
184177
joint_3.type = sg.JointType_REVOLUTE
185178
g.addJoint(joint_3)
186179

187-
joint_4 = sg.Joint("joint_4")
188-
joint_4.parent_to_joint_origin_transform = _translation([0,1.25,0])
189-
joint_4.parent_link_name = "link_4"
190-
joint_4.child_link_name = "link_5"
180+
joint_4 = sg.Joint("joint_a4")
181+
joint_4.parent_to_joint_origin_transform = _translation([1.25,0,0])
182+
joint_4.parent_link_name = "link_3"
183+
joint_4.child_link_name = "link_4"
191184
joint_4.type = sg.JointType_REVOLUTE
192185
g.addJoint(joint_4)
193186

194-
joint_5 = sg.Joint("joint_5")
187+
joint_5 = sg.Joint("joint_a5")
195188
joint_5.parent_to_joint_origin_transform = _translation([0,1.25,0])
196-
joint_5.parent_link_name = "link_5"
197-
joint_5.child_link_name = "link_6"
189+
joint_5.parent_link_name = "link_4"
190+
joint_5.child_link_name = "link_5"
198191
joint_5.type = sg.JointType_REVOLUTE
199192
g.addJoint(joint_5)
200193

201-
joint_6 = sg.Joint("joint_6")
194+
joint_6 = sg.Joint("joint_a6")
202195
joint_6.parent_to_joint_origin_transform = _translation([0,1.25,0])
203-
joint_6.parent_link_name = "link_6"
204-
joint_6.child_link_name = "link_7"
196+
joint_6.parent_link_name = "link_5"
197+
joint_6.child_link_name = "link_6"
205198
joint_6.type = sg.JointType_REVOLUTE
206199
g.addJoint(joint_6)
207200

201+
joint_7 = sg.Joint("joint_a7")
202+
joint_7.parent_to_joint_origin_transform = _translation([0,1.25,0])
203+
joint_7.parent_link_name = "link_6"
204+
joint_7.child_link_name = "link_7"
205+
joint_7.type = sg.JointType_REVOLUTE
206+
g.addJoint(joint_7)
207+
208208
joint_tool0 = sg.Joint("base_joint")
209209
joint_tool0.parent_link_name = "link_7"
210210
joint_tool0.child_link_name = "tool0"
@@ -227,8 +227,3 @@ def test_load_srdf_unit():
227227

228228
g.clearAllowedCollisions()
229229
assert len(acm.getAllAllowedCollisions()) == 0
230-
231-
232-
233-
234-

0 commit comments

Comments
 (0)