Public Member Functions | Public Attributes | Static Public Attributes | Private Attributes | List of all members
uuv_waypoints.waypoint_set.WaypointSet Class Reference
Inheritance diagram for uuv_waypoints.waypoint_set.WaypointSet:
Inheritance graph
[legend]

Public Member Functions

def __init__ (self, scale=0.1, inertial_frame_id='world', max_surge_speed=None)
 
def __str__ (self)
 
def add_waypoint (self, waypoint, add_to_beginning=False)
 
def add_waypoint_from_msg (self, msg)
 
def clear_waypoints (self)
 
def dist_to_waypoint (self, pos, index=0)
 
def export_to_file (self, path, filename)
 
def from_message (self, msg)
 
def generate_circle (self, radius, center, num_points, max_forward_speed, theta_offset=0.0, heading_offset=0.0, append=False)
 
def generate_helix (self, radius, center, num_points, max_forward_speed, delta_z, num_turns, theta_offset=0.0, heading_offset=0.0, append=False)
 
def get_last_waypoint (self)
 
def get_radius_of_acceptance (self, index)
 
def get_start_waypoint (self)
 
def get_waypoint (self, index)
 
def inertial_frame_id (self)
 
def inertial_frame_id (self, frame_id)
 
def is_empty (self)
 
def num_waypoints (self)
 
def read_from_file (self, filename)
 
def remove_waypoint (self, waypoint)
 
def set_constraint_status (self, index, flag)
 
def set_radius_of_acceptance (self, index, radius)
 
def to_marker_list (self, clear=False)
 
def to_message (self)
 
def to_path_marker (self, clear=False)
 
def x (self)
 
def y (self)
 
def z (self)
 

Public Attributes

 inertial_frame_id
 
 num_waypoints
 

Static Public Attributes

list FAILED_WAYPOINT = [1.0, 0.0, 0.0]
 
list FINAL_WAYPOINT_COLOR = [1.0, 0.5737, 0.0]
 
list OK_WAYPOINT = [31. / 255, 106. / 255, 226. / 255]
 

Private Attributes

 _inertial_frame_id
 
 _max_surge_speed
 
 _scale
 
 _violates_constraint
 
 _waypoints
 

Detailed Description

Set of waypoints.

> *Attributes*

* `FINAL_WAYPOINT_COLOR` (*type:* list of `float`, *value:* `[1.0, 0.5737, 0.0]`): RGB color for marker of the final waypoint in RViz
* `OK_WAYPOINT` (*type:* list of `float`, *value:* `[0.1216, 0.4157, 0.8863]`): RGB color for marker of a successful waypoint in RViz
* `FAILED_WAYPOINT` (*type:* list of `float`, *value:* `[1.0, 0.0, 0.0]`): RGB color for marker of a failed waypoint in RViz

> *Input arguments*

* `scale` (*type:* `float`, *default:* `0.1`): Scale of the spherical marker for waypoints
* `inertial_frame_id` (*type:* `str`, *default:* `'world'`): Name of the inertial reference frame, options are `world` and `world_ned` for `ENU` and `NED` inertial reference frames, respectively
* `max_surge_speed` (*type:* `float`, *default:* `None`): Max. surge speed in m/s associated with each waypoint

Definition at line 27 of file waypoint_set.py.

Constructor & Destructor Documentation

def uuv_waypoints.waypoint_set.WaypointSet.__init__ (   self,
  scale = 0.1,
  inertial_frame_id = 'world',
  max_surge_speed = None 
)

Definition at line 47 of file waypoint_set.py.

Member Function Documentation

def uuv_waypoints.waypoint_set.WaypointSet.__str__ (   self)

Definition at line 55 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.add_waypoint (   self,
  waypoint,
  add_to_beginning = False 
)
Add a waypoint to the set

> *Input arguments*

* `waypoint` (*type:* `uuv_waypoints.Waypoint`): Waypoint object
* `add_to_beginning` (*type:* `bool`, *default:* `False`): If `True`, add the waypoint to the beginning of the list.

> *Returns*

`True` if waypoint was added to the set. `False` if a repeated waypoint is already found in the set.

Definition at line 142 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.add_waypoint_from_msg (   self,
  msg 
)
Add waypoint from ROS `uuv_control_msgs/Waypoint` message

> *Input arguments*

