4 Copyright (c) 2016, Allgeyer Tobias, Aumann Florian, Borella Jocelyn, Hutmacher Robin, Karrenbauer Oliver, Marek Felix, Meissner Pascal, Trautmann Jeremias, Wittenbeck Valerij 8 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 10 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 12 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. 14 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. 16 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. 28 from asr_flir_ptu_controller.msg
import PTUMovementGoal, PTUMovementAction
29 from move_base_msgs.msg
import MoveBaseAction, MoveBaseGoal
30 from geometry_msgs.msg
import (Pose, PoseWithCovariance, PoseWithCovarianceStamped)
31 from asr_robot_model_services.srv
import CalculateCameraPoseCorrection
32 from nav_msgs.msg
import Odometry
33 from actionlib
import *
35 from common.evaluation_decorators
import *
36 from visualization_msgs.msg
import Marker
37 from std_msgs.msg
import ColorRGBA
38 import state_acquisition
42 Defines states that are relevant for moving the robot, i.e. moving the base, 43 moving the ptu and getting the current positition. 52 Move the roboter base to given position. 58 outcomes=[
'succeeded',
'aborted'],
59 input_keys=[
'goal_robot_pose'])
64 rospy.loginfo(
'Executing MOVE_BASE')
67 next_goal = MoveBaseGoal()
68 next_goal.target_pose.header.frame_id =
"/map" 69 p =
Pose(userdata.goal_robot_pose.position,
70 userdata.goal_robot_pose.orientation)
71 next_goal.target_pose.pose = p
74 if not client.wait_for_server(rospy.Duration.from_sec(10)):
75 rospy.logwarn(
"Can't contact move_base action server")
78 rospy.loginfo(
'Sending goal to move_base action server.')
79 move_result = client.send_goal_and_wait(next_goal)
81 rospy.loginfo(
"Move_base action returned (3 being 'succeeded'): " + str(move_result))
83 elapsed_time = end - start
85 move_base_time += elapsed_time
87 target_pose = next_goal.target_pose.pose
88 rospy.loginfo(
"This has been the target robot pose, coming from NBV: " + str(target_pose))
89 actual_pose = state_acquisition.get_robot_pose_cpp()
90 rospy.loginfo(
"This is the actual robot pose after navigation: " + str(actual_pose))
91 rospy.loginfo(
"This is the absolut difference: position:" 92 +
"\n x: " + str(abs(target_pose.position.x - actual_pose.position.x))
93 +
"\n y: " + str(abs(target_pose.position.y - actual_pose.position.y))
94 +
"\n z: " + str(abs(target_pose.position.z - actual_pose.position.z))
96 +
"\n x: " + str(abs(target_pose.orientation.x - actual_pose.orientation.x))
97 +
"\n y: " + str(abs(target_pose.orientation.y - actual_pose.orientation.y))
98 +
"\n z: " + str(abs(target_pose.orientation.z - actual_pose.orientation.z))
99 +
"\n w: " + str(abs(target_pose.orientation.w - actual_pose.orientation.w)))
101 rospy.loginfo(
"Move Base took : " + str(elapsed_time) +
" seconds (Total time in move_base: " + str(move_base_time) +
")")
111 Sets robot to goal pose via '/initialpose' topic, bypassing actual ros navigation. 116 smach.State.__init__(
118 outcomes=[
'succeeded'],
119 input_keys=[
'goal_robot_pose'])
120 self.
pub = rospy.Publisher(
'/initialpose', PoseWithCovarianceStamped, queue_size=10)
125 rospy.loginfo(
'Executing FAKE_MOVE_BASE')
128 next_goal = PoseWithCovarianceStamped()
129 next_goal.header.frame_id =
"/map" 130 p =
Pose(userdata.goal_robot_pose.position,
131 userdata.goal_robot_pose.orientation)
132 next_goal.pose.pose = p
134 rospy.loginfo(
'Publish goal to /initialpose.')
135 self.
pub.publish(next_goal)
138 elapsed_time = end - start
139 global move_base_time
140 move_base_time += elapsed_time
142 target_pose = next_goal.pose.pose
143 rospy.loginfo(
"This has been the target robot pose: " + str(target_pose))
144 actual_pose = state_acquisition.get_robot_pose_cpp()
145 rospy.loginfo(
"This is the actual robot pose after navigation: " + str(actual_pose))
146 rospy.loginfo(
"This is the absolut difference: position:" 147 +
"\n x: " + str(abs(target_pose.position.x - actual_pose.position.x))
148 +
"\n y: " + str(abs(target_pose.position.y - actual_pose.position.y))
149 +
"\n z: " + str(abs(target_pose.position.z - actual_pose.position.z))
151 +
"\n x: " + str(abs(target_pose.orientation.x - actual_pose.orientation.x))
152 +
"\n y: " + str(abs(target_pose.orientation.y - actual_pose.orientation.y))
153 +
"\n z: " + str(abs(target_pose.orientation.z - actual_pose.orientation.z))
154 +
"\n w: " + str(abs(target_pose.orientation.w - actual_pose.orientation.w)))
156 rospy.loginfo(
"Move Base took : " + str(elapsed_time) +
" seconds (Total time in move_base: " + str(move_base_time) +
")")
162 Moves the PTU to a given pose. A pose should consist of a pan and tilt value. 166 smach.State.__init__(
168 outcomes=[
'succeeded',
'aborted'],
169 input_keys=[
'goal_ptu_position'])
172 """Callback for ptu movements""" 179 rospy.loginfo(
'Executing MOVE_PTU')
183 if not client.wait_for_server(rospy.Duration.from_sec(10)):
184 rospy.logwarn(
"Could not connect to ptu action server")
187 ptu_goal = PTUMovementGoal()
188 ptu_goal.target_joint.header.seq = 0
189 ptu_goal.target_joint.name = [
'pan',
'tilt']
190 ptu_goal.target_joint.velocity = [0, 0]
191 ptu_goal.target_joint.position = [userdata.goal_ptu_position[0],
192 userdata.goal_ptu_position[1]]
194 pan = userdata.goal_ptu_position[0] * numpy.pi/180.0
195 tilt = userdata.goal_ptu_position[1] * numpy.pi/180.0
196 rospy.loginfo(
"Moving PTU to goal (" + str(pan) +
", " + str(tilt) +
')')
198 ptu_result = client.send_goal_and_wait(ptu_goal)
199 rospy.loginfo(
"PTU action returned (3 being 'succeeded'): " + str(ptu_result))
208 smach.State.__init__(
210 outcomes=[
'succeeded',
'aborted'],
211 input_keys=[
'goal_camera_pose'])
216 rospy.loginfo(
'Executing PTU_POSE_CORRECTION')
218 targetPosition = userdata.goal_camera_pose.position
219 targetOrientation = userdata.goal_camera_pose.orientation
223 rospy.wait_for_service(
'/asr_robot_model_services/CalculateCameraPoseCorrection', timeout=5)
224 calculateCameraPoseCorrection = rospy.ServiceProxy(
225 '/asr_robot_model_services/CalculateCameraPoseCorrection',
226 CalculateCameraPoseCorrection)
227 actual_state = getRobotStateClass.get_robot_state()
229 rospy.loginfo(
'Robot state after navigation ' + str(actual_state))
231 actual_pan = actual_state.pan * numpy.pi/180
232 actual_tilt = actual_state.tilt * numpy.pi/180
233 rospy.loginfo(
'Pan and tilt in rad: ' + str(actual_pan) +
", " + str(actual_tilt))
235 ptuConfig = calculateCameraPoseCorrection(actual_state, targetOrientation, targetPosition)
236 except (rospy.ServiceException, rospy.exceptions.ROSException), e:
237 rospy.logwarn(str(e))
240 rospy.loginfo(
'Moving PTU to corrected goal (' + str(ptuConfig.pan) +
', ' + str(ptuConfig.tilt) +
')')
245 if not client.wait_for_server(rospy.Duration.from_sec(10)):
246 rospy.logwarn(
"Could not connect to ptu action server")
249 pan = ptuConfig.pan * 180/numpy.pi
250 tilt = ptuConfig.tilt * 180/numpy.pi
252 ptu_goal = PTUMovementGoal()
253 ptu_goal.target_joint.header.seq = 0
254 ptu_goal.target_joint.name = [
'pan',
'tilt']
255 ptu_goal.target_joint.velocity = [0, 0]
256 ptu_goal.target_joint.position = [pan, tilt]
257 ptu_result = client.send_goal_and_wait(ptu_goal)
258 rospy.loginfo(
"PTU action returned (3 being 'succeeded'): " + str(ptu_result))
263 rospy.logerr(
"Failed to correct PTU-pose. Resuming with current pose...")
def execute(self, userdata)
def execute(self, userdata)
def execute(self, userdata)
def execute(self, userdata)
def ptu_callback(self, data)