Planner#

Path planning consists of finding an ‘optimal’ or ‘suboptimal’ path from a start to a goal location given partial (local planning) or complete space information (global planning). In a 2D navigation system, path planning refers to the global path planning which seeks an optimal path given largely complete static environmental information that is perfectly known to the robot (i.e. the global or reference map).[1]

Path planning algorithms produce a complete path from the start point (robot location) to the final end point, then the robot can start following and locally modifying the planned path (see Control).

Planner Component is in charge of global path planning in Kompass. Planner uses the Open Motion Planning Library (OMPL) plugins to perform the path planning (more on OMPL integration with Kompass)

Available Run Types#

Planner can be used with all four available RunTypes:

Timed

Compute a new plan periodically from current location (last message received on location input Topic) to the goal location (last message received on goal_point input Topic)

Event

Compute a new plan from current location on every new message received on goal_point input Topic

Server

Offers a PlanPath ROS service and computes a new plan on every service request

ActionServer

Offers a PlanPath ROS action and continuously computes a plan once an action request is received until goal point is reached

Inputs#

Planner requires configuring three inputs:

Key Name

Allowed Types

Number

Default

map

nav_msgs.msg.OccupancyGrid

1

Topic(name="/map", msg_type="OccupancyGrid", qos_profile=QoSConfig(durability=TRANSIENT_LOCAL))

goal_point

nav_msgs.msg.Odometry, geometry_msgs.msg.PoseStamped, geometry_msgs.msg.PointStamped

1

Topic(name="/goal", msg_type="PointStamped")

location

nav_msgs.msg.Odometry, geometry_msgs.msg.PoseStamped, geometry_msgs.msg.Pose

1

Topic(name="/odom", msg_type="Odometry")

Note

‘goal_point’ input is only used if the Planner is running as TIMED or EVENT Component. In the other two types, the goal point is provided in the service request or the action goal.

Outputs#

Planner offers two outputs:

Key Name

Allowed Types

Number

Default

plan

nav_msgs.msg.Path

1

Topic(name="/plan", msg_type="Path")

reached_end

std_msgs.msg.Bool

1

Topic(name="/reached_end", msg_type="Bool")

Available Algorithms:#

OMPL geometric planners (see available OMPL integrations for more details)

Usage Example#

    from kompass.components import Planner, PlannerConfig
    from kompass.config import ComponentRunType
    from kompass.topic import Topic
    from kompass_core.models import RobotType, Robot, RobotGeometry, LinearCtrlLimits, AngularCtrlLimits
    import numpy as np

    # Configure your robot
    my_robot = RobotConfig(
            model_type=RobotType.DIFFERENTIAL_DRIVE,
            geometry_type=RobotGeometry.Type.CYLINDER,
            geometry_params=np.array([0.1, 0.3]),
            ctrl_vx_limits=LinearCtrlLimits(max_vel=1.0, max_acc=1.5, max_decel=2.5),
            ctrl_omega_limits=AngularCtrlLimits(
                max_vel=1.0, max_acc=2.0, max_decel=2.0, max_steer=np.pi / 3
            ),
        )

    # Setup the planner config
    config = PlannerConfig(
        robot=my_robot,
        loop_rate=1.0 # 1Hz
    )

    planner = Planner(component_name="planner", config=config)

    planner.run_type = ComponentRunType.EVENT   # Can also pass a string "Event"

    # Add rviz clicked_point as input topic
    goal_topic = Topic(name="/clicked_point", msg_type="PoseStamped")
    planner.inputs(goal_point=goal_topic)