Reactive navigation

These algorithms work with an occupancy grid representation of the world. Start and goal are specified by 2D \((x, y)\) coordinates in the plane.

class roboticstoolbox.mobile.Bug2(**kwargs)[source]

Bases: PlannerBase

Construct a Bug2 reactive navigator

Parameters:
  • occgrid (OccGrid instance or ndarray(N,M)) – occupancy grid

  • kwargs – common arguments for PlannerBase superclass

Returns:

Bug2 reactive navigator

Return type:

Bug2 instance

Creates an object which simulates an automaton, capable of omnidirectional motion, finding a path across an occupancy grid using only a bump sensor.

Reference:

“Path-Planning Strategies for a Point Mobile Automaton Moving Amidst Unknown Obstacles of Arbitrary Shape”, Lumelsky and Stepanov, Algorithmica (1987)2, pp.403-430

Note

This class is not a planner, even though it subclasses PlannerBase. It can produce very inefficient paths.

Author:

Kristian Gibson and Peter Corke, based on MATLAB version by Peter Corke

Seealso:

PlannerBase

property m_line

Get m-line

Returns:

m-line in homogeneous form

Return type:

ndarray(3)

This is the m-line computed for the last run().

run(start=None, goal=None, animate=False, pause=0.001, trail=True, movie=None, **kwargs)[source]

Find a path using Bug2 reactive navigation algorithm

Parameters:
  • start (array_like(2)) – starting position

  • goal (array_like(2)) – goal position

  • animate (bool, optional) – show animation of robot moving over the map, defaults to False

  • movie (str or tuple(str, float), optional) – save animation as a movie, defaults to None. Is either name of movie or a tuple (filename, frame interval)

  • trail – show the path followed by the robot, defaults to True

Returns:

path from start to goal

Return type:

ndarray(2,N)

Compute the path from start to goal assuming the robot is capable of 8-way motion from its current cell to the next.

Note

start and goal are given as (x,y) coordinates in the occupancy grid map, not as matrix row and column coordinates.

Seealso:

Bug2.plot()

plot_m_line(ls=None)[source]

Plot m-line

Parameters:

ls (str, optional) – linestyle, defaults to "k--"

Plots the m-line on the current axes.

__str__()

Compact representation of the planner

Returns:

pretty printed representation

Return type:

str

property goal

Set/get goal point or configuration (superclass)

Getter:

Return goal pointor configuration

Return type:

ndarray(2) or ndarray(3)

Setter:

Set goal point or configuration

Param:

array_like(2) or array_like(3)

The goal is either a point \((x, y)\) or a configuration \((x, y, \theta)\).

Seealso:

goal()

isoccupied(p)

Test if point is occupied (superclass)

Parameters:

p (array_like(2)) – world coordinate (x, y)

Returns:

occupancy status of corresponding grid cell

Return type:

bool

The world coordinate is transformed and the status of the occupancy grid cell is returned. If the point lies outside the bounds of the occupancy grid return True (obstacle)

If there is no occupancy grid this function always returns False (free).

Seealso:

occgrid() validate_endpoint() BinaryOccGrid.isoccupied()

message(s, color=None)

Print message to message channel

Parameters:
  • s (str) – message to print

  • color (str, optional) – color to print it, defaults to color specified at constructor time.

property occgrid

Occupancy grid

Returns:

occupancy grid used for planning

Return type:

OccGrid or subclass or None

Returns the occupancy grid that was optionally inflated at constructor time.

Seealso:

validate_endpoint() isoccupied()

plot(path=None, line=None, line_r=None, configspace=False, unwrap=True, direction=None, background=True, path_marker=None, path_marker_reverse=None, start_marker=None, goal_marker=None, start_vehicle=None, goal_vehicle=None, start=None, goal=None, ax=None, block=None, bgargs={}, **unused)

Plot vehicle path (superclass)

Parameters:
  • path ((N, 2) or ndarray(N, 3)) – path, defaults to None

  • direction (array_like(N), optional) – travel direction associated with each point on path, is either >0 or <0, defaults to None

  • line (sequence of dict of arguments for plot) – line style for forward motion, default is striped yellow on black

  • line_r (sequence of dict of arguments for plot) – line style for reverse motion, default is striped red on black

  • configspace (bool, optional) – plot the path in 3D configuration space, input must be 3xN. Start and goal style will be given by qstart_marker and qgoal_marker, defaults to False

  • unwrap (bool, optional) – for configuration space plot unwrap \(\theta\) so there are no discontinuities at \(\pm \pi\), defaults to True

  • background (bool, optional) – plot occupancy grid if present, default True

  • start_marker (dict, optional) – style for marking start point

  • goal_marker (dict, optional) – style for marking goal point

  • start_vehicle (dict) – style for vehicle animation object at start configuration

  • goal_vehicle (dict) – style for vehicle animation object at goal configuration

  • start (array_like(2) or array_like(3), optional) – start position \((x, y)\) or configuration \((x, y, \theta)\), defaults to value previously set

  • goal (array_like(2) or array_like(3), optional) – goal position \((x, y)\) or configuration \((x, y, \theta)\), defaults to value previously set

  • bgargs (dict, optional) – arguments passed to plot_bg(), defaults to None

  • ax (matplotlib axes) – axes to plot into

  • block (bool, optional) – block after displaying the plot

