Skip to content

Commit b5aef89

Browse files
committed
formatting
1 parent 3770887 commit b5aef89

File tree

2 files changed

+10
-9
lines changed

2 files changed

+10
-9
lines changed

doc/planning_scene_python/planning_scene_tutorial.rst

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,4 +45,4 @@ joint values so some things may be different. ::
4545
[INFO] [1615403459.498652]: Test 10: Random state is not constrained
4646
[INFO] [1615403459.503490]: Test 12: Random state is not valid
4747

48-
**Note:** Don't worry if your output has different ROS console format. You can customize your ROS console logger by following `this blog post <http://dav.ee/blog/notes/archives/898>`_.
48+
**Note:** Don't worry if your output has different ROS console format. You can customize your ROS console logger by following `this blog post <http://dav.ee/blog/notes/archives/898>`_.

doc/planning_scene_python/src/planning_scene_tutorial.py

Lines changed: 9 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -29,8 +29,8 @@ def main():
2929
# this tutorial, we will instantiate a PlanningScene class directly,
3030
# but this method of instantiation is only intended for illustration.
3131

32-
urdf_path = '/opt/ros/noetic/share/moveit_resources_panda_description/urdf/panda.urdf'
33-
srdf_path = '/opt/ros/noetic/share/moveit_resources_panda_moveit_config/config/panda.srdf'
32+
urdf_path = "/opt/ros/noetic/share/moveit_resources_panda_description/urdf/panda.urdf"
33+
srdf_path = "/opt/ros/noetic/share/moveit_resources_panda_moveit_config/config/panda.srdf"
3434
kinematic_model = moveit.core.load_robot_model(urdf_path, srdf_path)
3535
planning_scene = PlanningScene(kinematic_model, collision_detection.World())
3636
current_state = planning_scene.getCurrentStateNonConst()
@@ -115,8 +115,8 @@ def main():
115115
joint_values = np.array([0.0, 0.0, 0.0, -2.9, 0.0, 1.4, 0.0])
116116
joint_model_group = current_state.getJointModelGroup("panda_arm")
117117
current_state.setJointGroupPositions(joint_model_group, joint_values)
118-
rospy.loginfo(
119-
f"Test 4: Current state is {'valid' if current_state.satisfiesBounds(joint_model_group) else 'not valid'}")
118+
satisfied_bounds = current_state.satisfiesBounds(joint_model_group)
119+
rospy.loginfo(f"Test 4: Current state is {'valid' if satisfied_bounds else 'not valid'}")
120120

121121
# Modifying the Allowed Collision Matrix
122122
# ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
@@ -163,8 +163,8 @@ def main():
163163
# ^^^^^^^^^^^^^^^^^^^
164164
#
165165
# The PlanningScene class also includes easy to use function calls for checking constraints. The constraints can be
166-
# of two types: (a) constraints constructed using :moveit_core_python:`core.kinematic_constraints`, or (b) user defined
167-
# constraints specified through a callback. We will first look at an example with a simple
166+
# of two types: (a) constraints constructed using :moveit_core_python:`core.kinematic_constraints`,
167+
# or (b) user defined constraints specified through a callback. We will first look at an example with a simple
168168
# KinematicConstraint.
169169
#
170170
# Checking Kinematic Constraints
@@ -207,7 +207,8 @@ def main():
207207

208208
constraint_eval_result = kinematic_constraint_set.decide(copied_state)
209209
rospy.loginfo(
210-
f"Test 10: Random state is {'constrained' if constraint_eval_result.satisfied else 'not constrained'}")
210+
f"Test 10: Random state is {'constrained' if constraint_eval_result.satisfied else 'not constrained'}"
211+
)
211212

212213
# Whenever isStateValid is called, three checks are conducted: (a)
213214
# collision checking (b) constraint checking and (c) feasibility
@@ -224,5 +225,5 @@ def main():
224225
moveit_commander.roscpp_shutdown()
225226

226227

227-
if __name__ == '__main__':
228+
if __name__ == "__main__":
228229
main()

0 commit comments

Comments
 (0)