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 | |
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.
def uuv_thrusters.models.thruster.Thruster.__init__ | ( | self, | |
index, | |||
topic, | |||
pos, | |||
orientation, | |||
axis = DEFAULT_AXIS |
|||
) |
Definition at line 40 of file thruster.py.
|
private |
Convert the desired thrust force into angular velocity command according using a gain.
Definition at line 112 of file thruster.py.
|
private |
Definition at line 117 of file thruster.py.
|
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.
|
private |
Definition at line 55 of file thruster.py.
|
private |
Definition at line 57 of file thruster.py.
|
private |
Definition at line 45 of file thruster.py.
|
private |
Definition at line 41 of file thruster.py.
|
private |
Definition at line 44 of file thruster.py.
|
private |
Definition at line 43 of file thruster.py.
|
private |
Definition at line 56 of file thruster.py.
|
private |
Definition at line 42 of file thruster.py.
|
static |
Definition at line 38 of file thruster.py.
|
static |
Definition at line 37 of file thruster.py.