Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator Class Reference
Inheritance diagram for uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator:
Inheritance graph
[legend]

Public Member Functions

def __init__ (self)
 
def generate_pnt (self, s, t, args)
 
def generate_pos (self, s)
 
def generate_quat (self, s)
 
def get_samples (self, max_time, step=0.001)
 
def init_interpolator (self)
 
def set_parameters (self, params)
 

Static Public Attributes

string LABEL = 'dubins'
 

Private Member Functions

def _compute_u (self, angle, delta, heading)
 
def _generate_path (self, wp_init, heading_init, wp_final, heading_final)
 
def _get_2d_dubins_path (self, center_1, radius_1, heading_1, delta_1, center_2, radius_2, heading_2, delta_2)
 
def _get_center (self, side, y_vec, wp)
 
def _get_circle (self, u, center, radius, delta, heading)
 
def _get_circle_marker (self, center, radius, heading, delta, frame_id, circle_color=[0)
 
def _get_circles_center_pos (self, waypoint, heading, radius=None)
 
def _get_distance (self, pnt_1, pnt_2)
 
def _get_frame (self, heading)
 
def _get_phi (self, u, delta, heading)
 
def _get_tangent (self, u, delta, radius, heading)
 

Private Attributes

 _duration
 
 _interp_fcns
 
 _last_rot
 
 _logger
 
 _marker_id
 
 _markers_msg
 
 _max_pitch_angle
 
 _radius
 
 _s
 
 _start_time
 

Detailed Description

3D Dubins path interpolator implemented based on the sources 
below.

!!! note

    Owen, Mark, Randal W. Beard, and Timothy W. McLain. 
    "Implementing Dubins Airplane Paths on Fixed-Wing UAVs."
    Handbook of Unmanned Aerial Vehicles (2014): 1677-1701.

    Cai, Wenyu, Meiyan Zhang, and Yahong Zheng. "Task Assignment
    and Path Planning for Multiple Autonomous Underwater Vehicles
    Using 3D Dubins Curves." Sensors 17.7 (2017):1607.

    Hansen, Karl D., and Anders La Cour-Harbo. "Waypoint Planning
    with Dubins Curves Using Genetic Algorithms." 2016 European
    Control Conference (ECC) (2016).

    Lin, Yucong, and Srikanth Saripalli. "Path Planning Using
    3D Dubins Curve for Unmanned Aerial Vehicles." 2014 
    International Conference on Unmanned Aircraft Systems (ICUAS)
    (2014).

Definition at line 33 of file dubins_interpolator.py.

Constructor & Destructor Documentation

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator.__init__ (   self)

Definition at line 58 of file dubins_interpolator.py.

Member Function Documentation

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._compute_u (   self,
  angle,
  delta,
  heading 
)
private
Compute the parametric input for the circle path.

> *Input arguments*

* `angle` (*type:* `float`): Angle in the circle's path
in radians
* `delta` (*type:* `int`): Generate the points in counter-clockwise
direction if `delta` is -1 and clockwise if `delta` is 1
* `heading` (*type:* `float`): Heading offset angle in radians

> *Returns*

`float`: Circle's parametric variable

Definition at line 206 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._generate_path (   self,
  wp_init,
  heading_init,
  wp_final,
  heading_final 
)
private

Definition at line 577 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._get_2d_dubins_path (   self,
  center_1,
  radius_1,
  heading_1,
  delta_1,
  center_2,
  radius_2,
  heading_2,
  delta_2 
)
private
Compute the 2D Dubins path algorithm. It computes the shortest curve
that connects two points. Given two circles which are tangent to the
origin and target waypoints, with a chosen heading to depart the first
and reach the second, find the path that will be first tangent
on circle tangent to the first waypoint, travel to towards the
second in a straight line and reach the closest tangent on the
circle around the second waypoint.

> *Input arguments*

* `center_1` (*type:* `numpy.array`): 2D center of the circle tangent to 
the origin waypoint.
* `radius_1` (*type:* `float`): Radius of the circle related to the origin
waypoint in meters
* `heading_1` (*type:* `float`): Desired heading associated to the origin 
waypoint
* `delta_1` (*type:* `int`): Direction to travel around the circle, -1 for
counter-clockwise and 1 for clockwise
* `center_2` (*type:* `numpy.array`): 2D center of the circle tangent to 
the target waypoint.
* `radius_2` (*type:* `float`): Radius of the circle related to the target
waypoint in meters
* `heading_2` (*type:* `float`): Desired heading associated to the target 
waypoint
* `delta_2` (*type:* `int`): Direction to travel around the circle, -1 for
counter-clockwise and 1 for clockwise

> *Returns*

Description of return values

Definition at line 261 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._get_center (   self,
  side,
  y_vec,
  wp 
)
private

Definition at line 515 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._get_circle (   self,
  u,
  center,
  radius,
  delta,
  heading 
)
private
Compute the 2D coordinates for a circle.

> *Input arguments*

* `u` (*type:* `float`): Parametric variable in interval [0, 1]
* `center` (*type:* `numpy.array`): Center of the circle in meters
* `radius` (*type:* `float`): Radius of the circle in meters
* `delta` (*type:* `int`): Generate the points in counter-clockwise
direction if `delta` is -1 and clockwise if `delta` is 1
* `heading` (*type:* `float`): Heading associated to the waypoint

> *Returns*

Circle coordinates as `numpy.array`.

Definition at line 242 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._get_circle_marker (   self,
  center,
  radius,
  heading,
  delta,
  frame_id,
  circle_color = [0 
)
private

Definition at line 522 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._get_circles_center_pos (   self,
  waypoint,
  heading,
  radius = None 
)
private
Return the centers of the circles on the left and right of the 
waypoint with respect to the direction described the desired heading.

> *Input arguments*

* `waypoint` (*type:* `uuv_wapoints.Waypoint`): Waypoint
* `heading` (*type:* `float`): Desired heading in radians
* `radius` (*type:* `float`, *default:* `None`): Desired radius for the
circles. If `None` is provided, then the internal radius will be used.

> *Returns*

`dict` with the left `L` and right `R` center of the circles as `numpy.array`

Definition at line 172 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._get_distance (   self,
  pnt_1,
  pnt_2 
)
private
Compute the distance between two points.

> *Input arguments*

* `pnt_1` (*type:* `numpy.array`): Point 1
* `pnt_2` (*type:* `numpy.array`): Point 2

> *Returns*

`float`: Distance between points

Definition at line 158 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._get_frame (   self,
  heading 
)
private
Return the 2D rotation matrix for a desired heading. 

> *Input arguments*

* `heading` (*type:* `float`): Heading angle in radians 

> *Returns*

`numpy.array`: 2D rotation matrix

Definition at line 145 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._get_phi (   self,
  u,
  delta,
  heading 
)
private

Definition at line 203 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._get_tangent (   self,
  u,
  delta,
  radius,
  heading 
)
private
Function description

> *Input arguments*

* `param` (*type:* `data_type`, *default:* `data`): Parameter description

> *Returns*

Description of return values

Definition at line 226 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator.generate_pnt (   self,
  s,
  t,
  args 
)
Compute a point that belongs to the path on the 
interpolated space related to `s`, `s` being represented 
in the curve's parametric space.

> *Input arguments*

* `s` (*type:* `float`): Curve's parametric input expressed in the 
interval of [0, 1]
* `t` (*type:* `float`): Trajectory point's timestamp

> *Returns*

`uuv_trajectory_generator.TrajectoryPoint` including position
and quaternion vectors.

Definition at line 781 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator.generate_pos (   self,
  s 
)
Generate a position vector for the path sampled point
interpolated on the position related to `s`, `s` being  
represented in the curve's parametric space.

> *Input arguments*

* `s` (*type:* `float`): Curve's parametric input expressed in the 
interval of [0, 1]

> *Returns*

3D position vector as a `numpy.array`.

Definition at line 756 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator.generate_quat (   self,
  s 
)
Compute the quaternion of the path reference for a interpolated
point related to `s`, `s` being represented in the curve's parametric 
space.
The quaternion is computed assuming the heading follows the direction
of the path towards the target. Roll and pitch can also be computed 
in case the `full_dof` is set to `True`.

> *Input arguments*

* `s` (*type:* `float`): Curve's parametric input expressed in the 
interval of [0, 1]

> *Returns*

Rotation quaternion as a `numpy.array` as `(x, y, z, w)`

Definition at line 806 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator.get_samples (   self,
  max_time,
  step = 0.001 
)
Sample the full path for position and quaternion vectors.
`step` is represented in the path's parametric space.

> *Input arguments*

* `step` (*type:* `float`, *default:* `0.001`): Parameter description

> *Returns*

List of `uuv_trajectory_generator.TrajectoryPoint`.

Definition at line 730 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator.init_interpolator (   self)
Initialize the interpolator. To have the path segments generated,
`init_waypoints()` must be called beforehand by providing a set of 
waypoints as `uuv_waypoints.WaypointSet` type. 

> *Returns*

`bool`: `True` if the path segments were successfully generated.

Definition at line 66 of file dubins_interpolator.py.

def uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator.set_parameters (   self,
  params 
)
Set interpolator's parameters. All the options
for the `params` input can be seen below:

```python
params=dict(
    radius=0.0,
    max_pitch=0.0
    ) 
```

* `radius` (*type:* `float`): Turning radius
* `max_pitch` (*type:* `float`): Max. pitch angle allowed 
between two waypoints. If the pitch exceeds `max_pitch`, a
helical path is computed to perform steep climbs or dives.

> *Input arguments*

* `params` (*type:* `dict`): `dict` containing interpolator's
configurable elements.

Definition at line 701 of file dubins_interpolator.py.

Member Data Documentation

uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._duration
private

Definition at line 139 of file dubins_interpolator.py.

uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._interp_fcns
private

Definition at line 63 of file dubins_interpolator.py.

uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._last_rot
private

Definition at line 827 of file dubins_interpolator.py.

uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._logger
private

Definition at line 64 of file dubins_interpolator.py.

uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._marker_id
private

Definition at line 84 of file dubins_interpolator.py.

uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._markers_msg
private

Definition at line 83 of file dubins_interpolator.py.

uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._max_pitch_angle
private

Definition at line 62 of file dubins_interpolator.py.

uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._radius
private

Definition at line 61 of file dubins_interpolator.py.

uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._s
private

Definition at line 134 of file dubins_interpolator.py.

uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator._start_time
private

Definition at line 141 of file dubins_interpolator.py.

string uuv_trajectory_generator.path_generator.dubins_interpolator.DubinsInterpolator.LABEL = 'dubins'
static

Definition at line 56 of file dubins_interpolator.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