move.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 Copyright (c) 2016, Allgeyer Tobias, Aumann Florian, Borella Jocelyn, Hutmacher Robin, Karrenbauer Oliver, Marek Felix, Meissner Pascal, Trautmann Jeremias, Wittenbeck Valerij
5 
6 All rights reserved.
7 
8 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
9 
10 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
11 
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.
13 
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.
15 
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.
17 '''
18 
19 import roslib
20 import rospy
21 import smach
22 import smach_ros
23 import numpy
24 import time
25 import math
26 import timeit
27 
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 *
34 from actionlib.msg 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
39 import __builtin__
40 
41 """
42 Defines states that are relevant for moving the robot, i.e. moving the base,
43 moving the ptu and getting the current positition.
44 """
45 
46 # Make independent from class, so that in- and direct search will share the move_base_time
47 global move_base_time
48 move_base_time = 0.0
49 
50 class MoveBase(smach.State):
51  """
52  Move the roboter base to given position.
53  """
54 
55  def __init__(self):
56  smach.State.__init__(
57  self,
58  outcomes=['succeeded', 'aborted'],
59  input_keys=['goal_robot_pose'])
60 
61  @log
62  @timed
63  def execute(self, userdata):
64  rospy.loginfo('Executing MOVE_BASE')
65 
66  start = time()
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
72 
73  client = actionlib.SimpleActionClient('move_base', MoveBaseAction)
74  if not client.wait_for_server(rospy.Duration.from_sec(10)):
75  rospy.logwarn("Can't contact move_base action server")
76  return 'aborted'
77 
78  rospy.loginfo('Sending goal to move_base action server.')
79  move_result = client.send_goal_and_wait(next_goal)
80 
81  rospy.loginfo("Move_base action returned (3 being 'succeeded'): " + str(move_result))
82  end = time()
83  elapsed_time = end - start
84  global move_base_time
85  move_base_time += elapsed_time
86 
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))
95  + "\norientation:"
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)))
100 
101  rospy.loginfo("Move Base took : " + str(elapsed_time) + " seconds (Total time in move_base: " + str(move_base_time) + ")")
102 
103  if move_result == 3:
104  return 'succeeded'
105  else:
106  return 'aborted'
107 
108 
109 class FakeMoveBase(smach.State):
110  """
111  Sets robot to goal pose via '/initialpose' topic, bypassing actual ros navigation.
112  """
113  pub = None
114 
115  def __init__(self):
116  smach.State.__init__(
117  self,
118  outcomes=['succeeded'],
119  input_keys=['goal_robot_pose'])
120  self.pub = rospy.Publisher('/initialpose', PoseWithCovarianceStamped, queue_size=10)
121 
122  @log
123  @timed
124  def execute(self, userdata):
125  rospy.loginfo('Executing FAKE_MOVE_BASE')
126 
127  start = time()
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
133 
134  rospy.loginfo('Publish goal to /initialpose.')
135  self.pub.publish(next_goal)
136  rospy.sleep(0.5)
137  end = time()
138  elapsed_time = end - start
139  global move_base_time
140  move_base_time += elapsed_time
141 
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))
150  + "\norientation:"
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)))
155 
156  rospy.loginfo("Move Base took : " + str(elapsed_time) + " seconds (Total time in move_base: " + str(move_base_time) + ")")
157 
158  return 'succeeded'
159 
160 class MovePTU(smach.State):
161  """
162  Moves the PTU to a given pose. A pose should consist of a pan and tilt value.
163  """
164 
165  def __init__(self):
166  smach.State.__init__(
167  self,
168  outcomes=['succeeded', 'aborted'],
169  input_keys=['goal_ptu_position'])
170 
171  def ptu_callback(self, data):
172  """Callback for ptu movements"""
173  pass
174  # print "Feedback while PTU is moving: " + str(data)
175 
176  @timed
177  @log
178  def execute(self, userdata):
179  rospy.loginfo('Executing MOVE_PTU')
180 
181  client = actionlib.SimpleActionClient('ptu_controller_actionlib',
182  PTUMovementAction)
183  if not client.wait_for_server(rospy.Duration.from_sec(10)):
184  rospy.logwarn("Could not connect to ptu action server")
185  return 'aborted'
186 
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]]
193 
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) + ')')
197 
198  ptu_result = client.send_goal_and_wait(ptu_goal)
199  rospy.loginfo("PTU action returned (3 being 'succeeded'): " + str(ptu_result))
200 
201  if ptu_result == 3:
202  return 'succeeded'
203  else:
204  return 'aborted'
205 
206 class PTUPoseCorrection(smach.State):
207  def __init__(self):
208  smach.State.__init__(
209  self,
210  outcomes=['succeeded', 'aborted'],
211  input_keys=['goal_camera_pose'])
212 
213  @timed
214  @log
215  def execute(self, userdata):
216  rospy.loginfo('Executing PTU_POSE_CORRECTION')
217 
218  targetPosition = userdata.goal_camera_pose.position
219  targetOrientation = userdata.goal_camera_pose.orientation
220  getRobotStateClass = state_acquisition.GetRobotState()
221 
222  try:
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()
228 
229  rospy.loginfo('Robot state after navigation ' + str(actual_state))
230 
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))
234 
235  ptuConfig = calculateCameraPoseCorrection(actual_state, targetOrientation, targetPosition)
236  except (rospy.ServiceException, rospy.exceptions.ROSException), e:
237  rospy.logwarn(str(e))
238  return 'aborted'
239 
240  rospy.loginfo('Moving PTU to corrected goal (' + str(ptuConfig.pan) + ', ' + str(ptuConfig.tilt) + ')')
241 
242  client = actionlib.SimpleActionClient('ptu_controller_actionlib',
243  PTUMovementAction)
244 
245  if not client.wait_for_server(rospy.Duration.from_sec(10)):
246  rospy.logwarn("Could not connect to ptu action server")
247  return 'aborted'
248 
249  pan = ptuConfig.pan * 180/numpy.pi
250  tilt = ptuConfig.tilt * 180/numpy.pi
251 
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))
259 
260  if ptu_result == 3:
261  return 'succeeded'
262  else:
263  rospy.logerr("Failed to correct PTU-pose. Resuming with current pose...")
264  return 'aborted'
265 
def execute(self, userdata)
Definition: move.py:178
def execute(self, userdata)
Definition: move.py:63
def execute(self, userdata)
Definition: move.py:124
def __init__(self)
Definition: move.py:55
def execute(self, userdata)
Definition: move.py:215
def __init__(self)
Definition: move.py:165
def ptu_callback(self, data)
Definition: move.py:171


asr_state_machine
Author(s): Allgeyer Tobias, Aumann Florian, Borella Jocelyn, Hutmacher Robin, Karrenbauer Oliver, Marek Felix, Meißner Pascal, Trautmann Jeremias, Wittenbeck Valerij
autogenerated on Mon Feb 28 2022 21:53:50