Public Member Functions | Static Public Attributes | Private Attributes | List of all members
uuv_thrusters.models.thruster_custom.ThrusterCustom Class Reference
Inheritance diagram for uuv_thrusters.models.thruster_custom.ThrusterCustom:
Inheritance graph
[legend]

Public Member Functions

def __init__ (self, args, kwargs)
 
def get_command_value (self, thrust)
 
def get_thrust_value (self, command)
 

Static Public Attributes

string LABEL = 'custom'
 

Private Attributes

 _input
 
 _output
 

Detailed Description

Class describing a custom conversion curve between the command input,
usually the angular velocity, and the correspondent output thrust force.
Here the inverse of the conversion function can be computed so that the
command for the desired thrust force is retrieved.
The input vector corresponds to sampled values for the command input, and
the output vector corresponds to the sampled values for the correspondent
thrust forces.
This information is usually available in the datasheet of the thruster's
manufacturer.

> *Input arguments*

* `index` (*type:* `int`): Thruster's ID.
* `topic` (*type:* `str`): Thruster's command topic.
* `pos` (*type:* `numpy.array` or `list`): Position vector 
of the thruster with respect to the vehicle's frame.
* `orientation` (*type:* `numpy.array` or `list`): Quaternion 
with the orientation of the thruster with respect to the vehicle's
frame as `(qx, qy, qz, qw)`.
* `axis` (*type:* `numpy.array`): Axis of rotation of the thruster.
* `input` (*type:* `list` or `numpy.array`): Vector samples of 
angular velocities to be interpolated with the vector samples
of thrust force output.
* `output` (*type:* `list` or `numpy.array`): Vector samples
of thrust force output.

Definition at line 20 of file thruster_custom.py.

Constructor & Destructor Documentation

def uuv_thrusters.models.thruster_custom.ThrusterCustom.__init__ (   self,
  args,
  kwargs 
)
Class constructor.

Definition at line 49 of file thruster_custom.py.

Member Function Documentation

def uuv_thrusters.models.thruster_custom.ThrusterCustom.get_command_value (   self,
  thrust 
)
Compute the angular velocity necessary 
for the desired thrust force.

> *Input arguments*

* `thrust` (*type:* `float`): Thrust force magnitude in N

> *Returns*

`float`: Angular velocity set-point for the thruster in rad/s 

Definition at line 60 of file thruster_custom.py.

def uuv_thrusters.models.thruster_custom.ThrusterCustom.get_thrust_value (   self,
  command 
)
Computes the thrust force for the given angular velocity
set-point.

> *Input arguments*

* `command` (*type:* `float`): Angular velocity set-point for 
the thruster in rad/s 

> *Returns*

`thrust` (*type:* `float`): Thrust force magnitude in N

Definition at line 74 of file thruster_custom.py.

Member Data Documentation

uuv_thrusters.models.thruster_custom.ThrusterCustom._input
private

Definition at line 56 of file thruster_custom.py.

uuv_thrusters.models.thruster_custom.ThrusterCustom._output
private

Definition at line 58 of file thruster_custom.py.

string uuv_thrusters.models.thruster_custom.ThrusterCustom.LABEL = 'custom'
static

Definition at line 47 of file thruster_custom.py.


The documentation for this class was generated from the following file:


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