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
27 q = quaternion_from_euler(role, pitch, yaw)
28 return Quaternion(q[0], q[1], q[2], q[3])
31 rospy.init_node(
"obstacle_client")
33 SERVICE_NAME =
'obstacle_avoidance_example/obstacle_avoidance'
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')
43 handler = rospy.ServiceProxy(SERVICE_NAME, ObstacleAvoidance)
44 request = ObstacleAvoidanceRequest()
48 start_pose.position.x = 0.35
49 start_pose.position.y = -0.2
50 start_pose.position.z = 0.1
53 goal_pose = copy.deepcopy(start_pose)
54 goal_pose.position.y = 0.2
57 request.start_pose = start_pose
58 request.goal_pose = goal_pose
59 request.obstacle_enable =
False
61 result = handler(request)
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
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
78 result = handler(request)
83 obstacle_pose_stamped.pose.position.z = obstacle_size.x/2.0
86 request.obstacle_pose_stamped = obstacle_pose_stamped
88 result = handler(request)
92 if __name__ ==
'__main__':
94 if not rospy.is_shutdown():
96 except rospy.ROSInterruptException: