SetFocusPoint.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 Copyright (c) 2016, Aumann Florian, Borella Jocelyn, Heller Florian, Meissner Pascal, Schleicher Ralf, Stoeckle Patrick, Stroh Daniel, Trautmann Jeremias, Walter Milena, Wittenbeck Valerij
5 All rights reserved.
6 
7 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
8 
9 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
10 
11 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
12 
13 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.
14 
15 4. The use is explicitly not permitted to any application which deliberately try to kill or do harm to any living creature.
16 
17 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
18 '''
19 
20 import rospy
21 from geometry_msgs.msg import Point, PointStamped, Quaternion
22 from actionlib import *
23 from actionlib.msg import *
24 import numpy
25 from time import time
26 from asr_flir_ptu_controller.msg import PTUMovementGoal, PTUMovementAction
27 from asr_robot_model_services.srv import GetPose, CalculateCameraPoseCorrection, CalculateCameraPose
28 from asr_next_best_view.srv import TriggerFrustumVisualization
29 from asr_robot_model_services.msg import RobotStateMessage
30 from sensor_msgs.msg import JointState
31 import tf
32 import tf2_ros
33 
34 ptu = None
35 
37  rospy.wait_for_service('/asr_robot_model_services/GetRobotPose', timeout=5)
38  pose = rospy.ServiceProxy('/asr_robot_model_services/GetRobotPose',GetPose)
39  return pose().pose
40 
42  rospy.wait_for_service('/asr_robot_model_services/GetCameraPose', timeout=5)
43  pose = rospy.ServiceProxy('/asr_robot_model_services/GetCameraPose',GetPose)
44  return pose().pose
45 
46 def get_camera_frustum(camera_pose):
47  try:
48  rospy.wait_for_service('/nbv/trigger_frustum_visualization', timeout=5)
49  get_frustum = rospy.ServiceProxy(
50  '/nbv/trigger_frustum_visualization', TriggerFrustumVisualization)
51  get_frustum(camera_pose)
52  except (rospy.ServiceException, rospy.exceptions.ROSException), e:
53  rospy.logwarn(str(e))
54 
55 def ptu_callback(data):
56  global ptu
57  ptu = data.position
58 
60  global ptu
61 
62  sub_ptu = rospy.Subscriber('/asr_flir_ptu_driver/state', JointState, ptu_callback)
63 
64  future = time() + 2
65  while not ptu and time() < future:
66  pass
67 
68  rospy.sleep(2)
69  if not ptu:
70  ptu = [0,0]
71 
72  pose = get_robot_pose_cpp()
73 
74  robot_state = RobotStateMessage()
75  robot_state.pan = ptu[0]
76  robot_state.tilt = ptu[1]
77  robot_state.x = pose.position.x
78  robot_state.y = pose.position.y
79  robot_state.rotation = get_rotation_from_pose(pose)
80  return robot_state
81 
83  """
84  Returns the rotation in degrees from pose
85  """
86  pose.position.x = pose.position.x
87  pose.position.y = pose.position.y
88  pose.position.z = 0
89  q = numpy.array([
90  pose.orientation.x,
91  pose.orientation.y,
92  pose.orientation.z,
93  pose.orientation.w])
94  (_, _, yaw) = tf.transformations.euler_from_quaternion(q)
95  return yaw
96 
97 def point_published(data):
98  rospy.loginfo(rospy.get_caller_id() + "Set focus point to (" + str(data.point.x) + ", " + str(data.point.y) + ", "+ str(data.point.z) + ")")
99 
100  fcp = rospy.get_param("/asr_robot_model_services/fcp")
101  ncp = rospy.get_param("/asr_robot_model_services/ncp")
102 
103  targetPosition = Point()
104  targetOrientation = Quaternion()
105  targetPosition.x = data.point.x - (fcp + ncp) / 2.0
106  targetPosition.y = data.point.y
107  targetPosition.z = data.point.z
108  targetOrientation.w = 1.0
109  targetOrientation.x = 0.0
110  targetOrientation.y = 0.0
111  targetOrientation.z = 0.0
112 
113  try:
114  rospy.wait_for_service('/asr_robot_model_services/CalculateCameraPoseCorrection', timeout=5)
115  calculateCameraPoseCorrection = rospy.ServiceProxy(
116  '/asr_robot_model_services/CalculateCameraPoseCorrection',
117  CalculateCameraPoseCorrection)
118  actual_state = get_robot_state()
119 
120  rospy.loginfo('Current robot state is ' + str(actual_state))
121 
122  actual_pan = actual_state.pan * numpy.pi/180
123  actual_tilt = actual_state.tilt * numpy.pi/180
124  rospy.loginfo('Pan and tilt in rad: ' + str(actual_pan) + ", " + str(actual_tilt))
125 
126  ptuConfig = calculateCameraPoseCorrection(actual_state, targetOrientation, targetPosition)
127  except (rospy.ServiceException, rospy.exceptions.ROSException), e:
128  rospy.logwarn(str(e))
129  return 'aborted'
130 
131  rospy.loginfo('Moving PTU to corrected goal (' + str(ptuConfig.pan) + ', ' + str(ptuConfig.tilt) + ')')
132 
133  client = actionlib.SimpleActionClient('ptu_controller_actionlib',
134  PTUMovementAction)
135  if not client.wait_for_server(rospy.Duration.from_sec(10)):
136  rospy.logwarn("Could not connect to ptu action server")
137  return 'aborted'
138 
139  ptu_goal = PTUMovementGoal()
140  ptu_goal.target_joint.header.seq = 0
141  ptu_goal.target_joint.name = ['pan', 'tilt']
142  ptu_goal.target_joint.velocity = [0, 0]
143  ptu_goal.target_joint.position = [ptuConfig.pan*180/numpy.pi, ptuConfig.tilt*180/numpy.pi]
144 
145  rospy.loginfo("Moving PTU to goal (" + str(ptuConfig.pan) + ", " + str(ptuConfig.tilt) + ')')
146 
147  ptu_result = client.send_goal_and_wait(ptu_goal)
148  rospy.loginfo("PTU action returned (3 being 'succeeded'): " + str(ptu_result))
149 
150  future = time() + 1
151  while time() < future:
152  pass
153 
154  #Visualize new frustum
155  camera_pose = get_camera_pose_cpp()
156  get_camera_frustum(camera_pose)
157 
158 
159 
160 if __name__ == '__main__':
161  rospy.init_node('FPListener', anonymous=True)
162 
163  rospy.Subscriber("clicked_point", PointStamped, point_published)
164 
165  rospy.spin()
def get_robot_pose_cpp()
def get_robot_state()
def get_rotation_from_pose(pose)
def get_camera_pose_cpp()
def get_camera_frustum(camera_pose)
def ptu_callback(data)
def point_published(data)


asr_robot_model_services
Author(s): Aumann Florian, Borella Jocelyn, Heller Florian, Meißner Pascal, Schleicher Ralf, Stöckle Patrick, Stroh Daniel, Trautmann Jeremias, Walter Milena, Wittenbeck Valerij
autogenerated on Mon Jun 10 2019 12:49:59