start_helical_trajectory.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 import sys
19 from uuv_control_msgs.srv import InitHelicalTrajectory
20 from numpy import pi
21 from geometry_msgs.msg import Point
22 from std_msgs.msg import Time
23 
24 if __name__ == '__main__':
25  print('Starting the helical trajectory creator')
26  rospy.init_node('start_circular_trajectory')
27 
28  if rospy.is_shutdown():
29  print('ROS master not running!')
30  sys.exit(-1)
31 
32  # If no start time is provided: start *now*.
33  start_time = rospy.Time.now().to_sec()
34  start_now = False
35  if rospy.has_param('~start_time'):
36  start_time = rospy.get_param('~start_time')
37  if start_time < 0.0:
38  print('Negative start time, setting it to 0.0')
39  start_time = 0.0
40  start_now = True
41  else:
42  start_now = True
43 
44  param_labels = ['radius', 'center', 'n_points', 'heading_offset',
45  'duration', 'n_turns', 'delta_z', 'max_forward_speed']
46  params = dict()
47 
48  for label in param_labels:
49  if not rospy.has_param('~' + label):
50  print('{} must be provided for the trajectory generation!'.format(label))
51  sys.exit(-1)
52 
53  params[label] = rospy.get_param('~' + label)
54 
55  if len(params['center']) != 3:
56  raise rospy.ROSException('Center of circle must have 3 components (x, y, z)')
57 
58  if params['n_points'] <= 2:
59  raise rospy.ROSException('Number of points must be at least 2')
60 
61  if params['max_forward_speed'] <= 0:
62  raise rospy.ROSException('Velocity limit must be positive')
63 
64  try:
65  rospy.wait_for_service('start_helical_trajectory', timeout=20)
66  except rospy.ROSException:
67  raise rospy.ROSException('Service not available! Closing node...')
68 
69  try:
70  traj_gen = rospy.ServiceProxy('start_helical_trajectory', InitHelicalTrajectory)
71  except rospy.ServiceException as e:
72  raise rospy.ROSException('Service call failed, error={}'.format(e))
73 
74  print('Generating trajectory that starts at t={} s'.format(start_time))
75 
76  success = traj_gen(Time(rospy.Time(start_time)),
77  start_now,
78  params['radius'],
79  Point(params['center'][0], params['center'][1], params['center'][2]),
80  False,
81  0.0,
82  params['n_points'],
83  params['heading_offset'] * pi / 180,
84  params['max_forward_speed'],
85  params['duration'],
86  params['n_turns'],
87  params['delta_z'])
88 
89  if success:
90  print('Trajectory successfully generated!')
91  else:
92  print('Failed')


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