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