Skip to content

ROS 2 API for executing operations

Introduction

The Origin One can be commanded to execute a job, in which a job is an ordered list of tasks, such as GoToWaypoint, FollowPath, CoverArea, Dock, Undock and Wait, each executed by a specific Behavior. You may have defined a job in Cerebra Studio, and saved that job to the robot, but you don't need to open Cerebra Studio to execute that job, or to execute behaviors in general. You may also start the execution of jobs and behaviors using the ROS2 interface. Which is explained in this page.

Operational settings
But before explaining the ROS2 interface on jobs and behaviors, let us point out how to set important operational modes and information. The robot knows 3 modes of operations, that can be set using the service /set_mode_of_operation. These modes are the DEFAULT mode of operation, in which is robot is allowed to execute tasks, the MAPPING mode of operation, which is used for creating maps by the user, and the MULTIMAP mode of operation, which is similar to the DEFAULT mode.

Mode-of-operation

In DEFAULT mode the robot will only load the localization map that is linked to the Aruco marker detected when starting up.

In MULTIMAP mode the robot will switch to a different localization map when:

  • It is in front of a new Aruco marker linked to a map that is different compared to the one it is currently using.
  • Its current position is not anymore on the latest published map but on a different localization map (inferred from the map's polygon).

The robot navigates with respect to a mathematical origin in the global frame, i.e., the information of this origin in the global frame is denoted as "coordinate system information". When the robot starts outdoors then the latitude, longitude and altitude of the "coordinate system information" are set equal to the first accurate GPS fix acquired. When the robot starts indoors the "coordinate system information" is set as it is stored in the database of the robot. One may adjust these stored values by calling the service /set_stored_coord_info. See this page on coordinate systems for more information.

Finally, it may be useful to list jobs, maps, polygons, paths and artifacts, that are stored in the database of the robot. This information can be retrieved by calling the services /resource/list/[jobs,maps,polygons,paths,artifacts].

Before and during execution
Before starting to execute a job or a series of behaviors you may first want to check whether the robot has loaded the correct map for localization and planning. When the robot starts in front of an Aruco marker, then the map that was linked to that Aruco marker is automatically loaded. You may check whether this map is indeed loaded by the robot by calling the service /map/get_active_id, which will return the uuid by which the (currently used) map is saved in the knowledge base. This uuid is also visible in Cerebra Studio when you hover over the name of a map. In case you want to load a different map, then you may do so by calling the service /load_localization_map with the uuid of the map that you want the robot to use from that moment. In case you do not remember this uuid, then you may also define the name of the map (although names may not be unique!), or call the service /resource/list/map to acquire all maps in the knowledge base of the robot.

Warning

Switching a map should not be done arbitrarily! When the map was initially recorded the position of the Aruco marker was used to determine the position of the map in the global frame. However, this position of the maps may have become incorrect when the Aruco marker was placed elsewhere in the environment (without updating its position wrt to the global frame).

Once the robot started up you may retrieve important status information of the Autopilot Inference on the topic /system_status. This information, which is also displayed in Cerebra Studio, includes:

  • The accuracy with which the robot is estimating its position, i.e., ACCURATE, INNACCURATE_ORIENTATION, INACCURATE_POSITION, or UNKNOWN.
  • Whether the Autopilot Inference is operating properly.
  • A string referring to the status of executing behaviors, for example "moving" when it is controlling the robot to move along a (planned or predefined) path, or "waiting for behaviors to execute" when there are no behaviors to be executed and the robot is waiting until a job or new behaviors are set for execution.

Once the robot started up, and successfully finished its initialization procedure, you will see "system initialized" or "waiting for behaviors to execute" in Cerebra Studio and/or on the /system_status. You may then start and stop the execution of a job using the services /start_job and /stop_job, respectively. A job may only be started with its uuid, that you may find by hovering over the job in Cerebra Studio or by using the service /resource/list/job. More details on this ROS2 interface is found later on this page in the section on Job services.

Although you may define jobs, the robot is also able to execute one of the pre-designed Behaviors immediately, which are:

Behavior Meaning
MoveThoughPoses Plans a from the starting position of the robot through a given list of poses, and then moves along that path while avoiding ad-hoc obstacles. The path is re-planned when an obstacle is too large. It is the behavior that is called when executing a GoToWaypoint task.
MoveAlongPath Moves along the given path while avoiding ad-hoc obstacles. Path cannot be replanned, so large and sometimes medium-sized obstacles may not be avoided as the robot is not allowed to go too far from the original path. It is the behavior that is called when executing the FollowPath task.
CoverArea Plans a path to cover an area and then moves along that path while avoiding ad-hoc obstacles. Path cannot be replanned, so large and sometimes medium-sized obstacles may not be avoided as the robot is not allowed to go too far from the original path. It is the behavior that is called when executing the CoverArea task.
MoveInDock Turns and drives straight towards a given Aruco marker, until the distance between the robot and the marker is equal to some given approaching distance. It is the behavior that is called when executing the Dock task.
MoveOutDock Blindly drives 1 meter backwards. It is the behavior that is called when executing the Undock task.
Wait Waits for a given amount of seconds. It is the behavior that is called when executing the Wait task.

Behaviors are defined according to a particular message type, a Behavior, which can be found in the section behavior definition later on this page. Once you know how to define a behavior you may use the service /set_and_execute_behaviors to start the execution of behaviors. More details on this parts of the ROS2 interface is found in the section on Behavior services

The service /set_and_execute_behaviors is an important service as it defines a list of behaviors for the robot to immediately execute. The Autopilot Inference keeps track of the list of behaviors that it was asked to execute. When a behavior has been executed, then it is removed from that list and the next behavior in that list is executed. And so on. see also the illustration below. From your local computer you can add behaviors to this list using the /set_and_execute_behaviors service call.

BehaviorFifo

Operational settings

The services and topics related to the operational settings of the robot are summarized in the table below, while a more detailed account per service or topic is presented after the table.

Topic Format Type Function
/autopilot/information_manager/set_mode_of_operation knowledge_base_msgs/srv/SetModeOfOperation service Switch the mode of operation of the robot to DEFAULT, MAPPING, or MULTIMAP.
/autopilot/information_manager/set_stored_coord_info knowledge_base_msgs/srv/SetRobotCoordInfo service Set the latitude, longitude and altitude of the global origin for robot navigation.
/autopilot/information_manager/resource/list/job knowledge_base_msgs/srv/ListResource service Service to call for acquiring list all uuid's and names of a particular type of job.
/autopilot/information_manager/resource/list/map knowledge_base_msgs/srv/ListResource service Service to call for acquiring list all uuid's and names of a particular type of map.
/autopilot/information_manager/resource/list/path knowledge_base_msgs/srv/ListResource service Service to call for acquiring list all uuid's and names of a particular type of path.
/autopilot/information_manager/resource/list/polygon knowledge_base_msgs/srv/ListResource service Service to call for acquiring list all uuid's and names of a particular type of polygon.
/autopilot/information_manager/resource/list/artifact knowledge_base_msgs/srv/ListResource service Service to call for acquiring list all uuid's and names of a particular type of artifact.

Switch operational mode

The service /autopilot/information_manager/set_mode_of_operation has the following characteristics:
    Message type: knowledge_base_msgs/srv/SetModeOfOperation
    Request: mode_of_operation
    Response: success, message
The content of the service-request is a mode_of_operation, formatted as a knowledge_base_msgs/msg/ModesOfOperation, to indicate the mode too which should be switched. Hereto, ModeOfOperation defines the following values

  • mode_of_operation = 0 : Switch to DEFAULT mode.
  • mode_of_operation = 1 : Switch to MAPPING mode.
  • mode_of_operation = 2 : Switch to MULTIMAP mode.

Warning

When in MAPPING mode the Autopilot Inference only accepts a switch to DEFAULT, MAPPING, or MULTIMAP mode. This means that it does not accept any of the tasks, such as FollowPath, GoToWaypoint, Wait of CoverArea. Those tasks are only accepted in DEFAULT or MULTIMAP mode.

Set coordinate system (global origin)

The service /autopilot/information_manager/set_stored_coord_info has the following characteristics:
    Message type: knowledge_base_msgs/srv/SetRobotCoordSystem
    Request: coord_info
    Response: success, message
The content of the service-request is a coord_info, formatted as a autonomy_msgs/msg/CoordinateSystemInfo, which was also introduced on the page of the navigation interface. The service-response consists of two fields, i.e.,success formatted as a [Bool] indicating whether acquiring the list was successful or not, and a message formatted as a [string] to provide some logging information in the case that the service was unsuccessful.

Listing information

All five services /autopilot/information_manager/list/[jobs,maps,paths,polygons,artifacts] have the following characteristics:
    Message type: knowledge_base_msgs/srv/ListResource
    Request: type (optional)
    Response: json, result
The content of the service-request is a type, formatted as a [string], to specify which type of job, map, path, polygon or artifact is requested. Typically, the type field is not defined, unless it is specified in the list below:

  • polygon : type can be 'map_layout', 'go_area', 'nogo_area', 'cover_area'. The polygon type 'map_layout' refers to the border that is saved when creating a localization map. The robot uses this border to determine whether is should use the map for localization, as it is on the map, or not. The 'nogo_area', 'go_area' and 'cover_area' are polygons that can be linked to a CoverArea behavior. The purpose of these polygons is explained in the section on Behavior definition.

The service-response is the result, formatted as knowledge_base_msgs/msg/Result, which consists of two item, being success formatted as a [Bool] indicating whether acquiring the list was successful or not, and a message formatted as a [string] to provide some logging information in the case that the service was unsuccessful.

Before and during execution

The topics related to the preparing and executing operations with the robot are summarized in the table below, while a more detailed account per topic is presented later on this page.

Topic Format Type Function
/autopilot/information_manager/system_status autonomy_msgs/msg/SystemStatus publisher Status of the Autopilot Inference on position accuracy, health of the system and execution of behaviors.

The services and actions related to the preparing and executing operations with the robot are summarized in the table below, while a more detailed account per service/action is presented later on this page.

Service Format Request variable Function
/autopilot/information_manager/map/get_active_id knowledge_base_msgs/srv/GetActiveMapID n/a Service to call for acquiring the information about the current localization map that is used by the robot.
/autopilot/information_manager/load_localization_map knowledge_base_msgs/srv/PublishLocalizationMap n/a Service to call to request for loading a different localization map to be used by the robot.
/autopilot/information_manager/set_and_execute_behaviors knowledge_base_msgs/srv/SetAndExecuteBehaviors behaviors Service to call for adding behaviors to a list and requesting immediate execution of that list.
Action Format Request variable Function
/autopilot/information_manager/start_job knowledge_base_msgs/srv/StartJob uuid Service to call to start the execution of a job identifiable by the knowledge base on its uuid.
/autopilot/information_manager/stop_job knowledge_base_msgs/srv/StopJob n/a Service to call to stop the execution of the current job (note that the robot will always finish the current task that it is executing, and than stop the execution of any remaining tasks of that job).

Map preparations

The service /autopilot/information_manager/get_active_id has the following characteristics:
    Message type: knowledge_base_msgs/srv/GetActiveMapID
    Request: n/a
    Response: json, result
The content of the service-request is empty. The service-response items are uuid, formatted as [string], referring to the uuid of the localization map used by the robot for localization and planning, success formatted as a [Bool] indicating whether acquiring the list was successful or not, and message formatted as a [string] to provide some logging information in the case that the service was unsuccessful.

The service /autopilot/information_manager/load_localization_map has the following characteristics:
    Message type: knowledge_base_msgs/srv/PublishLocalizationMap
    Request: n/a
    Response: json, result
The content of the service-request is empty. The service-response items are uuid, formatted as [string], referring to the uuid of the localization map used by the robot for localization and planning, success formatted as a [Bool] indicating whether acquiring the list was successful or not, and message formatted as a [string] to provide some logging information in the case that the service was unsuccessful.

Triggering jobs

The actions /autopilot/information_manager/start_job has the following characteristics:
    Message type: knowledge_base_msgs/srv/StartJob
    Request: uuid
    Response: result
The content of the service-request is the uuid, formatted as [string], referring to the uuid of the job that should be started. The service-response items are success formatted as a [Bool] indicating whether acquiring the list was successful or not, and message formatted as a [string] to provide some logging information in the case that the service was unsuccessful.

The action /autopilot/information_manager/stop_job has the following characteristics:
    Message type: knowledge_base_msgs/srv/StopJob
    Request: n/a
    Response: result
The content of the service-request empty. The service-response items are success formatted as a [Bool] indicating whether acquiring the list was successful or not, and message formatted as a [string] to provide some logging information in the case that the service was unsuccessful.

Immediate execution of behaviors

The service /autopilot/information_manager/set_and_execute_behaviors has the following characteristics:
    Message type: knowledge_base_msgs/srv/SetAndExecuteBehaviors
    Request: behaviors
    Response: success, message
The content of the service-request is behaviors, formatted as a list of knowledge_base_msg/msg/Behavior, to define the list of behaviors that is to be added to the current list of behaviors (either ready for execution, or already in execution). The service call will immediately execute all the behaviors in the list, one by one, in case that is not already being done. How to define each behavior is explained in the section Behavior definitions. The service-response items are success formatted as a [Bool] indicating whether acquiring the list was successful or not, and message formatted as a [string] to provide some logging information in the case that the service was unsuccessful.

System status topic

The topic /autopilot/information_manager/system_status has the following characteristics:
    Message type: autonomy_msgs/msg/SystemStatus
    Frame: n/a
    Frequency: depends on the publisher
    Data: position_accuracy, is_operational, behavior_status and scheduling_enabled.
The content of the message that is published consists of 4 fields:

  • position_accuracy, formatted as a [string], is one of the following predefined messages to indicate whether the robot has an accurate position to safely navigate autonomously {"unknown", "inaccurate_position", "inaccurate_orientation", "accurate"}.
  • is_operational, formatted as a [Bool], is a statement indicating whether all (software) components of the Autopilot Inference are running properly.
  • scheduling_enabled, formatted as a [Bool], is a statement indicating whether the version of Autopilot Inference that is running on the robot supports the scheduling of jobs or not.
  • status, formatted as [string], is a freeform message published as logging statement by which one may assess the execution of a behavior. Some example are

    • "Waiting for next behavior to execute"
    • "Moving"
    • "Aborting"

Behavior definitions

The Autopilot Inference has 4 predefined behaviors, which are MoveThrougPoses, MoveAlongPath, CoverArea, MoveInDock, MoveOutDock and Wait. Each remaining section illustrates the construction of a behavior message object for each of these four behaviors in pseudo-code (python).

Code

Examples in Python for defining such a list of behavior elements can be found on our github repo with Code examples.

MoveThroughPoses (python)

    from knowledge_base_msgs.msg import Behavior            # import the behavior type
    from nav_msgs.msg import PoseStamped                    # import the pose type

    behavior = Behavior()                                   # knowledge_base_msg/msg/Behavior
    pose = PoseStamped()                                    # nav_msg/msg/PoseStamped
    pose.header.frame_id = "map"                            # the frame in which the poses are defined ("map" implies the global frame)
    pose.pose.position.x = 1.0                              # x-coordinate of destination
    pose.pose.position.y = 1.1                              # y-coordinate of destination
    pose.pose.orientation.z = 0.0                           # heading of destination in quaterions
    pose.pose.orientation.w = 1.0                           # quaternion normalization

    behavior.type = 10                                      # enum stating MoveTroughPoses
    behavior.goals.append(pose)                             # list of poses to plan the path
    behavior.policy.max_speed = 1.0                         # float less then 1.5 [m/s]
    behavior.policy.max_path_distance = 1.5                 # float in meters, where -1 implies that distance to path is discarded from the optimizer
    behavior.policy.controller_name = 'FollowPathLoosely'   # {'FollowPathLoosely', 'FollowPathRoughly', 'FollowPathStrictly'}, if not defined, then FollowPathLoosely is selected

MoveAlongPath (python)

    from knowledge_base_msgs.msg import Behavior            # import the behavior type

    behavior = Behavior()                                   # knowledge_base_msg/msg/Behavior
    [uuid, name] = json.dump(path_list)                     # here, path_list would be the result of a service call /autopilot/information_manager/resource/list/path
    path_uuid = uuid[3]                                     # pick the uuid of your desired path, in this case the third in the list is picked (or fourth if Python)

    behavior.type = 11                                      # enum stating MoveAlongPath
    behavior.constraint.path_uuid = path_uuid               # uuid of the selected path
    behavior.constraint.reverse = False                     # path can be taken in reverse, at which the robot should be located at the end of the non-reversed path
    behavior.policy.max_speed = 0.7                         # float less then 1.5 [m/s]
    behavior.policy.max_path_distance = 0.5                 # float in meters, where -1 implies that distance to path is discarded from the optimizer
    behavior.policy.controller_name = 'FollowPathStrictly'  # {'FollowPathLoosely', 'FollowPathRoughly', 'FollowPathStrictly'}, if not defined, then FollowPathRoughly is selected

CoverArea (python)

    from knowledge_base_msgs.msg import Behavior            # import the behavior type

    behavior = Behavior()                                   # knowledge_base_msg/msg/Behavior
    [uuid, name] = json.dump(polygon_list)                  # here, polygon_list would be the result of a service call /autopilot/information_manager/resource/list/polygon
    goarea_uuid = uuid[1]                                   # pick the uuid of your desired go area, in this case the first in the list is picked (or second if Python)


    behavior.type = 16                                      # enum stating CoverArea
    behavior.area_uuid = coverarea_uuid                     # uuid of the area to be covered
    behavior.policy.max_speed = 0.6                         # float less then 1.5 [m/s]
    behavior.policy.max_path_distance = 0.6                 # float in meters, where -1 implies that distance to path is discarded from the optimizer
    behavior.policy.controller_name = 'FollowPathStrictly'  # {'FollowPathLoosely', 'FollowPathRoughly', 'FollowPathStrictly'}, if not defined, then FollowPathRoughly is selected

MoveInDock (python)

    from knowledge_base_msgs.msg import Behavior            # import the behavior type

    behavior = Behavior()                                   # knowledge_base_msg/msg/Behavior
    behavior.type = 12                                      # enum stating CoverArea
    behavior.policy.dock_marker_id = 11                     # id of the Aruco marker where to dock
    behavior.policy.object_distance = 0.75                  # final distance between the marker and robot base-link

MoveOutDock (python)

    from knowledge_base_msgs.msg import Behavior            # import the behavior type

    behavior = Behavior()                                   # knowledge_base_msg/msg/Behavior
    behavior.type = 13                                      # enum stating CoverArea

Wait (python)

    behavior = Behavior.msg                     # knowledge_base_msg/msg/Behavior

    behavior.type = 40                                      # enum stating Wait
    behavior.constraint.time = 2.5                          # float in seconds defining the time to wait

Speak (python)

    behavior = Behavior.msg                     # knowledge_base_msg/msg/Behavior

    behavior.type = 40                                      # enum stating Wait
    behavior.constraint.time = 2.5                          # float in seconds defining the time to wait