Skip to content

ROS 2 API for managing the Origin One

With the Origin One you may record maps and paths. These can either be used for logging the whereabouts of the robot, for visualization, or for navigating along specific, pre-recorded paths later on which are necessary for your application.

When creating map you will first need to switch to the Autopilot Inference to MAPPING mode using a service /set_mode_of_operation. This will trigger a SLAM component for creating a 2D occupancy map. This map, and the pose of the robot within this map, can be found on the topics /mapping/map and /mapping/pose, respectively. You may visualize both topics in the mapping GUI of Avular, or in RViz. If you want the robot to be able to use your newly created map later, for example for localization, then you will need to save the map in the knowledge base of the robot using the service /save_map, which will save the data that is available on /mapping/map (so do not stop mapping before you have saved the map). This message will give you a unique ID, i.e., 'uuid', that is used by the knowledge base to query the map. You will need to capture this 'uuid'. Finally, you will need to set the boundary of the map, which is used to determine whether the robot is within this map and thus to trigger a functionality for estimating the pose of the robot within the map. You may set the boundary of this map by using the service /save_typed_polygon for which you will need the 'uuid' of the map and a list of points marking the vertices of the polygon with respect the the global frame.

Info

If you are uncertain about the (X, Y, Z) position of the points of the polygon, then you may drive the robot (close) to those point while echoing the topic /autopilot/estimated_pose.

Info

If you do not want to start from an Aruco marker, then the robot does not have an initial estimate of its pose which is required for the MAPPING mode to complete. Instead, you may set the initial pose manually by publishing on the topic /initial_pose of which more information can be found on navigation interfaces.

When creating paths you will need to ensure that the Autopilot Inference is in DEFAULT mode, which is the mode when turning on the robot. If you are uncertain, you may use a service /set_mode_of_operation to set the mode of operation of the Autopilot Inference, of which more details can be found here. You may start recording a path at any moment by calling the service /record_path. While recording the recorded path of the robot will be published on the topic /plan_twist. In order to save the path in the knowledge base of the robot you may use the service /save_path, which will save the data that is available on /plan_twist (so do not stop mapping before you have saved the map). The services /pause_path can be used to pause the recording of the path until further notice, i.e., until record_path is being called, while in order to clean the recorded path you may call the service /discard_path.

Mapping topics

The topics related to the SLAM functionality of the robot are summarized in the table below. A more details account per topic is presented later on this page.

Topic Format Type Function
autopilot/mapping/map nav_msgs/msg/OccupancyGrid publisher SLAM map
autopilot/mapping/pose geometry_msgs/msg/PoseWithCovarianceStamped publisher SLAM pose

SLAM map and pose

The topic /autopilot/mapping/map has the following characteristics:
    Message type: nav_msgs/msg/OccupancyGrid
    Frame: odom & base_link
    Frequency: depends on the publisher
    Data: header, info, data
The content of the message that is published is a header, formatted as std_msgs/Header to indicate the time, along with info, formatted as nav_msgs/msg/MapMetaData, to indicate meta data of the map, such as its height, width and origin, and the data itself, formatted as int8[] to represent the occupancy probability per cell in the 2D map.

The topic /autopilot/mapping/pose has the following characteristics:
    Message type: geometry_msgs/msg/PoseWithCovarianceStamped
    Frame: odom & base_link
    Frequency: depends on the publisher
    Data: header, pose
The content of the message that is published is a header, formatted as std_msgs/Header to indicate the time, and a pose, formatted as geometry_msgs/msg/PoseWithCovariance to represent the 6D position of the robot along with the uncertainty on that pose in the form of a covariance matrix.

Mapping services

The services related to the SLAM functionality of the robot are summarized in the table below. A more details account per service is presented later on this page.

Service Format Request variable Function
/autopilot/information_manager/set_mode_of_operation knowledge_base_msgs/srv/SetModeOfOperation mode_of_operation Service to trigger a switch between MAPPING and DEFAULT mode of the autopilot.
/autopilot/information_manager/save_map knowledge_base_msgs/srv/SaveMap uuid [string], name [string] Service to call for a saving a map in the knowledge base of the robot.
/autopilot/information_manager/save_typed_polygon knowledge_base_msgs/srv/SaveTypedPolygon polygon [TypedPolygon] Service to call for saving the border of a map as a polygon in the knowledge base of the robot.

Switch to MAPPING 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 value

mode_of_operation meaning
0 Switch to DEFAULT mode
1 Switch to MAPPING mode

The service-response is the success, formatted as Bool, to indicate whether the map was successful saved, and a message, formatted as a string, to provide some logging information in the case that the service was unsuccessful.

Warning

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

Saving a map and its border

The service /autopilot/information_manager/save_map has the following characteristics:
    Message type: knowledge_base_msgs/srv/SaveMap
    Request: uuid, name
    Response: uuid, success, message
