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

Public Member Functions

def __init__ (self, index, topic, pos, orientation, axis=DEFAULT_AXIS)
 
def get_command_value (self, thrust)
 
def get_curve (self, min_value, max_value, n_points)
 
def get_thrust_value (self, command)
 
def index (self)
 
def publish_command (self, thrust)
 
def tam_column (self)
 
def topic (self)
 

Static Public Member Functions

def create_thruster (model_name, args, kwargs)
 

Static Public Attributes

 DEFAULT_AXIS = numpy.array([1, 0, 0, 0])
 
string LABEL = ''
 

Private Member Functions

def _calc_command (self)
 
def _update (self, thrust)
 

Private Attributes

 _command
 
 _command_pub
 
 _force_dist
 
 _index
 
 _orientation
 
 _pos
 
 _thrust
 
 _topic
 

Detailed Description

Abstract function to all the thruster models avaialble. 
The instance of a thruster model must use the factory method.

> *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.

Definition at line 22 of file thruster.py.

Constructor & Destructor Documentation

def uuv_thrusters.models.thruster.Thruster.__init__ (   self,
  index,
  topic,
  pos,
  orientation,
  axis = DEFAULT_AXIS 
)

Definition at line 40 of file thruster.py.

Member Function Documentation

def uuv_thrusters.models.thruster.Thruster._calc_command (   self)
private
Convert the desired thrust force into angular velocity 
command according using a gain.

Definition at line 112 of file thruster.py.

def uuv_thrusters.models.thruster.Thruster._update (   self,
  thrust 
)
private

Definition at line 117 of file thruster.py.

def uuv_thrusters.models.thruster.Thruster.create_thruster (   model_name,
  args,
  kwargs 
)
static
Factory method for the thruster models.

> *Input arguments*

* `model_name` (*type:* `str`): Name identifier of
the thruster model.

> *Returns*

Thruster model instance.

Definition at line 76 of file thruster.py.

def uuv_thrusters.models.thruster.Thruster.get_command_value (   self,
  thrust 
)
Convert desired thrust force to input command according to this
function. Overwrite this method to implement custom models.

Definition at line 93 of file thruster.py.

def uuv_thrusters.models.thruster.Thruster.get_curve (   self,
  min_value,
  max_value,
  n_points 
)
Sample the conversion curve and return the values.

Definition at line 102 of file thruster.py.

def uuv_thrusters.models.thruster.Thruster.get_thrust_value (   self,
  command 
)
Computes the thrust force for the given command.

Definition at line 98 of file thruster.py.

def uuv_thrusters.models.thruster.Thruster.index (   self)

Definition at line 64 of file thruster.py.

def uuv_thrusters.models.thruster.Thruster.publish_command (   self,
  thrust 
)
Publish the thrust force command set-point
to a thruster unit.

> *Input arguments*

* `thrust` (*type:* `float`): Thrust force set-point
in N.

Definition at line 121 of file thruster.py.

def uuv_thrusters.models.thruster.Thruster.tam_column (   self)

Definition at line 72 of file thruster.py.

def uuv_thrusters.models.thruster.Thruster.topic (   self)

Definition at line 68 of file thruster.py.

Member Data Documentation

uuv_thrusters.models.thruster.Thruster._command
private

Definition at line 55 of file thruster.py.

uuv_thrusters.models.thruster.Thruster._command_pub
private

Definition at line 57 of file thruster.py.

uuv_thrusters.models.thruster.Thruster._force_dist
private

Definition at line 45 of file thruster.py.

uuv_thrusters.models.thruster.Thruster._index
private

Definition at line 41 of file thruster.py.

uuv_thrusters.models.thruster.Thruster._orientation
private

Definition at line 44 of file thruster.py.

uuv_thrusters.models.thruster.Thruster._pos
private

Definition at line 43 of file thruster.py.

uuv_thrusters.models.thruster.Thruster._thrust
private

Definition at line 56 of file thruster.py.

uuv_thrusters.models.thruster.Thruster._topic
private

Definition at line 42 of file thruster.py.

uuv_thrusters.models.thruster.Thruster.DEFAULT_AXIS = numpy.array([1, 0, 0, 0])
static

Definition at line 38 of file thruster.py.

string uuv_thrusters.models.thruster.Thruster.LABEL = ''
static

Definition at line 37 of file thruster.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