Public Member Functions | |
def | __init__ (self, source_pos, n_points, start_time) |
def | apply_constraints (self) |
def | get_contraints_filter (self) |
def | get_markers (self) |
def | get_point_cloud_as_msg (self) |
def | n_points (self) |
def | num_particles (self) |
def | points (self) |
def | reset_plume (self) |
def | set_n_points (self, n_points) |
def | set_plume_particles (self, t, x, y, z, time_creation) |
def | set_x_lim (self, min_value, max_value) |
def | set_y_lim (self, min_value, max_value) |
def | set_z_lim (self, min_value, max_value) |
def | source_pos (self) |
def | source_pos (self, new_pos) |
def | time_of_creation (self) |
def | update (self, t=0.0) |
def | update_current_vel (self, vel) |
def | x (self) |
def | x_lim (self) |
def | y (self) |
def | y_lim (self) |
def | z (self) |
def | z_lim (self) |
Static Public Member Functions | |
def | create_plume_model (tag, args) |
Static Public Attributes | |
string | LABEL = '' |
Private Attributes | |
_current_vel | |
_dt | |
_n_points | |
_pnts | |
_source_pos | |
_start_time | |
_t | |
_time_creation | |
_x_lim | |
_y_lim | |
_z_lim | |
Base class for plume model classes. Plume models should inherit this class and implement the update function to maintain a standard interface with the plume server. Each new inherited plume model must have an unique *LABEL* tag, since it will be used by the factory method to create plume models without the need to import all the plume model class files.
def uuv_plume_model.plume.Plume.__init__ | ( | self, | |
source_pos, | |||
n_points, | |||
start_time | |||
) |
Plume class constructor, abstract class for plume model classes. > **Parameters** * `source_pos` (*type:* `list`): 3D position of the plume source wrt ENU frame * `n_points` (*type:* `int`): maximum number of plume particles to be generated * `start_time (*type:* `float): time stamp of time of the creation of the plume model in seconds. This will be used to compute the relative time of creation of each particle
def uuv_plume_model.plume.Plume.apply_constraints | ( | self | ) |
|
static |
def uuv_plume_model.plume.Plume.get_contraints_filter | ( | self | ) |
Return a binary vector of $N$ elements, $N$ being current number of particles created. The $i$-th element is set to False if the $i$-th particle finds itself outside of the bounding box limits. > **Returns** Logical vector with elements set to *True* if they fulfill the constraints.
def uuv_plume_model.plume.Plume.get_markers | ( | self | ) |
Return a ROS marker array message structure with an sphere marker to represent the plume source, the bounding box and an arrow marker to show the direction of the current velocity if it's norm is greater than zero. > **Returns** `visualizaton_msgs/MarkerArray` message with markers for the current velocity arrow and source position or `None` if no plume particles are found.
def uuv_plume_model.plume.Plume.get_point_cloud_as_msg | ( | self | ) |
Return a ROS point cloud sensor message with the points representing the plume's particles and one channel containing the time of creation for each particle. > **Returns** The plume particles as a `sensor_msgs/PointCloud` message or `None` if no particles are found.
def uuv_plume_model.plume.Plume.n_points | ( | self | ) |
def uuv_plume_model.plume.Plume.num_particles | ( | self | ) |
def uuv_plume_model.plume.Plume.points | ( | self | ) |
def uuv_plume_model.plume.Plume.reset_plume | ( | self | ) |
def uuv_plume_model.plume.Plume.set_n_points | ( | self, | |
n_points | |||
) |
def uuv_plume_model.plume.Plume.set_plume_particles | ( | self, | |
t, | |||
x, | |||
y, | |||
z, | |||
time_creation | |||
) |
Set the plume particles with the input coordinates wrt ENU frame and time of creation vector in seconds. > **Parameters** * `t` (*type:* `float`): Current time stamp in seconds * `x` (*type:* `list`): List of X coordinates for the plume particles' positions * `y` (*type:* `list`): List of Y coordinates for the plume particles' positions * `z` (*type:* `list`): List of Z coordinates for the plume particles' positions * `time_creation`(*type:* `list`): List of the relative time of creation for each particle in seconds
def uuv_plume_model.plume.Plume.set_x_lim | ( | self, | |
min_value, | |||
max_value | |||
) |
Set the X limits for the plume bounding box. The bounding box is defined with respect to the ENU inertial frame. > **Parameters** * `min_value` (*type:* `float`): lower limit for the bounding box over the X axis. * `max_value` (*type:* `float`): upper limit for the bounding box over the X axis. > **Returns** `True` if limits are valid.
def uuv_plume_model.plume.Plume.set_y_lim | ( | self, | |
min_value, | |||
max_value | |||
) |
Set the Y limits for the plume bounding box. The bounding box is defined with respect to the ENU inertial frame. > **Parameters** * `min_value` (*type:* `float`): lower limit for the bounding box over the Y axis. * `max_value` (*type:* `float`): upper limit for the bounding box over the Y axis. > **Returns** `True` if limits are valid.
def uuv_plume_model.plume.Plume.set_z_lim | ( | self, | |
min_value, | |||
max_value | |||
) |
Set the Z limits for the plume bounding box. The bounding box is defined with respect to the ENU inertial frame. > **Parameters** * `min_value` (*type:* `float`): lower limit for the bounding box over the Z axis. * `max_value` (*type:* `float`): upper limit for the bounding box over the Z axis. > **Returns** `True` if limits are valid.
def uuv_plume_model.plume.Plume.source_pos | ( | self | ) |
def uuv_plume_model.plume.Plume.source_pos | ( | self, | |
new_pos | |||
) |
def uuv_plume_model.plume.Plume.time_of_creation | ( | self | ) |
def uuv_plume_model.plume.Plume.update | ( | self, | |
t = 0.0 |
|||
) |
def uuv_plume_model.plume.Plume.update_current_vel | ( | self, | |
vel | |||
) |
def uuv_plume_model.plume.Plume.x | ( | self | ) |
def uuv_plume_model.plume.Plume.x_lim | ( | self | ) |
def uuv_plume_model.plume.Plume.y | ( | self | ) |
def uuv_plume_model.plume.Plume.y_lim | ( | self | ) |
def uuv_plume_model.plume.Plume.z | ( | self | ) |
def uuv_plume_model.plume.Plume.z_lim | ( | self | ) |