The content of the service-request is either a uuid or a name, both formatted as string, for which we propose to provide a name so that the knowledge base may create a unique ID that it knows how to handle. The service-response is the uuid, formatted as a string, that is given by the knowledge base of the robot in case the user did not provide one, the success, formatted as Bool, to indicate whether the map was successful saved, and a message, formatted as a string, to provide some logging information in the case that the service was unsuccessful.

The service /autopilot/information_manager/save_typed_polygon has the following characteristics:
    Message type: knowledge_base_msgs/srv/SaveTypedPolygon
    Request: polygon
    Response: uuid, success, message
The content of the service-request is a polygon, formatted as knowledge_base_msgs/msg/TypedPolygon, which is a customized message that is used to distinguish between the different types of polygons that are used by the robot. In this case, the TypedPolygon is formatted as follows

field format remark
type string value should be 'map_layout'
uuid string this field is optional, unless name is empty
name string this field is optional, unless uuid is empty
polygon autonomy_msgs/msg/Polygon list of (x, y, z) of the actual points of the polygon
map_id string uuid of the map that is retrieved via the service call autopilot/information_manager/save_map
coord_info autonomy_msgs/msg/CoordinateSystemInfo information about the coordinate system that is used by the robot upon creating the map. See the navigation interface for more information.

The service-response is the uuid, formatted as a string[], that is given by the knowledge base of the robot in case the user did not provide one, the success, formatted as Bool, to indicate whether the map was successful saved, and a message, formatted as a string[], to provide some logging information in the case that the service was unsuccessful.

Paths topics

The topics related to the path recording functionality of the robot are summarized in the table below. A more details account per topic is presented later on this page.

Topic Format Type Function
autopilot/path_recorder/plan_twist autonomy_msgs/msg/Path publisher List of pose and twist elemtns of the path.

The topic /autopilot/plan_twist has the following characteristics:
    Message type: autonomy_msgs/msg/Path
    Frame: map or odom
    Frequency: depends on the publisher
    Data: uuid, name, info and poses
The content of the message that is published are a uuid and a name, both formatted as [string], to give the path a unique identifier and a human readable name. Further, the field info, formatted CoordinateSystemInfo, is a representation of the coordinate system in which the path was recorded referring to either the map-frame or the odom-frame. Finally, the field of poses is a list of PoseWithTwist with elements of the poses and the twists for each point on the path.

, and a nameindicate the time, and a pose, formatted as geometry_msgs/msg/PoseWithCovariance to represent the 6D position of the robot along with the uncertainty on that pose in the form of a covariance matrix.

Paths services

The services related to the path recording functionality of the robot are summarized in the table below. A more details account per service is presented later on this page.

Service Format Request variable Function
/autopilot/information_manager/save_path knowledge_base_msgs/srv/SavePath uuid [string], name [string] Service to call for a saving a map in the knowledge base of the robot.
/autopilot/path_recorder/record_path planner_msgs/srv/RecordPath override [Bool] Service to call for start recording a path.
/autopilot/path_recorder/discard_path autonomy_msgs/srv/Trigger n/a Service to call for discarding the path that has been recorded.
/autopilot/path_recorder/pause_path autonomy_msgs/srv/Trigger n/a Service to call for pausing the recording of a path.

Saving a path

The service /autopilot/information_manager/save_path has the following characteristics:
    Message type: knowledge_base_msgs/srv/SavePath
    Request: uuid, name
    Response: uuid, success, message
The content of the service-request is either a uuid or a name, both formatted as string, for which we propose to provide a name so that the knowledge base may create a unique ID that it knows how to handle. The service-response is the uuid, formatted as a string, that is given by the knowledge base of the robot in case the user did not provide one, the success, formatted as Bool, to indicate whether the map was successful saved, and a message, formatted as a string, to provide some logging information in the case that the service was unsuccessful.

Start, pause and stop recording a path

The service /autopilot/record_path has the following characteristics:
    Message type: knowledge_base_msgs/srv/SaveTypedPolygon
    Request: override
    Response: success, message
The content of the service-request is an override or a name, formatted as [Bool], to indicate whether the new recordings should be added to the prior recorded path, or whether the prior path should be cleared and only the new path should be recorded. The service-response is success, formatted as [Bool], to indicate whether the map was successful saved, and a message, formatted as a [string], to provide some logging information in the case that the service was unsuccessful.

The two services /autopilot/discard_path and /autopilot/pause_path have the following characteristics:
    Message type: knowledge_base_msgs/srv/SaveTypedPolygon
    Request: n/a
    Response: success, message
The content of the service-request is empty. The service-response is success, formatted as [Bool], to indicate whether the map was successful saved, and a message, formatted as a [string], to provide some logging information in the case that the service was unsuccessful.