LocalPlanner

Module

The LocalPlanner module generates velocity commands to keep the robot on a given path or to reach a certain goal which is in reach. Usually the given path is generated by the HybridPlanner and depending on configuration further optimized by the LocalPlanner.

Most functions require a special permission, 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.
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.

General Functions

Path2D *get_path() const

Returns the current original map path being followed, if any. See pilot.Path2D.

Path2D *get_optimized_path() const

Returns the current optimized map path being followed, if any. See pilot.Path2D.

LocalPlannerState get_state() const

Returns the current planner state. See pilot.LocalPlannerState.

Movement Functions

void pause(bool em_stop)

Will pause movement, similar to an EM stop, but with a soft decceleration. However, if em_stop is set to true will perform an emergency stop. resume() needs to be called to continue with the current or any new goal.

void resume()

Will resume movement after having been paused, while adhering to acceleration limits.

void await_goal() const

Waits for the current goal to finish. If currently idle it returns immediately.

void await_goal_ex(Hash64 job) const

Waits for a specific goal to finish. Either the currently active or finished goal, or any in the future. If the specified goal has already been reached in the past and subsequently been superseeded by another, this function will fail, ie. it will wait forever. Ideally this function is called before setting the goal to be waited for.

void cancel_goal()

Will cancel any pending goal and bring the robot to an immediate stop. Requires permission MOVE.

void cancel_goal_await()

Same as cancel_goal() and then await_goal() in one call.

void set_path(Path2D *path, goal_options_t options)

Sets a new path to be followed and returns immediately. Any pending goal is canceled beforehand. The path needs to be in map coordinates. See pilot.Path2D. Requires permission MOVE.

void update_path(Path2D *path, goal_options_t options)

Updates the current path to be followed without stopping or canceling the current goal. If the new path does not include the current position (to within some tolerance) a failure will be issued. The path needs to be in map coordinates and it’s job id needs to match the current job id. See pilot.Path2D. Requires permission MOVE.

void follow_path(Path2D *path, goal_options_t options)

Same as set_path(...) but will block until the goal is reached or canceled. See pilot.Path2D. Requires permission MOVE.

void set_goal(PathPoint2D goal, goal_options_t options, Hash64 job)

Sets a new goal position, either relative to the current position or an absolute map position. The new goal must be within reach, with a maximum distance depending on configuration, but usually around 1 m. See pilot.PathPoint2D. Requires permission MOVE.

void move_to(PathPoint2D goal, goal_options_t options, Hash64 job)

Same as set_goal(...) but will block until the goal is reached or canceled. See pilot.PathPoint2D. Requires permission MOVE.