kompass.components.controller

Module Contents

Classes

CmdPublishType

Control command publishing method:

ControllerConfig

Controller component configuration parameters

Controller

Controller component used for path tracking and control around dynamic obstacles during navigation.

API

class kompass.components.controller.CmdPublishType

Bases: kompass.utils.StrEnum

Control command publishing method:

Value

Description

TWIST_SEQUENCE (Literal “Sequence”)

the controller publishes a Twist message in the same thread running the control algorithm. If a series of commands is computed (up to the control horizon), the controller publishes the commands one by one before running the control algorithm again

TWIST_PARALLEL (Literal “Parallel”)

the controller handles publishing a Twist message in a new thread. If a series of commands is computed (up to the control horizon), the controller publishes the commands one by one in parallel while running the control algorithm again

TWIST_ARRAY (Literal “Array”)

the controller publishes a TwistArray msg of all the computed control commands (up to the control horizon)

class kompass.components.controller.ControllerConfig

Bases: kompass.config.ComponentConfig

Controller component configuration parameters

Name

Type, Default

Description

algorithm

ControllersID| str, DWA

Algorithm used to compute the control command

control_time_step

float, 0.1

Time step in MPC-like controllers (s)

debug

bool, False

Turn on debug mode to published additional data for visualization

use_direct_sensor

bool, False

To used direct sensor information, otherwise the node subscriber to a local map

ctrl_publish_type

CmdPublishType | str, TWIST_ARRAY

How to publish the control commands

class kompass.components.controller.Controller(*, component_name: str, config_file: Optional[str] = None, config: Optional[kompass.components.controller.ControllerConfig] = None, inputs: Optional[Dict[kompass.components.defaults.TopicsKeys, kompass.components.ros.Topic]] = None, outputs: Optional[Dict[kompass.components.defaults.TopicsKeys, kompass.components.ros.Topic]] = None, **kwargs)

Bases: kompass.components.component.Component

Controller component used for path tracking and control around dynamic obstacles during navigation.

Inputs:

Key Name

Allowed Types

Number

Default

plan

nav_msgs.msg.Path

1

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

location

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

1

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

sensor_data

sensor_msgs.msg.LaserScan, sensor_msgs.msg.PointCloud2

1

Topic(name="/scan", msg_type="LaserScan")

local_map

nav_msgs.msg.OccupancyGrid

1

Topic(name="/local_map/occupancy_layer", msg_type="OccupancyGrid")

vision_tracking

automatika_embodied_agents.msg.Trackings, automatika_embodied_agents.msg.Detections2D

1

Topic(name="/trackings", msg_type="Trackings")

Outputs:

Key Name

Allowed Types

Number

Default

command

geometry_msgs.msg.Twist

1

Topic(name="/control", msg_type="Twist")

multi_command

kompass_interfaces.msg.TwistArray

1

Topic(name="/control_list", msg_type="TwistArray")

interpolation

nav_msgs.msg.Path

1

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

local_plan

nav_msgs.msg.Path

1

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

tracked_point

nav_msgs.msg.Odometry, geometry_msgs.msg.PoseStamped, geometry_msgs.msg.Poseautomatika_embodied_agents.msg.Detection2D

1

Topic(name="/tracked_point", msg_type="PoseStamped")

Available Run Types:

Set directly from Controller ‘run_type’ property.

  • TIMED: Compute a new control command periodically if all inputs are available.

  • ACTIONSERVER: Offers a ControlPath ROS action and continuously computes a new control once an action request is received until goal point is reached

Usage Example:

from kompass.components import ControllerConfig, Controller
from kompass.topic import Topic

# Setup custom configuration
my_config = ControllerConfig(loop_rate=10.0)

# Init a controller object
my_controller = Controller(component_name="controller", config=my_config)

# Change an input
my_controller.inputs(plan=Topic(name='/global_path', msg_type='Path'))

# Change run type (default "Timed")
my_controller.run_type = "ActionServer"

# Change plugin
my_controller.plugin = 'DWA'
custom_on_activate()

Component custom activation method to add activation based on the control mode

custom_create_all_subscribers()

Overrides BaseComponent create_all_subscribers to implement controller mode change

create_all_timers()

Overrides create_all_timers from BaseComponent to add timers for commands execution and tracking publishing

destroy_all_timers()

Overrides destroy_all_timers from BaseComponent to destroy the timers for commands execution and tracking publishing

create_all_services()

Creates all node services

destroy_all_services()

Destroys all node services

property tracked_point: Optional[numpy.ndarray]

Getter of tracked pose on the reference path if a path is set to the controller

Returns:

description

Return type:

StrEnum

property local_plan: Optional[nav_msgs.msg.Path]

Getter of controller local plan

Returns:

description

Return type:

StrEnum

property local_plan_debug: Optional[nav_msgs.msg.Path]

Getter of controller local plan debug (collected samples)

Returns:

description

Return type:

StrEnum

property interpolated_path: Optional[nav_msgs.msg.Path]

Getter of interpolated global path

Returns:

Path Interpolation

Return type:

Optional[Path]

property direct_sensor: bool

Getter of flag to use direct sensor data in the controller, if False the controller uses the local map

Returns:

Use direct sensor data flag

Return type:

bool

property algorithm: kompass_core.control.ControllersID

Getter of controller algorithm

Returns:

description

Return type:

StrEnum

set_algorithm(algorithm_value: Union[str, kompass_core.control.ControllersID], **_) bool

Component action - Set controller algorithm action

Parameters:

algorithm_value (Union[str, ControllersID]) – algorithm value

Raises:

Exception – Exception while updating algorithm value

Returns:

Success

Return type:

bool

init_variables()

Overwrites the init variables method called at Node init

main_action_callback(goal_handle) Union[kompass_interfaces.action.ControlPath.Result, kompass_interfaces.action.TrackVisionTarget.Result]

Executes the selected control action

Parameters:

goal_handle (ControlPath | TrackVisionTarget) – Action request

Returns:

Action result

Return type:

Union[ControlPath.Result, TrackVisionTarget.Result]

reached_point(goal_point: Optional[kompass_core.models.RobotState]) bool

Checks if the current robot state is close to a given goal point

Parameters:
  • goal_point (RobotState | None) – Goal point

  • tolerance (PathTrackingError) – Tolerance to goal

Returns:

If the distance to the goal is less than the given tolerance

Return type:

bool