* `msg` (*type:* `uuv_control_msgs/Waypoint`): Waypoint message

> *Returns*

`True`, if waypoint could be added to set, `False`, otherwise.

Definition at line 170 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.clear_waypoints (   self)
Clear the list of waypoints

Definition at line 106 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.dist_to_waypoint (   self,
  pos,
  index = 0 
)
Compute the distance of a waypoint in the set to point 

> *Input arguments*

* `pos` (*type:* list of `float`): 3D point as a list of coordinates
* `index` (*type:* `int`, *default:* `0`): Waypoint index in set

> *Returns*

Distance between `pos` and the waypoint in `index`. `None` if waypoint set is empty.

Definition at line 329 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.export_to_file (   self,
  path,
  filename 
)
Export waypoint set to YAML file.

> *Input arguments*

* `path` (*type:* `str`): Path to the folder containing the file
* `filename` (*type:* `str`): Name of the YAML file.

> *Returns*

`True` is waypoints could be exported to file. `False`, otherwise.

Definition at line 272 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.from_message (   self,
  msg 
)
Convert `uuv_control_msgs/WaypointSet` message into `uuv_waypoints.WaypointSet`

> *Input arguments*

* `msg` (*type:* `uuv_control_msgs/WaypointSet` object): Waypoint set message

Definition at line 317 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.generate_circle (   self,
  radius,
  center,
  num_points,
  max_forward_speed,
  theta_offset = 0.0,
  heading_offset = 0.0,
  append = False 
)
Generate a set of waypoints describing a circle

> *Input arguments*

* `radius` (*type:* `float`): Radius of the circle in meters
* `num_points` (*type:* `int`): Number of waypoints to be generated
* `max_forward_speed` (*type:* `float`): Max. forward speed set to each waypoint in m/s
* `theta_offset` (*type:* `float`, *default:* `0`): Angle offset to start generating the waypoints in radians
* `heading_offset` (*type:* `float`, *default:* `0`): Heading offset set to the reference heading of the vehicle in radians
* `append` (*type:* `bool`, *default:* `False`): If `True`, append the generated waypoints to the existent waypoints in the set

> *Returns*

`True` if the circle was successfully generated, `False`, otherwise

Definition at line 452 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.generate_helix (   self,
  radius,
  center,
  num_points,
  max_forward_speed,
  delta_z,
  num_turns,
  theta_offset = 0.0,
  heading_offset = 0.0,
  append = False 
)
Generate a set of waypoints describing a helix

> *Input arguments*

* `radius` (*type:* `float`): Radius of the circle in meters
* `num_points` (*type:* `int`): Number of waypoints to be generated
* `max_forward_speed` (*type:* `float`): Max. forward speed set to each waypoint in m/s
* `delta_z` (*type:* `float`): Step in the Z direction for each lap of the helix in meters
* `theta_offset` (*type:* `float`, *default:* `0`): Angle offset to start generating the waypoints in radians
* `heading_offset` (*type:* `float`, *default:* `0`): Heading offset set to the reference heading of the vehicle in radians
* `append` (*type:* `bool`, *default:* `False`): If `True`, append the generated waypoints to the existent waypoints in the set

> *Returns*

`True` if the circle was successfully generated, `False`, otherwise

Definition at line 497 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.get_last_waypoint (   self)
Return the final waypoint

> *Returns*

A `uuv_waypoints.Waypoint` object or None, if the list of waypoints is empty.

Definition at line 197 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.get_radius_of_acceptance (   self,
  index 
)
Return the radius of acceptance for a waypoint

> *Input arguments*

* `index` (*type:* `int`): Index of the waypoint

> *Returns*

Radius of acceptance for the waypoint in position 
given by `index` as a `float`. `None` if waypoint
set is empty.

Definition at line 359 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.get_start_waypoint (   self)
Return the starting waypoint

> *Returns*

A `uuv_waypoints.Waypoint` object or None, if the list of waypoints is empty.

Definition at line 185 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.get_waypoint (   self,
  index 
)
Return a waypoint

> *Input arguments*

* `index` (*type:* `int`): Index of the waypoint

> *Returns*

Return a waypoint as `uuv_waypoints.Waypoint` or `None` if `index` is outside of range.

Definition at line 127 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.inertial_frame_id (   self)
`str`: Name of inertial reference frame

