thruster_custom.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 import rospy
17 import numpy
18 from thruster import Thruster
19 
20 
21 class ThrusterCustom(Thruster):
22  """Class describing a custom conversion curve between the command input,
23  usually the angular velocity, and the correspondent output thrust force.
24  Here the inverse of the conversion function can be computed so that the
25  command for the desired thrust force is retrieved.
26  The input vector corresponds to sampled values for the command input, and
27  the output vector corresponds to the sampled values for the correspondent
28  thrust forces.
29  This information is usually available in the datasheet of the thruster's
30  manufacturer.
31  """
32  LABEL = 'custom'
33 
34  def __init__(self, *args, **kwargs):
35  """Class constructor."""
36  super(ThrusterCustom, self).__init__(*args)
37 
38  if 'input' not in kwargs or 'output' not in kwargs:
39  rospy.ROSException('Thruster input/output sample points not given')
40  # Vector of sample values for each angular velocity
41  self._input = kwargs['input']
42  # Vector of sample values for each thrust force relative to the input
43  self._output = kwargs['output']
44 
45  def get_command_value(self, thrust):
46  # Compute the angular velocity necessary for the desired thrust force
47  return numpy.interp(thrust, self._output, self._input)
48 
49  def get_thrust_value(self, command):
50  """Computes the thrust force for the given command."""
51  return numpy.interp(command, self._input, self._output)


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