43 sys.modules[
"pyassimp"] = sys
48 from subprocess
import check_call
50 import actionlib_msgs.msg
51 from geometry_msgs.msg
import Pose, PoseStamped, Point, Quaternion
52 from moveit_commander
import MoveGroupCommander, conversions
53 from rospkg
import RosPack
57 from tf.transformations
import quaternion_from_euler
61 rospy.init_node(
"test_vs060_moveit")
63 arm = MoveGroupCommander(
"manipulator")
64 running_pub = rospy.Publisher(
"/irex_demo_running", std_msgs.msg.Bool);
66 cancel_pub = rospy.Publisher(
"/move_group/cancel", actionlib_msgs.msg.GoalID);
70 SCENE_FILE = _rospack.get_path(
'vs060') +
'/model/irex_model.scene' 71 _path_rosroot = rospy.get_ros_root()
72 _len_cut = len(_path_rosroot) - len(
'/share/ros')
73 _path_rosroot_top = _path_rosroot[:_len_cut]
74 LOAD_SCENE_PROG = _path_rosroot_top +
'/lib/vs060/publish_scene_from_text' 76 print 'SCENE_FILE=', SCENE_FILE
77 print 'LOAD_SCENE_PROG=', LOAD_SCENE_PROG
81 check_call([LOAD_SCENE_PROG, SCENE_FILE])
82 for p
in [[ 0.35, -0.35, 0.4],
88 print "set_pose_target(", p,
")" 89 pose = PoseStamped(header = rospy.Header(stamp = rospy.Time.now(), frame_id =
'/BASE'),
90 pose = Pose(position = Point(*p),
91 orientation = Quaternion(*quaternion_from_euler(1.57, 0, 1.57,
'sxyz'))))
93 arm.set_pose_target(pose)
94 arm.go()
or arm.go()
or rospy.logerr(
"arm.go fails")
96 if rospy.is_shutdown():
99 if __name__ ==
"__main__":
100 while not rospy.is_shutdown():