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
13 q = quaternion_from_euler(role, pitch, yaw)
14 return Quaternion(q[0], q[1], q[2], q[3])
17 rospy.init_node(
"obstacle_client")
19 SERVICE_NAME =
'obstacle_avoidance_example/obstacle_avoidance' 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')
29 handler = rospy.ServiceProxy(SERVICE_NAME, ObstacleAvoidance)
30 request = ObstacleAvoidanceRequest()
34 start_pose.position.x = 0.35
35 start_pose.position.y = -0.2
36 start_pose.position.z = 0.1
39 goal_pose = copy.deepcopy(start_pose)
40 goal_pose.position.y = 0.2
43 request.start_pose = start_pose
44 request.goal_pose = goal_pose
45 request.obstacle_enable =
False 47 result = handler(request)
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
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
64 result = handler(request)
69 obstacle_pose_stamped.pose.position.z = obstacle_size.x/2.0
72 request.obstacle_pose_stamped = obstacle_pose_stamped
74 result = handler(request)
78 if __name__ ==
'__main__':
80 if not rospy.is_shutdown():
82 except rospy.ROSInterruptException:
def euler_to_quaternion(role, pitch, yaw)