SetFocusPoint.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 '''
00004 Copyright (c) 2016, Aumann Florian, Borella Jocelyn, Heller Florian, Meissner Pascal, Schleicher Ralf, Stoeckle Patrick, Stroh Daniel, Trautmann Jeremias, Walter Milena, Wittenbeck Valerij
00005 All rights reserved.
00006 
00007 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
00008 
00009 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
00010 
00011 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.
00012 
00013 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.
00014 
00015 4. The use is explicitly not permitted to any application which deliberately try to kill or do harm to any living creature.
00016 
00017 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.
00018 '''
00019 
00020 import rospy
00021 from geometry_msgs.msg import Point, PointStamped, Quaternion
00022 from actionlib import *
00023 from actionlib.msg import *
00024 import numpy
00025 from time import time
00026 from asr_flir_ptu_controller.msg import PTUMovementGoal, PTUMovementAction
00027 from asr_robot_model_services.srv import GetPose, CalculateCameraPoseCorrection, CalculateCameraPose
00028 from asr_next_best_view.srv import TriggerFrustumVisualization
00029 from asr_robot_model_services.msg import RobotStateMessage
00030 from sensor_msgs.msg import JointState
00031 import tf
00032 import tf2_ros
00033 
00034 ptu = None
00035 
00036 def get_robot_pose_cpp():
00037     rospy.wait_for_service('/asr_robot_model_services/GetRobotPose', timeout=5)
00038     pose = rospy.ServiceProxy('/asr_robot_model_services/GetRobotPose',GetPose)
00039     return pose().pose
00040 
00041 def get_camera_pose_cpp():
00042     rospy.wait_for_service('/asr_robot_model_services/GetCameraPose', timeout=5)
00043     pose = rospy.ServiceProxy('/asr_robot_model_services/GetCameraPose',GetPose)
00044     return pose().pose
00045 
00046 def get_camera_frustum(camera_pose):
00047     try:
00048         rospy.wait_for_service('/nbv/trigger_frustum_visualization', timeout=5)
00049         get_frustum = rospy.ServiceProxy(
00050             '/nbv/trigger_frustum_visualization', TriggerFrustumVisualization)
00051         get_frustum(camera_pose)
00052     except (rospy.ServiceException, rospy.exceptions.ROSException), e:
00053         rospy.logwarn(str(e))
00054 
00055 def ptu_callback(data):
00056     global ptu
00057     ptu = data.position
00058 
00059 def get_robot_state():
00060     global ptu
00061 
00062     sub_ptu = rospy.Subscriber('/asr_flir_ptu_driver/state', JointState, ptu_callback)
00063 
00064     future = time() + 2
00065     while not ptu and time() < future:
00066         pass
00067 
00068     rospy.sleep(2)
00069     if not ptu:
00070         ptu = [0,0]
00071 
00072     pose = get_robot_pose_cpp()
00073 
00074     robot_state = RobotStateMessage()
00075     robot_state.pan = ptu[0]
00076     robot_state.tilt = ptu[1]
00077     robot_state.x = pose.position.x
00078     robot_state.y = pose.position.y
00079     robot_state.rotation = get_rotation_from_pose(pose)
00080     return robot_state
00081 
00082 def get_rotation_from_pose(pose):
00083     """
00084     Returns the rotation in degrees from pose
00085     """
00086     pose.position.x = pose.position.x
00087     pose.position.y = pose.position.y
00088     pose.position.z = 0
00089     q = numpy.array([
00090         pose.orientation.x,
00091         pose.orientation.y,
00092         pose.orientation.z,
00093         pose.orientation.w])
00094     (_, _, yaw) = tf.transformations.euler_from_quaternion(q)
00095     return yaw
00096 
00097 def point_published(data):
00098     rospy.loginfo(rospy.get_caller_id() + "Set focus point to (" + str(data.point.x) + ", " + str(data.point.y) + ", "+ str(data.point.z) + ")")
00099 
00100     fcp = rospy.get_param("/asr_robot_model_services/fcp")
00101     ncp = rospy.get_param("/asr_robot_model_services/ncp")
00102 
00103     targetPosition = Point()
00104     targetOrientation = Quaternion()
00105     targetPosition.x = data.point.x - (fcp + ncp) / 2.0
00106     targetPosition.y = data.point.y
00107     targetPosition.z = data.point.z
00108     targetOrientation.w = 1.0
00109     targetOrientation.x = 0.0
00110     targetOrientation.y = 0.0
00111     targetOrientation.z = 0.0
00112 
00113     try:
00114         rospy.wait_for_service('/asr_robot_model_services/CalculateCameraPoseCorrection', timeout=5)
00115         calculateCameraPoseCorrection = rospy.ServiceProxy(
00116             '/asr_robot_model_services/CalculateCameraPoseCorrection',
00117             CalculateCameraPoseCorrection)
00118         actual_state = get_robot_state()
00119 
00120         rospy.loginfo('Current robot state is ' + str(actual_state))
00121 
00122         actual_pan = actual_state.pan * numpy.pi/180
00123         actual_tilt = actual_state.tilt * numpy.pi/180
00124         rospy.loginfo('Pan and tilt in rad: ' + str(actual_pan) + ", " + str(actual_tilt))
00125 
00126         ptuConfig = calculateCameraPoseCorrection(actual_state, targetOrientation, targetPosition)
00127     except (rospy.ServiceException, rospy.exceptions.ROSException), e:
00128         rospy.logwarn(str(e))
00129         return 'aborted'
00130 
00131     rospy.loginfo('Moving PTU to corrected goal (' + str(ptuConfig.pan) + ', ' + str(ptuConfig.tilt) + ')')
00132 
00133     client = actionlib.SimpleActionClient('ptu_controller_actionlib',
00134                                           PTUMovementAction)
00135     if not client.wait_for_server(rospy.Duration.from_sec(10)):
00136         rospy.logwarn("Could not connect to ptu action server")
00137         return 'aborted'
00138 
00139     ptu_goal = PTUMovementGoal()
00140     ptu_goal.target_joint.header.seq = 0
00141     ptu_goal.target_joint.name = ['pan', 'tilt']
00142     ptu_goal.target_joint.velocity = [0, 0]
00143     ptu_goal.target_joint.position = [ptuConfig.pan*180/numpy.pi, ptuConfig.tilt*180/numpy.pi]
00144 
00145     rospy.loginfo("Moving PTU to goal (" + str(ptuConfig.pan) + ", " + str(ptuConfig.tilt) + ')')
00146 
00147     ptu_result = client.send_goal_and_wait(ptu_goal)
00148     rospy.loginfo("PTU action returned (3 being 'succeeded'): " + str(ptu_result))
00149 
00150     future = time() + 1
00151     while time() < future:
00152         pass
00153 
00154     #Visualize new frustum
00155     camera_pose = get_camera_pose_cpp()
00156     get_camera_frustum(camera_pose)
00157 
00158 
00159     
00160 if __name__ == '__main__':
00161     rospy.init_node('FPListener', anonymous=True)
00162 
00163     rospy.Subscriber("clicked_point", PointStamped, point_published)
00164 
00165     rospy.spin()


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 Sat Jun 8 2019 18:24:52