thruster_custom.py
Go to the documentation of this file.
1 # Copyright (c) 2016-2019 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 import rospy
16 import numpy
17 from .thruster import Thruster
18 
19 
20 class ThrusterCustom(Thruster):
21  """Class describing a custom conversion curve between the command input,
22  usually the angular velocity, and the correspondent output thrust force.
23  Here the inverse of the conversion function can be computed so that the
24  command for the desired thrust force is retrieved.
25  The input vector corresponds to sampled values for the command input, and
26  the output vector corresponds to the sampled values for the correspondent
27  thrust forces.
28  This information is usually available in the datasheet of the thruster's
29  manufacturer.
30 
31  > *Input arguments*
32 
33  * `index` (*type:* `int`): Thruster's ID.
34  * `topic` (*type:* `str`): Thruster's command topic.
35  * `pos` (*type:* `numpy.array` or `list`): Position vector
36  of the thruster with respect to the vehicle's frame.
37  * `orientation` (*type:* `numpy.array` or `list`): Quaternion
38  with the orientation of the thruster with respect to the vehicle's
39  frame as `(qx, qy, qz, qw)`.
40  * `axis` (*type:* `numpy.array`): Axis of rotation of the thruster.
41  * `input` (*type:* `list` or `numpy.array`): Vector samples of
42  angular velocities to be interpolated with the vector samples
43  of thrust force output.
44  * `output` (*type:* `list` or `numpy.array`): Vector samples
45  of thrust force output.
46  """
47  LABEL = 'custom'
48 
49  def __init__(self, *args, **kwargs):
50  """Class constructor."""
51  super(ThrusterCustom, self).__init__(*args)
52 
53  if 'input' not in kwargs or 'output' not in kwargs:
54  rospy.ROSException('Thruster input/output sample points not given')
55  # Vector of sample values for each angular velocity
56  self._input = kwargs['input']
57  # Vector of sample values for each thrust force relative to the input
58  self._output = kwargs['output']
59 
60  def get_command_value(self, thrust):
61  """Compute the angular velocity necessary
62  for the desired thrust force.
63 
64  > *Input arguments*
65 
66  * `thrust` (*type:* `float`): Thrust force magnitude in N
67 
68  > *Returns*
69 
70  `float`: Angular velocity set-point for the thruster in rad/s
71  """
72  return numpy.interp(thrust, self._output, self._input)
73 
74  def get_thrust_value(self, command):
75  """Computes the thrust force for the given angular velocity
76  set-point.
77 
78  > *Input arguments*
79 
80  * `command` (*type:* `float`): Angular velocity set-point for
81  the thruster in rad/s
82 
83  > *Returns*
84 
85  `thrust` (*type:* `float`): Thrust force magnitude in N
86  """
87  return numpy.interp(command, self._input, self._output)


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