set_thruster_state.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Copyright (c) 2016 The UUV Simulator Authors.
3 # All rights reserved.
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 from __future__ import print_function
17 import rospy
18 from uuv_gazebo_ros_plugins_msgs.srv import SetThrusterState
19 
20 
21 if __name__ == '__main__':
22  print('Set the state of thrusters for vehicle, namespace=', rospy.get_namespace())
23  rospy.init_node('set_thrusters_states')
24 
25  if rospy.is_shutdown():
26  rospy.ROSException('ROS master not running!')
27 
28  starting_time = 0.0
29  if rospy.has_param('~starting_time'):
30  starting_time = rospy.get_param('~starting_time')
31 
32  print('Starting time={} s'.format(starting_time))
33 
34  duration = 0.0
35  if rospy.has_param('~duration'):
36  duration = rospy.get_param('~duration')
37 
38  if duration == 0.0:
39  raise rospy.ROSException('Duration not set, leaving node...')
40 
41  print('Duration [s]=', ('Inf.' if duration < 0 else duration))
42 
43  if rospy.has_param('~is_on'):
44  is_on = bool(rospy.get_param('~is_on'))
45  else:
46  raise rospy.ROSException('State flag not provided')
47 
48  if rospy.has_param('~thruster_id'):
49  thruster_id = rospy.get_param('~thruster_id')
50  else:
51  raise rospy.ROSException('Thruster ID not given')
52 
53  if thruster_id < 0:
54  raise rospy.ROSException('Invalid thruster ID')
55 
56  print('Setting state of thruster #{} as {}'.format(thruster_id, 'ON' if is_on else 'OFF'))
57 
58  vehicle_name = rospy.get_namespace().replace('/', '')
59 
60  srv_name = '/%s/thrusters/%d/set_thruster_state' % (vehicle_name, thruster_id)
61 
62  try:
63  rospy.wait_for_service(srv_name, timeout=2)
64  except rospy.ROSException:
65  raise rospy.ROSException('Service not available! Closing node...')
66 
67  try:
68  set_state = rospy.ServiceProxy(srv_name, SetThrusterState)
69  except rospy.ServiceException as e:
70  raise rospy.ROSException('Service call failed, error=' + e)
71 
72  rate = rospy.Rate(100)
73  while rospy.get_time() < starting_time:
74  rate.sleep()
75 
76  success = set_state(is_on)
77 
78  if success:
79  print('Time={} s'.format(rospy.get_time()))
80  print('Current state of thruster #{}={}'.format(thruster_id, 'ON' if is_on else 'OFF'))
81 
82  if duration > 0:
83  rate = rospy.Rate(100)
84  while rospy.get_time() < starting_time + duration:
85  rate.sleep()
86 
87  success = set_state(not is_on)
88 
89  if success:
90  print('Time={} s'.format(rospy.get_time()))
91  print('Returning to previous state of thruster #{}={}'.format(thruster_id, 'ON' if not is_on else 'OFF'))
92 
93  print('Leaving node...')


uuv_control_utils
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Thu Jun 18 2020 03:28:47