$search
00001 #!/usr/bin/env python 00002 ############################################################################### 00003 # \file 00004 # 00005 # $Id:$ 00006 # 00007 # Copyright (C) Brno University of Technology 00008 # 00009 # This file is part of software developed by dcgm-robotics@FIT group. 00010 # 00011 # Author: Zdenek Materna (imaterna@fit.vutbr.cz) 00012 # Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00013 # Date: dd/mm/2012 00014 # 00015 # This file is free software: you can redistribute it and/or modify 00016 # it under the terms of the GNU Lesser General Public License as published by 00017 # the Free Software Foundation, either version 3 of the License, or 00018 # (at your option) any later version. 00019 # 00020 # This file is distributed in the hope that it will be useful, 00021 # but WITHOUT ANY WARRANTY; without even the implied warranty of 00022 # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00023 # GNU Lesser General Public License for more details. 00024 # 00025 # You should have received a copy of the GNU Lesser General Public License 00026 # along with this file. If not, see <http://www.gnu.org/licenses/>. 00027 # 00028 import roslib; roslib.load_manifest('srs_user_tests') 00029 import rospy 00030 from std_srvs.srv import Empty as EmptySrv 00031 from geometry_msgs.msg import Pose 00032 from gazebo_msgs.srv import SetModelState 00033 from gazebo_msgs.msg import ModelState 00034 from geometry_msgs.msg import PoseWithCovarianceStamped 00035 from std_msgs.msg import Empty as EmptyMsg 00036 00037 00038 def main(): 00039 00040 rospy.init_node('move_robot_to_given_place') 00041 00042 g_pause = rospy.ServiceProxy("/gazebo/pause_physics", EmptySrv) 00043 g_unpause = rospy.ServiceProxy("/gazebo/unpause_physics", EmptySrv) 00044 g_set_state = rospy.ServiceProxy("/gazebo/set_model_state",SetModelState) 00045 pub = rospy.Publisher("/initialpose", PoseWithCovarianceStamped,latch=True) 00046 #rospy.sleep(26) 00047 00048 sim = rospy.get_param('/use_sim_time') 00049 00050 if sim is True: 00051 00052 rospy.loginfo('Waiting until simulated robot is prepared for the task...') 00053 00054 rospy.wait_for_message('/sim_robot_init',EmptyMsg) 00055 00056 00057 rospy.wait_for_service("/gazebo/pause_physics") 00058 00059 rospy.loginfo("Pausing physics") 00060 00061 try: 00062 00063 g_pause() 00064 00065 except Exception, e: 00066 00067 rospy.logerr('Error on calling service: %s',str(e)) 00068 00069 00070 pose = Pose() 00071 00072 pose.position.x = rospy.get_param('~position_x') 00073 pose.position.y = rospy.get_param('~position_y') 00074 pose.position.z = rospy.get_param('~position_z') 00075 00076 pose.orientation.x = rospy.get_param('~orientation_x') 00077 pose.orientation.y = rospy.get_param('~orientation_y') 00078 pose.orientation.z = rospy.get_param('~orientation_z') 00079 pose.orientation.w = rospy.get_param('~orientation_w') 00080 00081 state = ModelState() 00082 00083 state.model_name = "robot" 00084 state.pose = pose 00085 00086 00087 rospy.loginfo("Moving robot") 00088 try: 00089 00090 ret = g_set_state(state) 00091 00092 print ret.status_message 00093 00094 except Exception, e: 00095 00096 rospy.logerr('Error on calling service: %s',str(e)) 00097 00098 00099 00100 00101 rospy.loginfo("Unpausing physics") 00102 00103 try: 00104 00105 g_unpause() 00106 00107 except Exception, e: 00108 00109 rospy.logerr('Error on calling service: %s',str(e)) 00110 00111 00112 00113 00114 loc = PoseWithCovarianceStamped() 00115 00116 loc.pose.pose = pose 00117 loc.header.frame_id = "/map" 00118 #loc.pose.covariance = [0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891945200942] 00119 00120 rospy.loginfo("Adjusting localization") 00121 pub.publish(loc) 00122 pub.publish(loc) 00123 pub.publish(loc) 00124 00125 rospy.sleep(1) 00126 00127 if sim is True: 00128 00129 rospy.loginfo('Simulation is completely ready, publishing to /sim_init topic') 00130 00131 pub = rospy.Publisher('/sim_init', EmptyMsg,latch=True) 00132 pub.publish(EmptyMsg()) 00133 pub.publish(EmptyMsg()) 00134 pub.publish(EmptyMsg()) 00135 00136 rospy.spin() 00137 00138 00139 00140 if __name__ == '__main__': 00141 try: 00142 main() 00143 except rospy.ROSInterruptException: pass