File tree Expand file tree Collapse file tree 1 file changed +10
-7
lines changed
doc/planning_scene_python/src Expand file tree Collapse file tree 1 file changed +10
-7
lines changed Original file line number Diff line number Diff line change 1
1
#!/usr/bin/env python
2
2
import sys
3
+ import rospy
3
4
4
5
def main ():
5
- rospy .init_node ("planning_scene_tutorial" )
6
- moveit_commander .roscpp_initialize (sys .argv )
7
-
8
6
# BEGIN_TUTORIAL
9
7
#
10
8
# Setup
@@ -19,13 +17,18 @@ def main():
19
17
# using data from the robot's joints and the sensors on the robot. In
20
18
# this tutorial, we will instantiate a PlanningScene class directly,
21
19
# but this method of instantiation is only intended for illustration.
22
- import moveit_commander
23
- import numpy as np
24
- import rospy
25
20
from geometry_msgs .msg import PoseStamped
26
- import moveit .core
27
21
from moveit .core import kinematic_constraints , collision_detection , robot_model
28
22
from moveit .core .planning_scene import PlanningScene
23
+ import moveit .core
24
+ import moveit_commander
25
+ import numpy as np
26
+ import pathlib
27
+ import rospkg
28
+ import rospy
29
+
30
+ rospy .init_node ("planning_scene_tutorial" )
31
+ moveit_commander .roscpp_initialize (sys .argv )
29
32
30
33
r = rospkg .RosPack ()
31
34
urdf_path = pathlib .Path (r .get_path ("moveit_resources_panda_description" )) / "urdf" / "panda.urdf"
You can’t perform that action at this time.
0 commit comments