irex_demo_noteaching.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2013, Tokyo Opensource Robotics Kyokai Association
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of Tokyo Opensource Robotics Kyokai Association. nor the
19 # names of its contributors may be used to endorse or promote products
20 # derived from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 #
35 # Author: Isaac Isao Saito
36 
37 ## THIS IS A COPY FROM irex_demo.py, removing reading dead-man switch from pendant
38 
39 #%Tag(FULLTEXT)%
40 
41 ## workaround until https://github.com/ros-planning/moveit/pull/581 is released
42 import sys
43 sys.modules["pyassimp"] = sys
44 import pyassimp
45 
46 
47 import os
48 from subprocess import check_call
49 
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
54 import roslib
55 import rospy
56 import std_msgs.msg
57 from tf.transformations import quaternion_from_euler
58 #roslib.load_manifest("denso_pendant_publisher")
59 #roslib.load_manifest("actionlib_msgs")
60 
61 rospy.init_node("test_vs060_moveit")
62 
63 arm = MoveGroupCommander("manipulator")
64 running_pub = rospy.Publisher("/irex_demo_running", std_msgs.msg.Bool);
65 #cancel_pub = rospy.Publisher("/arm_controller/follow_joint_trajectory/cancel", actionlib_msgs.msg.GoalID);
66 cancel_pub = rospy.Publisher("/move_group/cancel", actionlib_msgs.msg.GoalID);
67 
68 # Get paths for files used later.
69 _rospack = RosPack()
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') # This is used to get ros root path /opt/%DISTRO% path.
73 _path_rosroot_top = _path_rosroot[:_len_cut]
74 LOAD_SCENE_PROG = _path_rosroot_top + '/lib/vs060/publish_scene_from_text'
75 
76 print 'SCENE_FILE=', SCENE_FILE
77 print 'LOAD_SCENE_PROG=', LOAD_SCENE_PROG
78 
79 def demo() :
80  # load scene
81  check_call([LOAD_SCENE_PROG, SCENE_FILE])
82  for p in [[ 0.35, -0.35, 0.4],
83  [ 0.6, 0.0, 0.4],
84  [ 0.35, 0.35, 0.4],
85  [ 0.6, 0.0, 0.2],
86  [ 0.4, 0.0, 0.8]]:
87  if True:
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'))))
92 
93  arm.set_pose_target(pose)
94  arm.go() or arm.go() or rospy.logerr("arm.go fails")
95  rospy.sleep(1)
96  if rospy.is_shutdown():
97  return
98 
99 if __name__ == "__main__":
100  while not rospy.is_shutdown():
101  demo()
102 #%EndTag(FULLTEXT)%


vs060
Author(s): Ryohei Ueda
autogenerated on Mon Jun 10 2019 13:13:22