From 20e30a4567f34159bfbd831741b8bcb27c7ce0bb Mon Sep 17 00:00:00 2001 From: Kolin Guo Date: Wed, 21 Feb 2024 16:55:57 -0800 Subject: [PATCH] Move user_link_names before generate_collision_pair() --- mplib/planner.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/mplib/planner.py b/mplib/planner.py index d1c3d32..f44fbe1 100644 --- a/mplib/planner.py +++ b/mplib/planner.py @@ -72,6 +72,8 @@ def __init__( verbose=False, ) self.pinocchio_model = self.robot.get_pinocchio_model() + self.user_link_names = self.pinocchio_model.get_link_names() + self.user_joint_names = self.pinocchio_model.get_joint_names() self.planning_world = PlanningWorld( [self.robot], @@ -84,10 +86,6 @@ def __init__( self.generate_collision_pair() self.robot.update_SRDF(self.srdf) - self.pinocchio_model = self.robot.get_pinocchio_model() - self.user_link_names = self.pinocchio_model.get_link_names() - self.user_joint_names = self.pinocchio_model.get_joint_names() - self.joint_name_2_idx = {} for i, joint in enumerate(self.user_joint_names): self.joint_name_2_idx[joint] = i