obstacle_client.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 import rospy
5 import copy
6 import math
7 from geometry_msgs.msg import Quaternion, Pose, PoseStamped, Vector3
8 from tf.transformations import quaternion_from_euler
9 from crane_x7_examples.srv import ObstacleAvoidance, ObstacleAvoidanceRequest
10 
11 
12 def euler_to_quaternion(role, pitch, yaw):
13  q = quaternion_from_euler(role, pitch, yaw)
14  return Quaternion(q[0], q[1], q[2], q[3])
15 
16 def main():
17  rospy.init_node("obstacle_client")
18 
19  SERVICE_NAME = 'obstacle_avoidance_example/obstacle_avoidance'
20 
21  # サービスの起動を待つ
22  try:
23  rospy.wait_for_service(SERVICE_NAME, 10.0)
24  except (rospy.ServiceException, rospy.ROSException) as e:
25  rospy.logwarn('Service call failed: %s'%e)
26  rospy.signal_shutdown('SERVICE CALL FAILED')
27  return
28 
29  handler = rospy.ServiceProxy(SERVICE_NAME, ObstacleAvoidance)
30  request = ObstacleAvoidanceRequest()
31 
32  # 目標姿勢を設定
33  start_pose = Pose()
34  start_pose.position.x = 0.35
35  start_pose.position.y = -0.2
36  start_pose.position.z = 0.1
37  start_pose.orientation = euler_to_quaternion(0.0, math.pi/2.0, 0.0)
38 
39  goal_pose = copy.deepcopy(start_pose)
40  goal_pose.position.y = 0.2
41 
42  # 障害物無しでアームを動かす
43  request.start_pose = start_pose
44  request.goal_pose = goal_pose
45  request.obstacle_enable = False
46  print('Request ...')
47  result = handler(request)
48  print(result)
49 
50  # 障害物を設定
51  obstacle_name = "box"
52  obstacle_size = Vector3(0.28, 0.16, 0.14)
53  obstacle_pose_stamped = PoseStamped()
54  obstacle_pose_stamped.header.frame_id = "/base_link"
55  obstacle_pose_stamped.pose.position.x = 0.35
56  obstacle_pose_stamped.pose.position.z = obstacle_size.z/2.0
57 
58  # 障害物有りでアームを動かす
59  request.obstacle_enable = True
60  request.obstacle_size = obstacle_size
61  request.obstacle_pose_stamped = obstacle_pose_stamped
62  request.obstacle_name = obstacle_name
63  print('Request ...')
64  result = handler(request)
65  print(result)
66 
67  # 障害物の姿勢を変更
68  obstacle_pose_stamped.pose.orientation = euler_to_quaternion(0.0, math.pi/2.0, math.pi/2.0)
69  obstacle_pose_stamped.pose.position.z = obstacle_size.x/2.0
70 
71  # 障害物有りでアームを動かす
72  request.obstacle_pose_stamped = obstacle_pose_stamped
73  print('Request ...')
74  result = handler(request)
75  print(result)
76 
77 
78 if __name__ == '__main__':
79  try:
80  if not rospy.is_shutdown():
81  main()
82  except rospy.ROSInterruptException:
83  pass
def euler_to_quaternion(role, pitch, yaw)


crane_x7_examples
Author(s): Daisuke Sato , Hiroyuki Nomura
autogenerated on Mon Mar 1 2021 03:18:34