Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 import os
00040 from subprocess import check_call
00041
00042 import actionlib_msgs.msg
00043 from geometry_msgs.msg import Pose, PoseStamped, Point, Quaternion
00044 from moveit_commander import MoveGroupCommander, conversions
00045 from rospkg import RosPack
00046 import roslib
00047 import rospy
00048 import std_msgs.msg
00049 from tf.transformations import quaternion_from_euler
00050
00051
00052
00053 rospy.init_node("test_vs060_moveit")
00054
00055 g_runnable = False
00056 g_prev_status = None
00057
00058 arm = MoveGroupCommander("manipulator")
00059 running_pub = rospy.Publisher("/irex_demo_running", std_msgs.msg.Bool);
00060
00061 cancel_pub = rospy.Publisher("/move_group/cancel", actionlib_msgs.msg.GoalID);
00062
00063
00064 _rospack = RosPack()
00065 SCENE_FILE = _rospack.get_path('vs060') + '/model/irex_model.scene'
00066 _path_rosroot = rospy.get_ros_root()
00067 _len_cut = len(_path_rosroot) - len('/share/ros')
00068 _path_rosroot_top = _path_rosroot[:_len_cut]
00069 LOAD_SCENE_PROG = _path_rosroot_top + '/lib/vs060/publish_scene_from_text'
00070
00071 print 'SCENE_FILE=', SCENE_FILE
00072 print 'LOAD_SCENE_PROG=', LOAD_SCENE_PROG
00073
00074 def demo() :
00075
00076 global g_runnable
00077 running_pub.publish(std_msgs.msg.Bool(g_runnable))
00078 check_call([LOAD_SCENE_PROG, SCENE_FILE])
00079 for p in [[ 0.35, -0.35, 0.4],
00080 [ 0.6, 0.0, 0.4],
00081 [ 0.35, 0.35, 0.4],
00082 [ 0.6, 0.0, 0.2],
00083 [ 0.4, 0.0, 0.8]]:
00084 running_pub.publish(std_msgs.msg.Bool(g_runnable))
00085 if g_runnable:
00086 print "set_pose_target(", p, ")"
00087 pose = PoseStamped(header = rospy.Header(stamp = rospy.Time.now(), frame_id = '/BASE'),
00088 pose = Pose(position = Point(*p),
00089 orientation = Quaternion(*quaternion_from_euler(1.57, 0, 1.57, 'sxyz'))))
00090
00091 arm.set_pose_target(pose)
00092 arm.go() or arm.go() or rospy.logerr("arm.go fails")
00093 rospy.sleep(1)
00094 if rospy.is_shutdown():
00095 return
00096
00097 if __name__ == "__main__":
00098 while not rospy.is_shutdown():
00099 demo()
00100