Plots the start and goal location/pose if they are specified by start or goal or were set by the object constructor or plan or query method.

If the start and goal have length 2, planning in \(\mathbb{R}^2\), then markers are drawn using styles specified by start_marker and end_marker which are dicts using Matplotlib keywords, for example:

planner.plot(path, start=dict(marker='s', color='b'))

If the start and goal have length 3, planning in \(\SE{2}\), and configspace is False, then direction-indicating markers are used to display start and goal configuration. These are also given as dicts but have two items: 'shape' which is the shape of the polygonal marker and is either 'triangle' or 'car'. The second item 'args' is passed to base.plot_poly() and Matplotlib and could have values such as filled=True or color.

If configspace is False then a 3D plot is created and the start and goal are indicated by Matplotlib markers specified by the dicts start_marker and end_marker

Default values are provided for all markers:

  • the start point is a circle

  • the goal point is a star

  • the start vehicle style is a VehiclePolygon(shape='car') as an unfilled outline

  • the goal vehicle style is a VehiclePolygon(shape='car') as a transparent filled shape

If background is True then the background of the plot is either or both of:

  • the occupancy grid

  • the distance field of the planner

Additional arguments bgargs can be passed through to plot_bg()

If path is specified it has one column per point and either 2 or 3 rows:

  • 2 rows describes motion in the \(xy\)-plane and a 2D plot is created

  • 3 rows describes motion in the \(xy\theta\)-configuration space. By default only the \(xy\)-plane is plotted unless configspace is True in which case motion in \(xy\theta\)-configuration space is shown as a 3D plot.

If the planner supports bi-directional motion then the direction option gives the direction for each point on the path.

Forward motion segments are drawn using style information from line while reverse motion segments are drawn using style information from line_r. These are each a sequence of dicts of Matplotlib plot options which can draw an arbitrary number of lines on top of each other. The default:

line = (
        {color:'black', linewidth:4},
        {color:'yellow', linewidth:3, dashes:(5,5)}
    )

will draw a blackline of width 4 with a dashed yellow line of width 3 plotted on top, giving a line of alternating black and yellow dashes.

Seealso:

plot_bg() base.plot_poly()

plot_bg(distance=None, cmap='gray', ax=None, inflated=True, colorbar=True, block=None, **unused)

Plot background (superclass)

Parameters:
  • distance (ndarray(N,M), optional) – override distance field, defaults to None

  • cmap (str or Colormap, optional) – Specify a colormap for the distance field, defaults to ‘gray’

Displays the background which is either the occupancy grid or a distance field. The distance field encodes the distance of a point from the goal, small distance is dark, a large distance is bright.

If the planner has an occupancy grid then that will be displayed with:
  • free cells in white

  • occupied cells in red

  • inflated occupied cells in pink

If distance is provided, or the planner has a distancemap attribute the the distance field will be used as the background and obstacle cells (actual or inflated) will be shown in red. A colorbar is added.

progress_end()

Finalize a progress bar (superclass)

Remove/cleanip a progress bar, for example:

planner.progress_start(100)
for i in range(100):
    # ...
    planner.progress_next()
planner.progress_end()
Seealso:

progress_start() progress_next()

progress_next()

Increment a progress bar (superclass)

Create a progress bar for an operation that has n steps, for example:

planner.progress_start(100)
for i in range(100):
    # ...
    planner.progress_next()
planner.progress_end()
Seealso:

progress_start() progress_end()

progress_start(n)

Initialize a progress bar (superclass)

Parameters:

n (int) – Number of iterations in the operation

Create a progress bar for an operation that has n steps, for example:

planner.progress_start(100)
for i in range(100):
    # ...
    planner.progress_next()
planner.progress_end()
Seealso:

progress_next() progress_end()

property random

Get private random number generator

Returns:

NumPy random number generator

Return type:

numpy.random.Generator

Has methods including:

The generator is initialized with the seed provided at constructor time.

Seealso:

numpy.random.default_rng()

random_init(seed=None)

Initialize private random number generator

Parameters:

seed (int) – random number seed, defaults to value given to constructor

The private random number generator is initialized. The seed is seed or the value given to the constructor. If None, the generator will be randomly seeded using a seed from the operating system.

property start

Set/get start point or configuration (superclass)

Getter:

Return start point or configuration

Return type:

ndarray(2) or ndarray(3)

Setter:

Set start point or configuration

Param:

array_like(2) or array_like(3)

The start is either a point \((x, y)\) or a configuration \((x, y, \theta)\).

Seealso:

goal()

validate_endpoint(p, dtype=None)

Validate start or goal point

Parameters:
  • p (array_like(2)) – the point

  • dtype (str, optional) – data type for point coordinates, defaults to None

Raises:

ValueError – point is inside obstacle

Returns:

point as a NumPy array of specified dtype

Return type:

ndarray(2)

The coordinate is tested to be a free cell in the occupancy grid.

Seealso:

isoccupied() occgrid()

property verbose

Get verbosity

Returns:

verbosity

Return type:

bool

If verbosity print more diagnostic messages to the planner’s message channel.