HybridPlanner¶
Module¶
The HybridPlanner module supports a combined path planning by taking into account a Road Map as well as a Grid Map. It automatically chooses to drive on the Road Map when possible, only to fall back to Grid Map based navigation if needed. As such it supports different ways to specify a goal, either by station name, by providing a modified station structure or by specifying an arbitrary pose.
Multiple goals can be specified, in which case the goals are traversed one after the other, without waiting or stopping at intermediate goals.
Most functions require permission pilot.permission_e.MOVE
, see pilot.permission_e.
Functions¶
Common Parameters¶
goal_options_t options
Optional goal options, see pilot.goal_options_t. If not specified will use default values.
If
options.planner_mode
is set toFREE_ROAMING
, the HybridPlanner ignores the roadmap and uses free path planning.Hash64 job
- Optional job id, to identify the new goal. If not specified (or set to zero) will generate a new random id. See vnx.Hash64.
Asynchronous Move Functions¶
The following functions set / append a new goal while returning immediately.
If there is already a goal in progress, the set_*
functions cancel it before
setting the new goal (the call blocks until the robot stops) while the append_*
functions append the new goal after the end of the path.
-
void
set_goal
(MapStation goal, goal_options_t options, Hash64 job)¶ Sets a new goal using the provided pose and parameters in
goal
. Any pending goals are canceled beforehand. See pilot.MapStation. Requires permissionMOVE
.
-
void
set_goal_station
(string name, goal_options_t options, Hash64 job)¶ Sets a new goal using the provided station
name
. Any pending goals are canceled beforehand. The station must exist in the current Road Map. Requires permissionMOVE
.
-
void
set_goal_position
(PathPoint2D goal, goal_options_t options, Hash64 job)¶ Sets a new goal using the provided pose and parameters in
goal
. Similar toset_goal()
. Any pending goals are canceled beforehand. See pilot.PathPoint2D. Requires permissionMOVE
.
-
void
append_goal
(MapStation goal, goal_options_t options, Hash64 job)¶ Same as
set_goal(...)
but will not cancel active or pending goals. See pilot.MapStation. Requires permissionMOVE
.
-
void
append_goal_station
(string name, goal_options_t options, Hash64 job)¶ Same as
set_goal_station(...)
but will not cancel active or pending goals. Requires permissionMOVE
.
-
void
append_goal_position
(PathPoint2D goal, goal_options_t options, Hash64 job)¶ Same as
set_goal_position(...)
but will not cancel active or pending goals. See pilot.PathPoint2D. Requires permissionMOVE
.
Synchronous Move Functions¶
The following functions return when the new goal is physically reached, or the goal was canceled.
-
void
move_to
(MapStation goal, goal_options_t options, Hash64 job)¶ Same as
set_goal(...)
but will block until goal is reached or canceled. See pilot.MapStation. Requires permissionMOVE
.
-
void
move_to_station
(string name, goal_options_t options, Hash64 job)¶ Same as
set_goal_station(...)
but will block until goal is reached or canceled. Requires permissionMOVE
.
-
void
move_to_position
(PathPoint2D goal, goal_options_t options, Hash64 job)¶ Same as
set_goal_position(...)
but will block until goal is reached or canceled. See pilot.PathPoint2D. Requires permissionMOVE
.
Asynchronous Move Sequence Functions¶
The following functions set / append a list of new goals while returning immediately.
If there is already a goal in progress, the set_*
functions cancel it before
setting the new goal (the call blocks until the robot stops) while the append_*
functions append the new goals after the end of the path.
-
void
set_goals
(vector<MapStation> goals, goal_options_t options, Hash64 job)¶ Sets a list of new goals, similar to
set_goal(...)
. See pilot.MapStation. Requires permissionMOVE
.
-
void
set_goal_stations
(vector<string> names, goal_options_t options, Hash64 job)¶ Sets a list of new goals, similar to
set_goal_station(...)
. The stations must exist in the current Road Map. Requires permissionMOVE
.
-
void
set_goal_positions
(vector<PathPoint2D> goals, goal_options_t options, Hash64 job)¶ Sets a list of new goals, similar to
set_goal_position(...)
. See pilot.PathPoint2D. Requires permissionMOVE
.
-
void
append_goals
(vector<MapStation> goals, goal_options_t options, Hash64 job)¶ Appends a list of new goals, similar to
append_goal(...)
. See pilot.MapStation. Requires permissionMOVE
.
-
void
append_goal_stations
(vector<string> names, goal_options_t options, Hash64 job)¶ Appends a list of new goals, similar to
append_goal_station(...)
. Requires permissionMOVE
.
-
void
append_goal_positions
(vector<PathPoint2D> goals, goal_options_t options, Hash64 job)¶ Appends a list of new goals, similar to
append_goal_position(...)
. See pilot.PathPoint2D. Requires permissionMOVE
.
Synchronous Move Sequence Functions¶
The following functions return when the last goal specified has been physically reached, or the goals were canceled.
-
void
move_tos
(vector<MapStation> goals, goal_options_t options, Hash64 job)¶ Same as
set_goals(...)
but will block until last goal is reached or canceled. See pilot.MapStation. Requires permissionMOVE
.
-
void
move_to_stations
(vector<string> names, goal_options_t options, Hash64 job)¶ Same as
set_goal_stations(...)
but will block until last goal is reached or canceled. Requires permissionMOVE
.
-
void
move_to_positions
(vector<PathPoint2D> goals, goal_options_t options, Hash64 job)¶ Same as
set_goal_positions(...)
but will block until last goal is reached or canceled. See pilot.PathPoint2D. Requires permissionMOVE
.