Definition at line 96 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.inertial_frame_id (   self,
  frame_id 
)

Definition at line 101 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.is_empty (   self)
`bool`: True if the list of waypoints is empty

Definition at line 91 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.num_waypoints (   self)
`int`: Number of waypoints

Definition at line 71 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.read_from_file (   self,
  filename 
)
Read waypoint set from a YAML file.

> *Input arguments*

* `filename` (*type:* `str`): Filename of the waypoint set

> *Returns*

`True` if waypoint set file could be parsed, `False`, otherwise.

Definition at line 222 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.remove_waypoint (   self,
  waypoint 
)
Remove waypoint from set.

> *Input arguments*

* `waypoint` (*type:* `uuv_waypoints.Waypoint`): Waypoint object

Definition at line 208 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.set_constraint_status (   self,
  index,
  flag 
)
Set the flag violates_constraint to a waypoint

> *Input arguments*

* `index` (*type:* `int`): Index of the waypoints
* `flag` (*type:* `bool`): True, if waypoint violates a constraint

> *Returns*

`True` if successful, and `False` if the waypoint `index` is outsite of the list's range.

Definition at line 110 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.set_radius_of_acceptance (   self,
  index,
  radius 
)
Set the radius of acceptance around each waypoint 
inside which a vehicle is considered to have reached 
a waypoint. 

> *Input arguments*

* `index` (*type:* `int`): Index of the waypoint
* `radius` (*type:* `float`): Radius of the sphere representing the volume of acceptance 

Definition at line 346 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.to_marker_list (   self,
  clear = False 
)
Return waypoint set as a markers list message of type `visualization_msgs/MarkerArray`

> *Input arguments*

* `clear` (*type:* `bool`, *default:* `False`): Return an empty marker array message

> *Returns*

`visualization_msgs/MarkerArray` message

Definition at line 404 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.to_message (   self)
Convert waypoints set to message `uuv_control_msgs/WaypointSet`

> *Returns*

`uuv_control_msgs/WaypointSet` message object

Definition at line 300 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.to_path_marker (   self,
  clear = False 
)
Return a `nav_msgs/Path` message with all waypoints in the set

> *Input arguments*

* `clear` (*type:* `bool`, *default:* `False`): Return an empty `nav_msgs/Path` message.

> *Returns*

`nav_msgs/Path` message

Definition at line 377 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.x (   self)
`list`: List of the X-coordinates of all waypoints

Definition at line 76 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.y (   self)
`list`: List of the Y-coordinates of all waypoints

Definition at line 81 of file waypoint_set.py.

def uuv_waypoints.waypoint_set.WaypointSet.z (   self)
`list`: List of the Z-coordinates of all waypoints

Definition at line 86 of file waypoint_set.py.

Member Data Documentation

uuv_waypoints.waypoint_set.WaypointSet._inertial_frame_id
private

Definition at line 52 of file waypoint_set.py.

uuv_waypoints.waypoint_set.WaypointSet._max_surge_speed
private

Definition at line 53 of file waypoint_set.py.

uuv_waypoints.waypoint_set.WaypointSet._scale
private

Definition at line 51 of file waypoint_set.py.

uuv_waypoints.waypoint_set.WaypointSet._violates_constraint
private

Definition at line 50 of file waypoint_set.py.

uuv_waypoints.waypoint_set.WaypointSet._waypoints
private

Definition at line 49 of file waypoint_set.py.

list uuv_waypoints.waypoint_set.WaypointSet.FAILED_WAYPOINT = [1.0, 0.0, 0.0]
static

Definition at line 45 of file waypoint_set.py.

list uuv_waypoints.waypoint_set.WaypointSet.FINAL_WAYPOINT_COLOR = [1.0, 0.5737, 0.0]
static

Definition at line 43 of file waypoint_set.py.

uuv_waypoints.waypoint_set.WaypointSet.inertial_frame_id

Definition at line 325 of file waypoint_set.py.

uuv_waypoints.waypoint_set.WaypointSet.num_waypoints

Definition at line 417 of file waypoint_set.py.

list uuv_waypoints.waypoint_set.WaypointSet.OK_WAYPOINT = [31. / 255, 106. / 255, 226. / 255]
static

Definition at line 44 of file waypoint_set.py.


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


uuv_trajectory_control
Author(s):
autogenerated on Thu Jun 18 2020 03:28:42