actuator_manager.py
Go to the documentation of this file.
1 # Copyright (c) 2016 The UUV Simulator Authors.
2 # All rights reserved.
3 #
4 # Licensed under the Apache License, Version 2.0 (the "License");
5 # you may not use this file except in compliance with the License.
6 # You may obtain a copy of the License at
7 #
8 # http://www.apache.org/licenses/LICENSE-2.0
9 #
10 # Unless required by applicable law or agreed to in writing, software
11 # distributed under the License is distributed on an "AS IS" BASIS,
12 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 # See the License for the specific language governing permissions and
14 # limitations under the License.
15 
16 from fin_model import FinModel
17 import rospy
18 import numpy as np
19 import tf2_ros
20 from tf_quaternion.transformations import quaternion_matrix
21 from uuv_thrusters.models import Thruster
22 from uuv_auv_control_allocator.msg import AUVCommand
23 from uuv_gazebo_ros_plugins_msgs.msg import FloatStamped
24 from geometry_msgs.msg import Wrench, WrenchStamped
25 import os
26 import yaml
27 
28 
29 class ActuatorManager(object):
30  MAX_FINS = 4
31 
32 
33  def __init__(self):
34  # Acquiring the namespace of the vehicle
35  self.namespace = rospy.get_namespace().replace('/', '')
36  rospy.loginfo('Initialize control allocator for vehicle <%s>' % self.namespace)
37 
38  self.tf_buffer = tf2_ros.Buffer()
39  self.listener = tf2_ros.TransformListener(self.tf_buffer)
40  tf_trans_ned_to_enu = None
41 
42  try:
43  target = '%s/base_link' % self.namespace
44  source = '%s/base_link_ned' % self.namespace
45  rospy.loginfo('Lookup transfrom from %s to %s' % (source, target))
46  tf_trans_ned_to_enu = self.tf_buffer.lookup_transform(
47  target, source, rospy.Time(), rospy.Duration(1))
48  except Exception, e:
49  print('No transform found between base_link and base_link_ned'
50  ' for vehicle ' + self.namespace)
51  print(str(e))
53 
54  if tf_trans_ned_to_enu is not None:
55  self.base_link_ned_to_enu = quaternion_matrix(
56  (tf_trans_ned_to_enu.transform.rotation.x,
57  tf_trans_ned_to_enu.transform.rotation.y,
58  tf_trans_ned_to_enu.transform.rotation.z,
59  tf_trans_ned_to_enu.transform.rotation.w))[0:3, 0:3]
60 
61  print 'base_link transform NED to ENU=\n', self.base_link_ned_to_enu
62 
63  self.base_link = rospy.get_param('~base_link', 'base_link')
64 
65  # Check if the thruster configuration is available
66  if not rospy.has_param('~thruster_config'):
67  raise rospy.ROSException('Thruster configuration not available')
68 
69  # Retrieve the thruster configuration parameters
70  self.thruster_config = rospy.get_param('~thruster_config')
71 
72  # Check if all necessary thruster model parameter are available
73  thruster_params = ['conversion_fcn_params', 'conversion_fcn',
74  'topic_prefix', 'topic_suffix', 'frame_base', 'max_thrust']
75  for p in thruster_params:
76  if p not in self.thruster_config:
77  raise rospy.ROSException(
78  'Parameter <%s> for thruster conversion function is missing' % p)
79 
80  # Setting up the thruster topic name
81  self.thruster_topic = '/%s/%s/%d/%s' % (self.namespace,
82  self.thruster_config['topic_prefix'], 0,
83  self.thruster_config['topic_suffix'])
84  self.thruster = None
85 
86  # Check if the fin configuration is available
87  if not rospy.has_param('~fin_config'):
88  raise rospy.ROSException('Fin configuration is not available')
89 
90  # Retrieve the fin configuration is available
91  self.fin_config = rospy.get_param('~fin_config')
92 
93  # Check if all necessary fin parameters are available
94  fin_params = ['fluid_density', 'lift_coefficient', 'fin_area',
95  'topic_prefix', 'topic_suffix', 'frame_base']
96 
97  for p in fin_params:
98  if p not in self.fin_config:
99  raise rospy.ROSException(
100  'Parameter <%s> for fin configuration is missing' % p)
101 
102  self.fin_lower_limit = -np.pi / 2
103  if 'lower_limit' in self.fin_config:
104  self.fin_lower_limit = self.fin_config['lower_limit']
105 
106  self.fin_upper_limit = np.pi / 2
107  if 'upper_limit' in self.fin_config:
108  self.fin_upper_limit = self.fin_config['upper_limit']
109 
110  if self.fin_config['lower_limit'] >= self.fin_config['upper_limit']:
111  raise rospy.ROSException('Fin angle limits are invalid')
112 
113  self.fins = dict()
114 
115  self.n_fins = 0
116 
117  if not self.find_actuators():
118  raise rospy.ROSException('No thruster and/or fins found')
119 
120  def find_actuators(self):
121  """Calculate the control allocation matrix, if one is not given."""
122 
123  self.ready = False
124  rospy.loginfo('ControlAllocator: updating thruster poses')
125 
126  base = '%s/%s' % (self.namespace, self.base_link)
127 
128  frame = '%s/%s%d' % (self.namespace, self.thruster_config['frame_base'], 0)
129 
130  rospy.loginfo('Lookup: Thruster transform found %s -> %s' % (base, frame))
131  trans = self.tf_buffer.lookup_transform(base, frame, rospy.Time(), rospy.Duration(1))
132  pos = np.array([trans.transform.translation.x,
133  trans.transform.translation.y,
134  trans.transform.translation.z])
135  quat = np.array([trans.transform.rotation.x,
136  trans.transform.rotation.y,
137  trans.transform.rotation.z,
138  trans.transform.rotation.w])
139  rospy.loginfo('Thruster transform found %s -> %s' % (base, frame))
140  rospy.loginfo('pos=' + str(pos))
141  rospy.loginfo('rot=' + str(quat))
142 
143  # Read transformation from thruster
144  self.thruster = Thruster.create_thruster(
145  self.thruster_config['conversion_fcn'], 0,
146  self.thruster_topic, pos, quat,
147  **self.thruster_config['conversion_fcn_params'])
148 
149  for i in range(self.MAX_FINS):
150  try:
151  frame = '%s/%s%d' % (self.namespace, self.fin_config['frame_base'], i)
152 
153  rospy.loginfo('Lookup: Fin transform found %s -> %s' % (base, frame))
154  trans = self.tf_buffer.lookup_transform(base, frame, rospy.Time(), rospy.Duration(1))
155  pos = np.array([trans.transform.translation.x,
156  trans.transform.translation.y,
157  trans.transform.translation.z])
158  quat = np.array([trans.transform.rotation.x,
159  trans.transform.rotation.y,
160  trans.transform.rotation.z,
161  trans.transform.rotation.w])
162  rospy.loginfo('Fin transform found %s -> %s' % (base, frame))
163  rospy.loginfo('pos=' + str(pos))
164  rospy.loginfo('quat=' + str(quat))
165 
166  fin_topic = '/%s/%s/%d/%s' % (self.namespace,
167  self.fin_config['topic_prefix'], i, self.fin_config['topic_suffix'])
168 
169  self.fins[i] = FinModel(
170  i,
171  pos,
172  quat,
173  fin_topic)
174 
175  except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException):
176  rospy.loginfo('Could not get transform from %s to %s ' % (base, frame))
177  break
178 
179  self.n_fins = len(self.fins.keys())
180  rospy.loginfo('# fins found: %d' % len(self.fins.keys()))
181 
182  for i in range(self.n_fins):
183  rospy.loginfo(i)
184  rospy.loginfo(self.fins[i].pos)
185  rospy.loginfo(self.fins[i].rot)
186 
187  self.ready = True
188  return True
189 
190  def compute_control_force(self, thrust, delta, u):
191  actuator_model = self.thruster.tam_column.reshape((6, 1)) * thrust
192  for i in self.fins:
193  f_lift = (0.5 * self.fin_config['fluid_density'] *
194  self.fin_config['lift_coefficient'] * self.fin_config['fin_area'] *
195  delta[i] * u**2)
196 
197  tau = np.zeros(6)
198  tau[0:3] = f_lift * self.fins[i].lift_vector
199  tau[3::] = np.cross(self.fins[i].pos, f_lift)
200 
201  actuator_model += tau
202  return actuator_model
203 
204  def publish_commands(self, command):
205  self.thruster.publish_command(command[0])
206 
207  for i in range(self.n_fins):
208  self.fins[i].publish_command(command[i + 1])


uuv_auv_control_allocator
Author(s): Musa Morena Marcusso Manhaes
autogenerated on Mon Jul 1 2019 19:39:09