thruster_manager.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 
17 import numpy
18 import rospy
19 import tf
20 import tf.transformations as trans
21 import tf2_ros
22 from os.path import isdir, join
23 import yaml
24 from time import sleep
25 from models import Thruster
26 from uuv_gazebo_ros_plugins_msgs.msg import FloatStamped
27 from geometry_msgs.msg import Wrench
28 import xml.etree.ElementTree as etree
29 
30 
32  """
33  The thruster manager generates the thruster allocation matrix using the
34  TF information and publishes the thruster forces assuming the the thruster
35  topics are named in the following pattern
36 
37  <thruster_topic_prefix>/<index>/<thruster_topic_suffix>
38 
39  Thruster frames should also be named as follows
40 
41  <thruster_frame_base>_<index>
42  """
43 
44  MAX_THRUSTERS = 16
45 
46  def __init__(self):
47  """Class constructor."""
48  # This flag will be set to true once the thruster allocation matrix is
49  # available
50  self._ready = False
51 
52  # Acquiring the namespace of the vehicle
53  self.namespace = rospy.get_namespace()
54  if self.namespace[-1] != '/':
55  self.namespace += '/'
56 
57  if self.namespace[0] != '/':
58  self.namespace = '/' + self.namespace
59 
60  if not rospy.has_param('thruster_manager'):
61  raise rospy.ROSException('Thruster manager parameters not '
62  'initialized for uuv_name=' +
63  self.namespace)
64 
65  # Load all parameters
66  self.config = rospy.get_param('thruster_manager')
67 
68  robot_description_param = self.namespace+'robot_description'
69  self.use_robot_descr = False
70  self.axes = {}
71  if rospy.has_param(robot_description_param):
72  self.use_robot_descr = True
73  self.parse_urdf(rospy.get_param(robot_description_param))
74 
75  if self.config['update_rate'] < 0:
76  self.config['update_rate'] = 50
77 
79 
80  tf_buffer = tf2_ros.Buffer()
81  listener = tf2_ros.TransformListener(tf_buffer)
82  tf_trans_ned_to_enu = None
83 
84  try:
85  target = '%sbase_link' % self.namespace
86  target = target[1::]
87  source = '%sbase_link_ned' % self.namespace
88  source = source[1::]
89  tf_trans_ned_to_enu = tf_buffer.lookup_transform(
90  target, source, rospy.Time(), rospy.Duration(1))
91  except Exception, e:
92  rospy.loginfo('No transform found between base_link and base_link_ned'
93  ' for vehicle ' + self.namespace)
94  rospy.loginfo(str(e))
95  self.base_link_ned_to_enu = None
96 
97  if tf_trans_ned_to_enu is not None:
98  self.base_link_ned_to_enu = trans.quaternion_matrix(
99  (tf_trans_ned_to_enu.transform.rotation.x,
100  tf_trans_ned_to_enu.transform.rotation.y,
101  tf_trans_ned_to_enu.transform.rotation.z,
102  tf_trans_ned_to_enu.transform.rotation.w))[0:3, 0:3]
103 
104  rospy.loginfo('base_link transform NED to ENU=\n' + str(self.base_link_ned_to_enu))
105 
106  rospy.loginfo(
107  'ThrusterManager::update_rate=' + str(self.config['update_rate']))
108 
109  # Set the tf_prefix parameter
110  rospy.set_param('thruster_manager/tf_prefix', self.namespace)
111 
112  # Retrieve the output file path to store the TAM
113  # matrix for future use
114  self.output_dir = None
115  if rospy.has_param('~output_dir'):
116  self.output_dir = rospy.get_param('~output_dir')
117  if not isdir(self.output_dir):
118  raise rospy.ROSException(
119  'Invalid output directory, output_dir=' + self.output_dir)
120  rospy.loginfo('output_dir=' + self.output_dir)
121 
122  # Number of thrusters
123  self.n_thrusters = 0
124 
125  # Thruster objects used to calculate the right angular velocity command
126  self.thrusters = list()
127 
128  # Thrust forces vector
129  self.thrust = None
130 
131  # Thruster allocation matrix: transform thruster inputs to force/torque
133  if rospy.has_param('~tam'):
134  tam = rospy.get_param('~tam')
135  self.configuration_matrix = numpy.array(tam)
136  # Set number of thrusters from the number of columns
137  self.n_thrusters = self.configuration_matrix.shape[1]
138  # Create publishing topics to each thruster
139  params = self.config['conversion_fcn_params']
140  conv_fcn = self.config['conversion_fcn']
141  if type(params) == list and type(conv_fcn) == list:
142  if len(params) != self.n_thrusters or len(conv_fcn) != self.n_thrusters:
143  raise rospy.ROSException('Lists conversion_fcn and '
144  'conversion_fcn_params must have '
145  'the same number of items as of '
146  'thrusters')
147  for i in range(self.n_thrusters):
148  topic = self.config['thruster_topic_prefix'] + str(i) + \
149  self.config['thruster_topic_suffix']
150  if list not in [type(params), type(conv_fcn)]:
151  thruster = Thruster.create_thruster(
152  conv_fcn, i, topic, None, None,
153  **params)
154  else:
155  thruster = Thruster.create_thruster(
156  conv_fcn[i], i, topic, None, None,
157  **params[i])
158 
159  if thruster is None:
160  rospy.ROSException('Invalid thruster conversion '
161  'function=%s'
162  % self.config['conversion_fcn'])
163  self.thrusters.append(thruster)
164  rospy.loginfo('Thruster allocation matrix provided!')
165  rospy.loginfo('TAM=')
166  rospy.loginfo(self.configuration_matrix)
167  self.thrust = numpy.zeros(self.n_thrusters)
168 
169  if not self.update_tam():
170  raise rospy.ROSException('No thrusters found')
171 
172  # (pseudo) inverse: force/torque to thruster inputs
174  if self.configuration_matrix is not None:
175  self.inverse_configuration_matrix = numpy.linalg.pinv(
177 
178  # If an output directory was provided, store matrix for further use
179  if self.output_dir is not None:
180  with open(join(self.output_dir, 'TAM.yaml'), 'w') as yaml_file:
181  yaml_file.write(
182  yaml.safe_dump(
183  dict(tam=self.configuration_matrix.tolist())))
184  else:
185  rospy.loginfo('Invalid output directory for the TAM matrix, dir=' + str(self.output_dir))
186 
187  self.ready = True
188  rospy.loginfo('ThrusterManager: ready')
189 
190  def parse_urdf(self, urdf_str):
191  root = etree.fromstring(urdf_str)
192  for joint in root.findall('joint'):
193  if joint.get('type') == 'fixed':
194  continue
195  axis_str_list = joint.find('axis').get('xyz').split()
196  child = joint.find('child').get('link')
197  if child[0]!='/':
198  child = '/'+child
199 
200  self.axes[child] = numpy.array([float(axis_str_list[0]),
201  float(axis_str_list[1]),
202  float(axis_str_list[2]), 0.0])
203 
204 
205  def update_tam(self, recalculate=False):
206  """Calculate the thruster allocation matrix, if one is not given."""
207  if self.configuration_matrix is not None and not recalculate:
208  self.ready = True
209  rospy.loginfo('TAM provided, skipping...')
210  rospy.loginfo('ThrusterManager: ready')
211  return True
212 
213  self.ready = False
214  rospy.loginfo('ThrusterManager: updating thruster poses')
215  # Small margin to make sure we get thruster frames via tf
216  now = rospy.Time.now() + rospy.Duration(1.0)
217 
218  base = self.namespace + self.config['base_link']
219 
220  self.thrusters = list()
221 
222  equal_thrusters = True
223  idx_thruster_model = 0
224 
225  if type(self.config['conversion_fcn_params']) == list and \
226  type(self.config['conversion_fcn']) == list:
227  if len(self.config['conversion_fcn_params']) != len(
228  self.config['conversion_fcn']):
229  raise rospy.ROSException(
230  'Lists of conversion_fcn_params and conversion_fcn'
231  ' must have equal length')
232  equal_thrusters = False
233 
234  rospy.loginfo('conversion_fcn=' + str(self.config['conversion_fcn']))
235  rospy.loginfo('conversion_fcn_params=' + str(self.config['conversion_fcn_params']))
236 
237  listener = tf.TransformListener()
238  sleep(5)
239 
240  for i in range(self.MAX_THRUSTERS):
241  frame = self.namespace + \
242  self.config['thruster_frame_base'] + str(i)
243  try:
244  # try to get thruster pose with respect to base frame via tf
245  rospy.loginfo('transform: ' + base + ' -> ' + frame)
246  now = rospy.Time.now() + rospy.Duration(1.0)
247  listener.waitForTransform(base, frame,
248  now, rospy.Duration(30.0))
249  [pos, quat] = listener.lookupTransform(base, frame, now)
250 
251  topic = self.config['thruster_topic_prefix'] + str(i) + \
252  self.config['thruster_topic_suffix']
253 
254  # If not using robot_description, thrust_axis=None which will
255  # result in the thrust axis being the x-axis,i.e. (1,0,0)
256  thrust_axis = None if not self.use_robot_descr else self.axes[frame]
257 
258  if equal_thrusters:
259  params = self.config['conversion_fcn_params']
260  thruster = Thruster.create_thruster(
261  self.config['conversion_fcn'],
262  i, topic, pos, quat, self.axes[frame], **params)
263  else:
264  if idx_thruster_model >= len(self.config['conversion_fcn']):
265  raise rospy.ROSException('Number of thrusters found and '
266  'conversion_fcn are different')
267  params = self.config['conversion_fcn_params'][idx_thruster_model]
268  conv_fcn = self.config['conversion_fcn'][idx_thruster_model]
269  thruster = Thruster.create_thruster(
270  conv_fcn,
271  i, topic, pos, quat, self.axes[frame],
272  **params)
273  idx_thruster_model += 1
274  if thruster is None:
275  rospy.ROSException('Invalid thruster conversion '
276  'function=%s'
277  % self.config['conversion_fcn'])
278  self.thrusters.append(thruster)
279  except tf.Exception:
280  rospy.loginfo('could not get transform from: ' + base)
281  rospy.loginfo('to: ' + frame)
282  break
283 
284  rospy.loginfo(str(self.thrusters))
285  if len(self.thrusters) == 0:
286  return False
287 
288  # Set the number of thrusters found
289  self.n_thrusters = len(self.thrusters)
290 
291  # Fill the thrust vector
292  self.thrust = numpy.zeros(self.n_thrusters)
293 
294  # Fill the thruster allocation matrix
295  self.configuration_matrix = numpy.zeros((6, self.n_thrusters))
296 
297  for i in range(self.n_thrusters):
298  self.configuration_matrix[:, i] = self.thrusters[i].tam_column
299 
300  # Eliminate small values
301  self.configuration_matrix[numpy.abs(
302  self.configuration_matrix) < 1e-3] = 0.0
303 
304  rospy.loginfo('TAM= %s', str(self.configuration_matrix))
305 
306  # Once we know the configuration matrix we can compute its
307  # (pseudo-)inverse:
308  self.inverse_configuration_matrix = numpy.linalg.pinv(
310 
311  # If an output directory was provided, store matrix for further use
312  if self.output_dir is not None and not recalculate:
313  with open(join(self.output_dir, 'TAM.yaml'), 'w') as yaml_file:
314  yaml_file.write(
315  yaml.safe_dump(
316  dict(tam=self.configuration_matrix.tolist())))
317  print 'TAM saved in <%s>' % join(self.output_dir, 'TAM.yaml')
318  elif recalculate:
319  print 'Recalculate flag on, matrix will not be stored in TAM.yaml'
320  else:
321  print 'Invalid output directory for the TAM matrix, dir=', self.output_dir
322 
323  self.ready = True
324  print ('ThrusterManager: ready')
325  return True
326 
327  def command_thrusters(self):
328  """Publish the thruster input into their specific topic."""
329  if self.thrust is None:
330  return
331  for i in range(self.n_thrusters):
332  self.thrusters[i].publish_command(self.thrust[i])
333 
334  def publish_thrust_forces(self, control_forces, control_torques,
335  frame_id=None):
336  if not self.ready:
337  return
338 
339  if frame_id is not None:
340  if self.config['base_link'] != frame_id:
341  assert self.base_link_ned_to_enu is not None, 'Transform from'
342  ' base_link_ned to base_link could not be found'
343  if 'base_link_ned' not in self.config['base_link']:
344  control_forces = numpy.dot(self.base_link_ned_to_enu,
345  control_forces)
346  control_torques = numpy.dot(self.base_link_ned_to_enu,
347  control_torques)
348  else:
349  control_forces = numpy.dot(self.base_link_ned_to_enu.T,
350  control_forces)
351  control_torques = numpy.dot(self.base_link_ned_to_enu.T,
352  control_torques)
353 
354  gen_forces = numpy.hstack(
355  (control_forces, control_torques)).transpose()
356  self.thrust = self.compute_thruster_forces(gen_forces)
357  self.command_thrusters()
358 
359  def compute_thruster_forces(self, gen_forces):
360  """Compute desired thruster forces using the inverse configuration
361  matrix.
362  """
363  # Calculate individual thrust forces
364  thrust = self.inverse_configuration_matrix.dot(gen_forces)
365  # Obey limit on max thrust by applying a constant scaling factor to all
366  # thrust forces
367  limitation_factor = 1.0
368  if type(self.config['max_thrust']) == list:
369  if len(self.config['max_thrust']) != self.n_thrusters:
370  raise rospy.ROSException('max_thrust list must have the length'
371  ' equal to the number of thrusters')
372  max_thrust = self.config['max_thrust']
373  else:
374  max_thrust = [self.config['max_thrust'] for _ in range(self.n_thrusters)]
375  for i in range(self.n_thrusters):
376  if abs(thrust[i]) > max_thrust[i]:
377  thrust[i] = numpy.sign(thrust[i]) * max_thrust[i]
378  return thrust
def publish_thrust_forces(self, control_forces, control_torques, frame_id=None)


uuv_thruster_manager
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Mon Jul 1 2019 19:39:26