obstacle_client.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 # Copyright 2019 RT Corporation
5 #
6 # Licensed under the Apache License, Version 2.0 (the "License");
7 # you may not use this file except in compliance with the License.
8 # You may obtain a copy of the License at
9 #
10 # http://www.apache.org/licenses/LICENSE-2.0
11 #
12 # Unless required by applicable law or agreed to in writing, software
13 # distributed under the License is distributed on an "AS IS" BASIS,
14 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 # See the License for the specific language governing permissions and
16 # limitations under the License.
17 
18 import rospy
19 import copy
20 import math
21 from geometry_msgs.msg import Quaternion, Pose, PoseStamped, Vector3
22 from tf.transformations import quaternion_from_euler
23 from crane_x7_examples.srv import ObstacleAvoidance, ObstacleAvoidanceRequest
24 
25 
26 def euler_to_quaternion(role, pitch, yaw):
27  q = quaternion_from_euler(role, pitch, yaw)
28  return Quaternion(q[0], q[1], q[2], q[3])
29 
30 def main():
31  rospy.init_node("obstacle_client")
32 
33  SERVICE_NAME = 'obstacle_avoidance_example/obstacle_avoidance'
34 
35  # サービスの起動を待つ
36  try:
37  rospy.wait_for_service(SERVICE_NAME, 10.0)
38  except (rospy.ServiceException, rospy.ROSException) as e:
39  rospy.logwarn('Service call failed: %s'%e)
40  rospy.signal_shutdown('SERVICE CALL FAILED')
41  return
42 
43  handler = rospy.ServiceProxy(SERVICE_NAME, ObstacleAvoidance)
44  request = ObstacleAvoidanceRequest()
45 
46  # 目標姿勢を設定
47  start_pose = Pose()
48  start_pose.position.x = 0.35
49  start_pose.position.y = -0.2
50  start_pose.position.z = 0.1
51  start_pose.orientation = euler_to_quaternion(0.0, math.pi/2.0, 0.0)
52 
53  goal_pose = copy.deepcopy(start_pose)
54  goal_pose.position.y = 0.2
55 
56  # 障害物無しでアームを動かす
57  request.start_pose = start_pose
58  request.goal_pose = goal_pose
59  request.obstacle_enable = False
60  print('Request ...')
61  result = handler(request)
62  print(result)
63 
64  # 障害物を設定
65  obstacle_name = "box"
66  obstacle_size = Vector3(0.28, 0.16, 0.14)
67  obstacle_pose_stamped = PoseStamped()
68  obstacle_pose_stamped.header.frame_id = "/base_link"
69  obstacle_pose_stamped.pose.position.x = 0.35
70  obstacle_pose_stamped.pose.position.z = obstacle_size.z/2.0
71 
72  # 障害物有りでアームを動かす
73  request.obstacle_enable = True
74  request.obstacle_size = obstacle_size
75  request.obstacle_pose_stamped = obstacle_pose_stamped
76  request.obstacle_name = obstacle_name
77  print('Request ...')
78  result = handler(request)
79  print(result)
80 
81  # 障害物の姿勢を変更
82  obstacle_pose_stamped.pose.orientation = euler_to_quaternion(0.0, math.pi/2.0, math.pi/2.0)
83  obstacle_pose_stamped.pose.position.z = obstacle_size.x/2.0
84 
85  # 障害物有りでアームを動かす
86  request.obstacle_pose_stamped = obstacle_pose_stamped
87  print('Request ...')
88  result = handler(request)
89  print(result)
90 
91 
92 if __name__ == '__main__':
93  try:
94  if not rospy.is_shutdown():
95  main()
96  except rospy.ROSInterruptException:
97  pass
obstacle_client.main
def main()
Definition: obstacle_client.py:30
obstacle_client.euler_to_quaternion
def euler_to_quaternion(role, pitch, yaw)
Definition: obstacle_client.py:26


crane_x7_examples
Author(s): Daisuke Sato , Hiroyuki Nomura
autogenerated on Mon Oct 2 2023 02:39:27