start_simulator.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright (c) 2020 Kei Okada
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions are met:
8 #
9 # 1. Redistributions of source code must retain the above copyright notice,
10 # this list of conditions and the following disclaimer.
11 # 2. Redistributions in binary form must reproduce the above copyright
12 # notice, this list of conditions and the following disclaimer in the
13 # documentation and/or other materials provided with the distribution.
14 # 3. Neither the name of the Rethink Robotics nor the names of its
15 # contributors may be used to endorse or promote products derived from
16 # this software without specific prior written permission.
17 #
18 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28 # POSSIBILITY OF SUCH DAMAGE.
29 
30 import rospy
31 import time
32 import sys
33 from std_srvs.srv import Empty
34 from gazebo_msgs.srv import GetPhysicsProperties, GetPhysicsPropertiesResponse
35 
36 
38 
39  def __init__(self):
40  self.physics_properties = GetPhysicsPropertiesResponse()
41  self.physics_properties.pause = True
42  rospy.loginfo(self.physics_properties)
43  rospy.wait_for_service('/gazebo/get_physics_properties')
44  self.get_physics_properties_service = rospy.ServiceProxy('/gazebo/get_physics_properties', GetPhysicsProperties)
45  rospy.wait_for_service('/gazebo/unpause_physics')
46  self.start_simulation = rospy.ServiceProxy('/gazebo/unpause_physics', Empty)
47 
49  rospy.logwarn("start gazebo simulation")
50  self.start_simulation()
51  time.sleep(1.0) # use wall clock just in case
53  rospy.loginfo(self.physics_properties)
54 
55 
56 if __name__ == '__main__':
57  rospy.init_node('start_simulator', anonymous=True)
58  rospy.logwarn("wait for gazebo startup")
59  time.sleep(5.0) # wait for gazebo startup
60  start_gazebo_simulator = StartGazeboSimulator()
61 
62  # start simulator when pouse is true
63  while not rospy.is_shutdown() and start_gazebo_simulator.physics_properties.pause is True:
64  try:
65  start_gazebo_simulator.call_start_simulation()
66  except Exception as e:
67  print("Unexpected error:", e)
68  pass


gundam_rx78_gazebo
Author(s): Kei Okada
autogenerated on Wed Sep 2 2020 03:33:39