From 7bf2f541a74440a7eaed82ae474e53b7e7f96e4d Mon Sep 17 00:00:00 2001
From: Peter Mitrano <mitranopeter@gmail.com>
Date: Mon, 19 Jul 2021 16:12:34 -0400
Subject: [PATCH] fix imports

---
 .../src/planning_scene_tutorial.py              | 17 ++++++++++-------
 1 file changed, 10 insertions(+), 7 deletions(-)

diff --git a/doc/planning_scene_python/src/planning_scene_tutorial.py b/doc/planning_scene_python/src/planning_scene_tutorial.py
index cd6901ad5..eca6bcad0 100755
--- a/doc/planning_scene_python/src/planning_scene_tutorial.py
+++ b/doc/planning_scene_python/src/planning_scene_tutorial.py
@@ -1,10 +1,8 @@
 #!/usr/bin/env python
 import sys
+import rospy
 
 def main():
-    rospy.init_node("planning_scene_tutorial")
-    moveit_commander.roscpp_initialize(sys.argv)
-
     # BEGIN_TUTORIAL
     #
     # Setup
@@ -19,13 +17,18 @@ def main():
     # using data from the robot's joints and the sensors on the robot. In
     # this tutorial, we will instantiate a PlanningScene class directly,
     # but this method of instantiation is only intended for illustration.
-    import moveit_commander
-    import numpy as np
-    import rospy
     from geometry_msgs.msg import PoseStamped
-    import moveit.core
     from moveit.core import kinematic_constraints, collision_detection, robot_model
     from moveit.core.planning_scene import PlanningScene
+    import moveit.core
+    import moveit_commander
+    import numpy as np
+    import pathlib
+    import rospkg
+    import rospy
+
+    rospy.init_node("planning_scene_tutorial")
+    moveit_commander.roscpp_initialize(sys.argv)
 
     r = rospkg.RosPack()
     urdf_path = pathlib.Path(r.get_path("moveit_resources_panda_description")) / "urdf" / "panda.urdf"