demo.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 import sys
4 import time
5 import rospy
6 ##-- for smach
7 from smach import State,StateMachine
8 import smach_ros
9 ##-- for navigation
10 import yaml
11 import tf
12 import actionlib
13 from actionlib_msgs.msg import *
14 from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
15 ##-- for find pkg
16 import rospkg
17 ##-- for moveit
18 import moveit_commander
19 import moveit_msgs.msg
20 from geometry_msgs.msg import Pose, PoseStamped
21 import geometry_msgs.msg
22 ##-- for hand control
23 from seed_r7_ros_controller.srv import*
24 
25 
26 ###########################################
27 class NaviAction:
28  def __init__(self):
29  rospack = rospkg.RosPack()
30  rospack.list()
31  path = rospack.get_path('seed_r7_samples')
32  with open(path + '/config/waypoints.yaml') as f:
33  self.config = yaml.load(f)
34  rospy.on_shutdown(self.shutdown)
35  self.ac = actionlib.SimpleActionClient('move_base', MoveBaseAction)
36  while not self.ac.wait_for_server(rospy.Duration(5)):
37  rospy.loginfo("Waiting for the move_base action server to come up")
38  rospy.loginfo("The server comes up");
39  self.goal = MoveBaseGoal()
40 
41  def set_goal(self,_number):
42  rospy.on_shutdown(self.shutdown)
43 
44  rev = dict(self.config[_number]) #List to Dictionary
45 
46  self.goal.target_pose.header.frame_id = 'map'
47  self.goal.target_pose.header.stamp = rospy.Time.now()
48  self.goal.target_pose.pose.position.x = rev['pose']['position']['x']
49  self.goal.target_pose.pose.position.y = rev['pose']['position']['y']
50  self.goal.target_pose.pose.position.z = rev['pose']['position']['z']
51  self.goal.target_pose.pose.orientation.x = rev['pose']['orientation']['x']
52  self.goal.target_pose.pose.orientation.y = rev['pose']['orientation']['y']
53  self.goal.target_pose.pose.orientation.z = rev['pose']['orientation']['z']
54  self.goal.target_pose.pose.orientation.w = rev['pose']['orientation']['w']
55 
56  rospy.loginfo('Sending goal')
57  self.ac.send_goal(self.goal)
58  succeeded = self.ac.wait_for_result(rospy.Duration(60));
59  state = self.ac.get_state();
60  if succeeded:
61  rospy.loginfo("Succeed")
62  return 'succeeded'
63  else:
64  rospy.loginfo("Failed")
65  return 'aborted'
66 
67  def shutdown(self):
68  #rospy.loginfo("The robot was terminated")
69  self.ac.cancel_goal()
70 #--------------------------------
71 class GO_TO_PLACE(State):
72  def __init__(self,_place):
73  State.__init__(self, outcomes=['succeeded','aborted'])
74  self.place_ = _place
75 
76  def execute(self, userdata):
77  rospy.loginfo('Going to Place{}'.format(self.place_))
78  if(na.set_goal(self.place_) == 'succeeded'):return 'succeeded'
79  else: return 'aborted'
80 
81 ###########################################
83  def __init__(self):
84  rospy.loginfo('waiting service')
85  rospy.wait_for_service('/seed_r7_ros_controller/hand_control')
86 
87  def grasp(self):
88  try:
89  service = rospy.ServiceProxy('/seed_r7_ros_controller/hand_control', HandControl)
90  response = service(0,'grasp',100)
91  return True
92  except rospy.ServiceException as e:
93  rospy.logerr('Service call failed: {}'.format(e))
94  return False
95 
96  def release(self):
97  try:
98  service = rospy.ServiceProxy('/seed_r7_ros_controller/hand_control', HandControl)
99  response = service(0,'release',100)
100  return True
101  except rospy.ServiceException as e:
102  rospy.logerr('Service call failed: {}'.format(e))
103  return False
104 
105 ###########################################
107  def __init__(self):
108  self.robot = moveit_commander.RobotCommander()
109  self.scene = moveit_commander.PlanningSceneInterface()
110 
111  self.group = moveit_commander.MoveGroupCommander("rarm_with_torso")
112  self.group.set_pose_reference_frame("base_link")
113 
114  self.box1 = self.box_pose(0.6,-0.3,0.36)
115  self.box2 = self.box_pose(0.7,0.3,0.76)
116  self.box3 = self.box_pose(0.8,0,1.16)
117 
118  self.robot_model = rospy.get_param("/seed_r7_ros_controller/robot_model_plugin")
119 
120  def set_grasp_position(self, x, y, z, vel=1.0,direction="side"):
121  self.group = moveit_commander.MoveGroupCommander("rarm_with_torso")
122  self.group.set_pose_reference_frame("base_link")
123  self.group.set_planner_id( "RRTConnectkConfigDefault" )
124  self.group.allow_replanning( True )
125 
126  target_pose = Pose()
127  if(direction == "side"):
128  self.group.set_end_effector_link("r_eef_grasp_link")
129  quat = tf.transformations.quaternion_from_euler(0,0,0)
130  elif(direction == "top"):
131  self.group.set_end_effector_link("r_eef_pick_link")
132  quat = tf.transformations.quaternion_from_euler(-1.57,0.79,0)
133 
134  target_pose.orientation.x = quat[0]
135  target_pose.orientation.y = quat[1]
136  target_pose.orientation.z = quat[2]
137  target_pose.orientation.w = quat[3]
138 
139  target_pose.position.x = x
140  target_pose.position.y = y
141  target_pose.position.z = z
142 
143  self.group.set_pose_target(target_pose)
144  self.group.set_max_velocity_scaling_factor(vel)
145  plan = self.group.plan()
146  if type(plan) is tuple: # for noetic
147  plan = plan[1]
148 
149  if(len(plan.joint_trajectory.points)==0):
150  rospy.logwarn("IK can't be solved")
151  self.group.clear_pose_targets()
152  return 'aborted'
153  else:
154  self.group.execute(plan)
155  return 'succeeded'
156 
157  def set_lifter_position(self, x, z, vel=1.0):
158  self.group = moveit_commander.MoveGroupCommander("torso")
159  self.group.set_pose_reference_frame("base_link")
160  self.group.set_end_effector_link("body_link")
161  if("typef" in self.robot_model):
162  distance_body_lifter = 1.065 - 0.92
163  elif("typeg" in self.robot_model):
164  distance_body_lifter = 0.994 - 0.857
165 
166  target_pose = Pose()
167 
168  target_pose.orientation.x = 0
169  target_pose.orientation.y = 0
170  target_pose.orientation.z = 0
171  target_pose.orientation.w = 1
172 
173  target_pose.position.x = x
174  target_pose.position.y = 0
175  target_pose.position.z = z + distance_body_lifter
176 
177  self.group.set_start_state_to_current_state()
178  self.group.set_pose_target(target_pose)
179  self.group.set_max_velocity_scaling_factor(vel)
180  plan = self.group.plan()
181  if type(plan) is tuple: # for noetic
182  plan = plan[1]
183 
184  if(len(plan.joint_trajectory.points)==0):
185  rospy.logwarn("can't be solved lifter ik")
186  self.group.clear_pose_targets()
187  return 'aborted'
188  else:
189  self.group.execute(plan)
190  return 'succeeded'
191 
192  def set_initial_pose(self):
193  self.group = moveit_commander.MoveGroupCommander("upper_body")
194  self.group.set_named_target("reset-pose")
195  plan = self.group.plan()
196  if type(plan) is tuple: # for noetic
197  plan = plan[1]
198  self.group.go()
199 
200  if(len(plan.joint_trajectory.points)==0):
201  rospy.logwarn("IK can't be solved")
202  self.group.clear_pose_targets()
203  return 'aborted'
204  else:
205  self.group.execute(plan)
206  return 'succeeded'
207 
208  def wait_for_state_update(self, box_name,box_is_known=False, box_is_attached=False, timeout=4):
209  scene = self.scene
210 
211  start = rospy.get_time()
212  seconds = rospy.get_time()
213  while (seconds - start < timeout) and not rospy.is_shutdown():
214  attached_objects = scene.get_attached_objects([box_name])
215  is_attached = len(attached_objects.keys()) > 0
216 
217  is_known = box_name in scene.get_known_object_names()
218 
219  if (box_is_attached == is_attached) and (box_is_known == is_known):
220  return 'succeeded'
221 
222  rospy.sleep(0.1)
223  seconds = rospy.get_time()
224 
225  return 'aborted'
226 
227  def box_pose(self, x, y, z):
228  box_pose = geometry_msgs.msg.PoseStamped()
229  box_pose.header.frame_id = "base_link"
230  box_pose.pose.position.x = x
231  box_pose.pose.position.y = y
232  box_pose.pose.position.z = z
233  return box_pose
234 
235  def add_objects(self):
236  self.scene.add_box("shelf1", self.box_pose(0.8,0,0.3), size=(0.5, 1.0, 0.01))
237  self.scene.add_box("shelf2", self.box_pose(0.8,0,0.7), size=(0.5, 1.0, 0.01))
238  self.scene.add_box("shelf3", self.box_pose(0.8,0,1.1), size=(0.5, 1.0, 0.01))
239 
240  self.scene.add_box("wall1", self.box_pose(0.8,0.5,0.75), size=(0.5, 0.01, 1.5))
241  self.scene.add_box("wall2", self.box_pose(0.8,-0.5,0.75), size=(0.5, 0.01, 1.5))
242 
243  self.scene.add_box("box1", self.box1, size=(0.05, 0.1, 0.1))
244  self.scene.add_box("box2", self.box2, size=(0.05, 0.05, 0.1))
245  self.scene.add_box("box3", self.box3, size=(0.05, 0.05, 0.1))
246 
247  return 'succeeded'
248 
249  def remove_objects(self):
250  self.scene.remove_world_object()
251  return 'succeeded'
252 
253  def attach_objects(self,object_name):
254  self.group.set_end_effector_link("r_eef_pick_link")
255  eef_link = self.group.get_end_effector_link()
256  grasping_group = 'rhand'
257  touch_links = self.robot.get_link_names(group=grasping_group)
258  self.scene.attach_box(eef_link, object_name, touch_links=touch_links)
259 
260  return self.wait_for_state_update(object_name,box_is_attached=True, box_is_known=False, timeout=4)
261 
262  def detach_objects(self, object_name):
263  self.group.set_end_effector_link("r_eef_pick_link")
264  eef_link = self.group.get_end_effector_link()
265 
266  self.scene.remove_attached_object(eef_link, name=object_name)
267 
268  return self.wait_for_state_update(object_name,box_is_known=True, box_is_attached=False, timeout=4)
269 
270 #---------------------------------
271 class MANIPULATE(State):
272  def __init__(self,x,y,z,vel=1.0,direction="side"):
273  State.__init__(self, outcomes=['succeeded','aborted'])
274  self.x = x
275  self.y = y
276  self.z = z
277  self.vel = vel
278  self.direction = direction
279 
280  def execute(self, userdata):
281  rospy.loginfo('Manipulate at ({},{},{}) in scale velocity {}'.format(self.x,self.y,self.z,self.vel))
282  if(mc.set_grasp_position(self.x,self.y,self.z,self.vel,self.direction)
283  == 'succeeded'):return 'succeeded'
284  else: return 'aborted'
285 
286 #---------------------------------
287 class MOVE_LIFTER(State):
288  def __init__(self,x,z,vel=1.0):
289  State.__init__(self, outcomes=['succeeded','aborted'])
290  self.x = x
291  self.z = z
292  self.vel = vel
293 
294  def execute(self, userdata):
295  rospy.loginfo('Move Lifter at ({},{}) in scale velocity {}'.format(self.x,self.z,self.vel))
296  if(mc.set_lifter_position(self.x,self.z,self.vel) == 'succeeded'):return 'succeeded'
297  else: return 'aborted'
298 
299 #---------------------------------
300 class INIT_POSE(State):
301  def __init__(self):
302  State.__init__(self, outcomes=['succeeded','aborted'])
303 
304  def execute(self, userdata):
305  rospy.loginfo('initialize wholebody')
306 
307  if(mc.set_initial_pose() == 'succeeded'):return 'succeeded'
308  else: return 'aborted'
309 
310 class UPDATE_OBJECTS(State):
311  def __init__(self,action):
312  State.__init__(self, outcomes=['succeeded','aborted'])
313  self.action = action
314 
315  def execute(self, userdata):
316  if(self.action == 'add'):
317  print('add objects')
318  if(mc.add_objects() == 'succeeded'):return 'succeeded'
319  else: return 'aborted'
320  elif(self.action == 'remove'):
321  print('remove objects')
322  if(mc.remove_objects() == 'succeeded'):return 'succeeded'
323  else: return 'aborted'
324 
325 class PICK(State):
326  def __init__(self,object_name):
327  State.__init__(self, outcomes=['succeeded','aborted'])
328  self.object_name = object_name
329 
330  def execute(self, userdata):
331  if(mc.attach_objects(self.object_name) == 'succeeded'):
332  if(hc.grasp()): return 'succeeded'
333  else: return 'aborted'
334  else: return 'aborted'
335 
336 class PLACE(State):
337  def __init__(self,object_name):
338  State.__init__(self, outcomes=['succeeded','aborted'])
339  self.object_name = object_name
340 
341  def execute(self, userdata):
342  if(mc.detach_objects(self.object_name) == 'succeeded'):
343  if(hc.release()): return 'succeeded'
344  else: return 'aborted'
345  else: return 'aborted'
346 
347 #==================================
348 #==================================
349 if __name__ == '__main__':
350  rospy.init_node('scenario_node')
351 
352  na = NaviAction()
355 
356  go_to_shelf = StateMachine(outcomes=['succeeded','aborted'])
357  with go_to_shelf:
358  StateMachine.add('DOWN LIFTER', MOVE_LIFTER(0,0.6),\
359  transitions={'succeeded':'MOVE','aborted':'aborted'})
360  StateMachine.add('MOVE', GO_TO_PLACE(1),\
361  transitions={'succeeded':'succeeded','aborted':'aborted'})
362 
363  go_to_start_point = StateMachine(outcomes=['succeeded','aborted'])
364  with go_to_start_point:
365  StateMachine.add('DOWN LIFTER', MOVE_LIFTER(0,0.6),\
366  transitions={'succeeded':'MOVE','aborted':'aborted'})
367  StateMachine.add('MOVE', GO_TO_PLACE(0),\
368  transitions={'succeeded':'succeeded','aborted':'aborted'})
369 
370  pick_place_1 = StateMachine(outcomes=['succeeded','aborted'])
371  x = mc.box1.pose.position.x
372  y = mc.box1.pose.position.y
373  z = mc.box1.pose.position.z
374  with pick_place_1:
375  StateMachine.add('PICK MOTION', MANIPULATE(x, y, z, direction="top"), \
376  transitions={'succeeded':'PICK','aborted':'aborted'})
377  StateMachine.add('PICK', PICK('box1'),\
378  transitions={'succeeded':'PLACE MOTION','aborted':'aborted'})
379  StateMachine.add('PLACE MOTION', MANIPULATE(0.6, -0.4, z + 0.4, direction="top"), \
380  transitions={'succeeded':'PLACE','aborted':'aborted'})
381  StateMachine.add('PLACE', PLACE('box1'),\
382  transitions={'succeeded':'succeeded','aborted':'aborted'})
383 
384  pick_place_2 = StateMachine(outcomes=['succeeded','aborted'])
385  x = mc.box2.pose.position.x
386  y = mc.box2.pose.position.y
387  z = mc.box2.pose.position.z
388  with pick_place_2:
389  StateMachine.add('PICK MOTION', MANIPULATE(x, y, z), \
390  transitions={'succeeded':'PICK','aborted':'aborted'})
391  StateMachine.add('PICK', PICK('box2'),\
392  transitions={'succeeded':'PLACE MOTION','aborted':'aborted'})
393  StateMachine.add('PLACE MOTION', MANIPULATE(0.6, -0.2, z), \
394  transitions={'succeeded':'PLACE','aborted':'aborted'})
395  StateMachine.add('PLACE', PLACE('box2'),\
396  transitions={'succeeded':'succeeded','aborted':'aborted'})
397 
398  pick_place_3 = StateMachine(outcomes=['succeeded','aborted'])
399  x = mc.box3.pose.position.x
400  y = mc.box3.pose.position.y
401  z = mc.box3.pose.position.z
402  with pick_place_3:
403  StateMachine.add('PICK MOTION', MANIPULATE(x, y, z), \
404  transitions={'succeeded':'PICK','aborted':'aborted'})
405  StateMachine.add('PICK', PICK('box3'),\
406  transitions={'succeeded':'PLACE MOTION','aborted':'aborted'})
407  StateMachine.add('PLACE MOTION', MANIPULATE(0.6, 0.0, z - 0.4), \
408  transitions={'succeeded':'PLACE','aborted':'aborted'})
409  StateMachine.add('PLACE', PLACE('box3'),\
410  transitions={'succeeded':'succeeded','aborted':'aborted'})
411 
412  scenario_play = StateMachine(outcomes=['succeeded','aborted'])
413  with scenario_play:
414  StateMachine.add('GO TO SHELF', go_to_shelf,\
415  transitions={'succeeded':'ADD OBJECTS','aborted':'aborted'})
416  StateMachine.add('ADD OBJECTS', UPDATE_OBJECTS('add'),\
417  transitions={'succeeded':'PICK and PLACE 1','aborted':'aborted'})
418  StateMachine.add('PICK and PLACE 1', pick_place_1,\
419  transitions={'succeeded':'PICK and PLACE 2','aborted':'aborted'})
420  StateMachine.add('PICK and PLACE 2', pick_place_2,\
421  transitions={'succeeded':'PICK and PLACE 3','aborted':'aborted'})
422  StateMachine.add('PICK and PLACE 3', pick_place_3,\
423  transitions={'succeeded':'INITIALIZE','aborted':'aborted'})
424  StateMachine.add('INITIALIZE', INIT_POSE(),\
425  transitions={'succeeded':'REMOVE OBJECTS','aborted':'aborted'})
426  StateMachine.add('REMOVE OBJECTS', UPDATE_OBJECTS('remove'),\
427  transitions={'succeeded':'GO TO START POINT','aborted':'aborted'})
428  StateMachine.add('GO TO START POINT', go_to_start_point,\
429  transitions={'succeeded':'GO TO SHELF','aborted':'aborted'})
430 
431  sis = smach_ros.IntrospectionServer('server_name',scenario_play,'/SEED-Noid-Mover Scenario Play')
432  sis.start()
433  scenario_play.execute()
434  sis.stop()
435 
def set_grasp_position(self, x, y, z, vel=1.0, direction="side")
Definition: demo.py:120
def __init__(self, _place)
Definition: demo.py:72
def execute(self, userdata)
Definition: demo.py:280
def execute(self, userdata)
Definition: demo.py:76
def execute(self, userdata)
Definition: demo.py:330
def execute(self, userdata)
Definition: demo.py:304
def set_lifter_position(self, x, z, vel=1.0)
Definition: demo.py:157
– for hand control
Definition: demo.py:27
def detach_objects(self, object_name)
Definition: demo.py:262
def __init__(self, object_name)
Definition: demo.py:326
def box_pose(self, x, y, z)
Definition: demo.py:227
def __init__(self, object_name)
Definition: demo.py:337
def __init__(self)
Definition: demo.py:28
def execute(self, userdata)
Definition: demo.py:341
def shutdown(self)
Definition: demo.py:67
def __init__(self, x, z, vel=1.0)
Definition: demo.py:288
def __init__(self)
Definition: demo.py:301
def __init__(self, action)
Definition: demo.py:311
def attach_objects(self, object_name)
Definition: demo.py:253
def set_initial_pose(self)
Definition: demo.py:192
def add_objects(self)
Definition: demo.py:235
def set_goal(self, _number)
Definition: demo.py:41
def execute(self, userdata)
Definition: demo.py:315
def execute(self, userdata)
Definition: demo.py:294
def __init__(self, x, y, z, vel=1.0, direction="side")
Definition: demo.py:272
def remove_objects(self)
Definition: demo.py:249
def wait_for_state_update(self, box_name, box_is_known=False, box_is_attached=False, timeout=4)
Definition: demo.py:208


seed_r7_samples
Author(s):
autogenerated on Sun Apr 18 2021 02:41:07