Skip to content

Commit 9740a1c

Browse files
committed
renaming init_configuration to zero_configuration
1 parent 2467a50 commit 9740a1c

File tree

3 files changed

+10
-10
lines changed

3 files changed

+10
-10
lines changed

docs/examples/03_backends_ros/files/02_inverse_kinematics.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
robot = Robot(client)
77

88
frame_WCF = Frame([0.3, 0.1, 0.5], [1, 0, 0], [0, 1, 0])
9-
start_configuration = robot.init_configuration()
9+
start_configuration = robot.zero_configuration()
1010

1111
configuration = robot.inverse_kinematics(frame_WCF, start_configuration)
1212

docs/examples/03_backends_ros/files/02_inverse_kinematics_ros_loader.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
robot = client.load_robot()
66

77
frame_WCF = Frame([0.3, 0.1, 0.5], [1, 0, 0], [0, 1, 0])
8-
start_configuration = robot.init_configuration()
8+
start_configuration = robot.zero_configuration()
99

1010
configuration = robot.inverse_kinematics(frame_WCF, start_configuration)
1111

src/compas_fab/robots/robot.py

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -185,7 +185,7 @@ def get_end_effector_frame(self, group=None, full_configuration=None):
185185
:class: `compas.geometry.Frame`
186186
"""
187187
if full_configuration is None:
188-
full_configuration = self.init_configuration()
188+
full_configuration = self.zero_configuration()
189189
full_joint_state = dict(zip(full_configuration.joint_names, full_configuration.values))
190190
return self.model.forward_kinematics(full_joint_state, link_name=self.get_end_effector_link_name(group))
191191

@@ -248,7 +248,7 @@ def get_base_frame(self, group=None, full_configuration=None):
248248
:class: `compas.geometry.Frame`
249249
"""
250250
if full_configuration is None:
251-
full_configuration = self.init_configuration()
251+
full_configuration = self.zero_configuration()
252252
full_joint_state = dict(zip(full_configuration.joint_names, full_configuration.values))
253253
return self.model.forward_kinematics(full_joint_state, link_name=self.get_base_link_name(group))
254254

@@ -389,12 +389,12 @@ def get_configurable_joint_types(self, group=None):
389389
# configurations
390390
# ==========================================================================
391391

392-
def init_configuration(self, group=None):
392+
def zero_configuration(self, group=None):
393393
"""Returns the init joint configuration.
394394
395395
Examples
396396
--------
397-
>>> robot.init_configuration('manipulator')
397+
>>> robot.zero_configuration('manipulator')
398398
Configuration((0.000, 0.000, 0.000, 0.000, 0.000, 0.000), (0, 0, 0, 0, 0, 0), \
399399
('shoulder_pan_joint', 'shoulder_lift_joint', 'elbow_joint', 'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint'))
400400
"""
@@ -503,7 +503,7 @@ def _check_full_configuration(self, full_configuration=None):
503503
if not len(configuration.joint_names):
504504
configuration.joint_names = joint_names
505505
else:
506-
configuration = self.init_configuration() # with joint_names
506+
configuration = self.zero_configuration() # with joint_names
507507

508508
return configuration
509509

@@ -696,7 +696,7 @@ def attach_tool(self, tool, group=None, touch_links=None):
696696
tool.attached_collision_mesh = AttachedCollisionMesh(tool.collision_mesh, ee_link_name, touch_links)
697697
self.attached_tool = tool
698698
if self.artist:
699-
self.update(self.init_configuration(), group=group, visual=True, collision=True) # TODO: this is not so ideal! should be called from within artist
699+
self.update(self.zero_configuration(), group=group, visual=True, collision=True) # TODO: this is not so ideal! should be called from within artist
700700
self.artist.attach_tool(tool)
701701

702702
def detach_tool(self):
@@ -942,7 +942,7 @@ def inverse_kinematics(self, frame_WCF, start_configuration=None,
942942
Examples
943943
--------
944944
>>> frame_WCF = Frame([0.3, 0.1, 0.5], [1, 0, 0], [0, 1, 0])
945-
>>> start_configuration = robot.init_configuration()
945+
>>> start_configuration = robot.zero_configuration()
946946
>>> group = robot.main_group_name
947947
>>> robot.inverse_kinematics(frame_WCF, start_configuration, group) # doctest: +SKIP
948948
Configuration((4.045, 5.130, -2.174, -6.098, -5.616, 6.283), (0, 0, 0, 0, 0, 0)) # doctest: +SKIP
@@ -1025,7 +1025,7 @@ def forward_kinematics(self, full_configuration, group=None, backend=None, link_
10251025
if link_name not in self.get_link_names(group):
10261026
raise ValueError("Link name %s does not exist in planning group" % link_name)
10271027

1028-
zero_configuration = self.init_configuration()
1028+
zero_configuration = self.zero_configuration()
10291029
if len(full_configuration.values) != len(zero_configuration.values):
10301030
full_configuration = self.merge_group_with_full_configuration(full_configuration, zero_configuration, group)
10311031
full_configuration = self._check_full_configuration(full_configuration)

0 commit comments

Comments
 (0)