17 from .thruster
import 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 28 This information is usually available in the datasheet of the thruster's 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. 50 """Class constructor.""" 51 super(ThrusterCustom, self).
__init__(*args)
53 if 'input' not in kwargs
or 'output' not in kwargs:
54 rospy.ROSException(
'Thruster input/output sample points not given')
61 """Compute the angular velocity necessary 62 for the desired thrust force. 66 * `thrust` (*type:* `float`): Thrust force magnitude in N 70 `float`: Angular velocity set-point for the thruster in rad/s 75 """Computes the thrust force for the given angular velocity 80 * `command` (*type:* `float`): Angular velocity set-point for 85 `thrust` (*type:* `float`): Thrust force magnitude in N
def __init__(self, args, kwargs)
def get_thrust_value(self, command)
def get_command_value(self, thrust)