20 import tf.transformations
as trans
22 from os.path
import isdir, join
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
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 37 <thruster_topic_prefix>/<index>/<thruster_topic_suffix> 39 Thruster frames should also be named as follows 41 <thruster_frame_base>_<index> 47 """Class constructor.""" 60 if not rospy.has_param(
'thruster_manager'):
61 raise rospy.ROSException(
'Thruster manager parameters not ' 62 'initialized for uuv_name=' +
66 self.
config = rospy.get_param(
'thruster_manager')
68 robot_description_param = self.
namespace+
'robot_description' 71 if rospy.has_param(robot_description_param):
73 self.
parse_urdf(rospy.get_param(robot_description_param))
75 if self.
config[
'update_rate'] < 0:
76 self.
config[
'update_rate'] = 50
82 tf_trans_ned_to_enu =
None 87 source =
'%sbase_link_ned' % self.
namespace 89 tf_trans_ned_to_enu = tf_buffer.lookup_transform(
90 target, source, rospy.Time(), rospy.Duration(1))
92 rospy.loginfo(
'No transform found between base_link and base_link_ned' 97 if tf_trans_ned_to_enu
is not None:
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]
107 'ThrusterManager::update_rate=' + str(self.
config[
'update_rate']))
110 rospy.set_param(
'thruster_manager/tf_prefix', self.
namespace)
115 if rospy.has_param(
'~output_dir'):
116 self.
output_dir = rospy.get_param(
'~output_dir')
118 raise rospy.ROSException(
119 'Invalid output directory, output_dir=' + self.
output_dir)
120 rospy.loginfo(
'output_dir=' + self.
output_dir)
133 if rospy.has_param(
'~tam'):
134 tam = rospy.get_param(
'~tam')
137 self.
n_thrusters = self.configuration_matrix.shape[1]
139 params = self.
config[
'conversion_fcn_params']
140 conv_fcn = self.
config[
'conversion_fcn']
141 if type(params) == list
and type(conv_fcn) == list:
143 raise rospy.ROSException(
'Lists conversion_fcn and ' 144 'conversion_fcn_params must have ' 145 'the same number of items as of ' 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,
155 thruster = Thruster.create_thruster(
156 conv_fcn[i], i, topic,
None,
None,
160 rospy.ROSException(
'Invalid thruster conversion ' 162 % self.
config[
'conversion_fcn'])
163 self.thrusters.append(thruster)
164 rospy.loginfo(
'Thruster allocation matrix provided!')
165 rospy.loginfo(
'TAM=')
170 raise rospy.ROSException(
'No thrusters found')
180 with open(join(self.
output_dir,
'TAM.yaml'),
'w')
as yaml_file:
183 dict(tam=self.configuration_matrix.tolist())))
185 rospy.loginfo(
'Invalid output directory for the TAM matrix, dir=' + str(self.
output_dir))
188 rospy.loginfo(
'ThrusterManager: ready')
191 root = etree.fromstring(urdf_str)
192 for joint
in root.findall(
'joint'):
193 if joint.get(
'type') ==
'fixed':
195 axis_str_list = joint.find(
'axis').get(
'xyz').split()
196 child = joint.find(
'child').get(
'link')
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])
206 """Calculate the thruster allocation matrix, if one is not given.""" 209 rospy.loginfo(
'TAM provided, skipping...')
210 rospy.loginfo(
'ThrusterManager: ready')
214 rospy.loginfo(
'ThrusterManager: updating thruster poses')
216 now = rospy.Time.now() + rospy.Duration(1.0)
222 equal_thrusters =
True 223 idx_thruster_model = 0
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 234 rospy.loginfo(
'conversion_fcn=' + str(self.
config[
'conversion_fcn']))
235 rospy.loginfo(
'conversion_fcn_params=' + str(self.
config[
'conversion_fcn_params']))
242 self.
config[
'thruster_frame_base'] + str(i)
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)
251 topic = self.
config[
'thruster_topic_prefix'] + str(i) + \
252 self.
config[
'thruster_topic_suffix']
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)
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(
271 i, topic, pos, quat, self.
axes[frame],
273 idx_thruster_model += 1
275 rospy.ROSException(
'Invalid thruster conversion ' 277 % self.
config[
'conversion_fcn'])
278 self.thrusters.append(thruster)
280 rospy.loginfo(
'could not get transform from: ' + base)
281 rospy.loginfo(
'to: ' + frame)
312 if self.
output_dir is not None and not recalculate:
313 with open(join(self.
output_dir,
'TAM.yaml'),
'w')
as yaml_file:
316 dict(tam=self.configuration_matrix.tolist())))
317 print 'TAM saved in <%s>' % join(self.
output_dir,
'TAM.yaml')
319 print 'Recalculate flag on, matrix will not be stored in TAM.yaml' 321 print 'Invalid output directory for the TAM matrix, dir=', self.
output_dir 324 print (
'ThrusterManager: ready')
328 """Publish the thruster input into their specific topic.""" 339 if frame_id
is not None:
340 if self.
config[
'base_link'] != frame_id:
342 ' base_link_ned to base_link could not be found' 343 if 'base_link_ned' not in self.
config[
'base_link']:
349 control_forces = numpy.dot(self.base_link_ned_to_enu.T,
351 control_torques = numpy.dot(self.base_link_ned_to_enu.T,
354 gen_forces = numpy.hstack(
355 (control_forces, control_torques)).transpose()
360 """Compute desired thruster forces using the inverse configuration 364 thrust = self.inverse_configuration_matrix.dot(gen_forces)
367 limitation_factor = 1.0
368 if type(self.
config[
'max_thrust']) == list:
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']
376 if abs(thrust[i]) > max_thrust[i]:
377 thrust[i] = numpy.sign(thrust[i]) * max_thrust[i]
def publish_thrust_forces(self, control_forces, control_torques, frame_id=None)
def command_thrusters(self)
def parse_urdf(self, urdf_str)
def update_tam(self, recalculate=False)
def compute_thruster_forces(self, gen_forces)
inverse_configuration_matrix