Skip to content

ROS 2 API of the Origin One

The Origin One is created by Avular for users who want to continue developing robotic solutions. To support such developments, the Origin One has two types of interfaces of which one is the Origin's ROS 2 API.

The Origin is based on ROS 2 and its data and functionalities are exposed through ROS 2 topic, service calls and actions. As indicated in the picture below, these ROS 2 messages are divided into:

Service calls: services that can be called by the user
Input topics: topics that take input from the user
Output topics: topics that give output to the user

Where possible, the Origin One makes use of standardized ROS 2 messages, such as std_msgs, sensor_msgs, geometry_msgs and nav2_msgs. But for some messsages we have defined our own message set, called origin_msgs

Information

You can download an installable .deb file for the origin_msgs package here: arm64 | amd64

ROS 2 messages of the Origin One platform

An explanation of the messages and services as depicted in the illustration above are presented in the next sections. These sections are divided in accordance with the different functionalities of the robot, i.e.:

Controlling the robot

The velocity of the Origin One can be controlled via various different inputs, so that you as a user may switch on the fly from some from a computed velocity to a velocity set by the Origin's remote controller or some tele-operated input. The overall idea of this functionality is that multiple velocity inputs are supported and that, via a service call, one of these velocities is forwarded to the robot as the actual reference velocity. This functionality is implemented in the cmd_vel_controller.

The control mode is internal state of the cmd_vel_controller determines which input velocity, i.e., /robot/cmd_vel_XXX, is used to drive the Origin One. The control mode works like a state machine, where the service call /set_control_mode triggers the state machine to switch between different modes of operation. However, only certain transitions are allowed per mode. By default the robot starts in the NONE mode of operation, from which every transition is allowed. There are 2 control modes in which the robot is controlled by an operator or user (a.k.a. manually). These modes are called MANUAL (switching to /cmd_vel_joy) and TELEOPS (switching to /cmd_vel_teleops). The other modes are used for driving the robot autonomously, which are AUTONOMOUS (switching to /cmd_vel_aut), and USER (switching to /cmd_vel_user). Therefore, if you want your application to be able to control the Origin One, you must set the control mode to the USER and publish to the /cmd_vel_user topic. When the robot is driving in one of its autonomous modes, transitions to the other autonomous mode and the manual modes are allowed. This allows human intervention when the robot is driving autonomously.

When the robot is driving in any of the manual modes, transitions to the autonomous modes are not allowed. This prevents the robot from taking over control while a user is driving the robot manually. Instead, any manual control mode should first be released. Using the service /reset_control_mode the control mode can be reset to the NONE mode of operation, from which any transition is allowed.

Alternatively, after taking over control from the robot, you may want to return the control back to the robot. You can do this by calling the service /set_previous_control_mode. This way, you can always return to the original control mode, without having to know in which mode the robot was actually operating before taking control. When calling this service call, you have to provide the mode you are trying to return from.

Example on how to set/reset control modes

In order to be able to switch the control mode, you've to enter the pioneers container and you'll have to source the ROS 2 workspace. Then you can use ros2 service call /robot/cmd_vel_controller/set_control_mode origin_msgs/srv/SetControlMode "{ mode: { mode: X } }", where X is to be replaced by the following numbers:

mode (X) Meaning
0 none
10 manual
20 autonomous
30 user

The following example is a copy of the steps you've to take and responses you get in the terminal from the moment you've set up the ssh-connection with the Origin until the mode is switched to manual successfully:

avular@pioneers-2:~$ avular compose enter pioneers-prod
Entering pioneers-prod container

[~]
docker@pioneers-2 $ source ~/avular/system/install/setup.bash

[~]
docker@pioneers-2 $ ros2 service call /robot/cmd_vel_controller/set_control_mode origin_msgs/srv/SetControlMode "{ mode: { mode: 10 } }"
requester: making request: origin_msgs.srv.SetControlMode_Request(mode=origin_msgs.msg.ControlMode(mode=10))

response:
origin_msgs.srv.SetControlMode_Response(success=True, message='Control mode set to manual.')

If you now want to reset the control mode to none, you can use the reset_control_mode service as described in the following example (note that you'll have to give the mode it's comming from as input):

docker@pioneers-2 $ ros2 service call /robot/cmd_vel_controller/reset_control_mode origin_msgs/srv/ReturnControlMode "{ mode_from: { mode: 10 } }"
requester: making request: origin_msgs.srv.ReturnControlMode_Request(mode_from=origin_msgs.msg.ControlMode(mode=10))

response:
origin_msgs.srv.ReturnControlMode_Response(success=True, message='Control mode reset.')

cmd_vel_controller topics

The topics for interfacing with the cmd_vel_controller are summarized in the table below. A more detailed account per topic is presented later on this page.

Topic Format Type Function
/robot/cmd_vel_user geometry_msgs/Twist subscriber Topic via which a user may command velocity.
/robot/cmd_vel_aut geometry_msgs/Twist subscriber Topic that is used by Avular's autopilot for commanding velocity
Do not publish to this topic manually.
/robot/cmd_vel_joy geometry_msgs/Twist subscriber Topic that is used by the Origin's remote controller for commanding velocity
Do not publish to this topic manually.
/robot/cmd_vel_teleop geometry_msgs/Twist subscriber Topic that is used by Avular's (future) teleoperated application for commanding velocity over a cellular network
Do not publish to this topic manually.
/robot/cmd_vel geometry_msgs/Twist publisher Topic that is directly used by the robot itself for acquiring the robot's desired velocity
Do not publish to this topic manually.
/robot/cmd_vel_controller/control_mode origin_msgs/ControlMode publisher Topic that indicates the current velocity control mode

Each of the velocity topics above has the following characteristics:
    Message type: geometry_msgs/Twist
    Frame: odom & base_link
    Frequency: depends on the publisher
    Data: longitudinal velocity and yaw rate setpoint

The topic /robot/cmd_vel_controller/control_mode has the following characteristics:
    Message type: origin_msgs/ControlMode
    Frame: n/a
    Frequency: Latching and on change
    Data: mode

Example on how to use the cmd_vel_controller topics

In the next example, we want to let the Origin drive with a velocity of 0.5m/s in forward direction and with a rotational velocity of 0.5rad/s. Note that to do so, you'll have to set the control mode to 30 aka user and that you'll have to specify a rate/frequency at which the topic has to be published. The suggested frequency is 10Hz.

docker@pioneers-2 $ ros2 topic pub /robot/cmd_vel_user geometry_msgs/msg/Twist "{linear: {x: 0.5}, angular: {z: 0.5}}" --rate 10
publisher: beginning loop
publishing #1: geometry_msgs.msg.Twist(linear=geometry_msgs.msg.Vector3(x=0.5, y=0.0, z=0.0), angular=geometry_msgs.msg.Vector3(x=0.0, y=0.0, z=0.5))
You can stop the Origin driving by pressing the remote E-stop, taking over manual control by pressing 'O' on the controller or by giving the ctrl + C command in the terminal.

cmd_vel_controller services

Service Format Request variable Function
/robot/cmd_vel_controller/set_control_mode origin_msgs/srv/SetControlMode mode [str] Service to call for a switch to mode 'user', 'autonomous', 'manual' or 'teleops'.
/robot/cmd_vel_controller/reset_control_mode origin_msgs/srv/ResetControlMode n/a Service to call for a switch to mode 'none'.
/robot/cmd_vel_controller/previous_control_mode origin_msgs/srv/ReturnControlMode mode_from [mode] Service to call for a switch to the previous mode whilst the mode is currently at some mode_from.

All service calls above return a success bool to indicate whether the requested transition has been completed successfully.

Sensing data

The robot has various onboard sensor systems by which it observes its whereabouts and the environment in which it is operating. Results of these onboard sensors are, sometimes after filtering, published by the robot to be exploited for navigation typed applications.

Sensing data topics

The topics related to the onboard sensors are summarized in the table below. A more details account per topic is presented later on this page.

Topic Format Type Function
/robot/tf tf2_msgs/msg/TFMessage publisher Information obout the robot's tf-tree
/robot/joint_states sensor_msgs/JointState publisher Information on wheel states
/robot/odom nav_msgs/Odometry publisher 2D position, velocity, orientation and angular velocity of the robot after filtering the IMU and wheel encoders of the robot
/robot/gnss/fix sensor_msgs/NavSatFix publisher GNSS fix information
/robot/gnss/status origin_msgs/GNSSStatus publisher GNSS status information
/robot/initial_heading origin_msgs/InitialHeading publisher Initial heading at startup
/robot/camera/color/camera_info sensor_msgs/CameraInfo publisher Information about the camera characterstics
/robot/camera/color/image_raw sensor_msgs/Image publisher RGB image of the realsense camera of the robot
/robot/camera/color/meta_data realsense2_camera_msgs/MetaData publisher JSON string of the realsense settings
/robot/camera/depth/camera_info sensor_msgs/CameraInfo publisher Information about the camera characterstics
/robot/camera/depth/image_raw sensor_msgs/Image publisher depth image of the realsense camera of the robot
/robot/camera/depth/meta_data realsense2_camera_msgs/MetaData publisher JSON string of the realsense settings
/robot/lidar/points sensor_msgs/PointCloud2 publisher 3D pointcloud of the Ouster LiDAR (if available)

Transforms

The topic /robot/tf has the following characteristics:
    Message type: tf2_msgs/msg/TFMessage
    Published transforms
        odom->base_link
            Frequency: 25Hz
            Data: pose, twist
            Comment: Same transform as /robot/odom
         map->odom
            Frequency: 25Hz
            Data: pose, twist
            Comment: Same transform as /robot/pose_fused

Joint states

The topic /robot/joint_states has the following characteristics:
    Message type: sensor_msgs/JointState
    Frame: ${parent_link}_${prefix}_wheel (e.g. main_body_left_rear_joint_wheel)
    Frequency: 1Hz and on change
    Data: position, velocity, effort
Information on the state of the wheels, including wheel position [radians], velocity [radians per second] and motor effort [Nm] is the motor torque determined from the measured motor current and the motor torque constant.

Odometery

The topic /robot/odom has the following characteristics:
    Message type: nav_msgs/Odometry
    Frame: odom & base_link
    Frequency: 25Hz
    Data: pose, twist, covariances
Content of the message contains the output of a 2D EKF that uses the IMU and the wheel encoders as its inputs. The covariance estimate is updated each time step as part of the EKF algorithm. Note that the EKF only updates when movement is detected (i.e., moving wheels) to prevent drifting over time.

GNSS(-RTK)

Info

GNSS related topics output no data if no GNSS add-on is purchased/mounted.

The topic /robot/gnss/fix has the following characteristics:
    Message type: sensor_msgs/NavSatFix
    Frame: gps_link
    Frequency: 1Hz and on change
    Data: latitude, longitude, height, position covariance, fix status
Sends an updated fix if a new GNSS location is available or every second if no new value is provided. Latitude, longitude and height are just forwarded from the Simulink U-blox driver. Position covariance is calculated from the horizontal (x, y) and vertical accuracy (z) by squaring them to get the respective variances. The status field (or fix type) is mapped as follows:

fix status Meaning
0 No fix.
1 No fix and dead reckoning only.
2 2D RTK fix.
3 3D RTK fix.
4 GNSS fix with dead reckoning.
5 No fix and time only.

The topic /robot/gnss/status has the following characteristics:
    Message type: origin_msgs/GNSSStatus
    Frame: gps_link
    Frequency: 1Hz and on change
    Data: RTK fix status, position accuracy, number of satellites in view, number of satellites used
Contains information on the GNSS horizontal and vertical position accuracy, number of satellites visible and number of satellites used. Also contains GNSS status:

GNSS status Meaning
-2 Unknown status
-1 No fix
0 2D fix, no RTK base station used
1 3D fix, no RTK base station used
2 RTK fix with floating ambiguity, multiple solution possible
3 RTK fix with fixed ambiguity, single solution, highest accuracy

Initial heading (magnetometer)

The topic /robot/initial_heading has the following characteristics:
    Message type: origin_msgs/InitialHeading
    Frame: n/a
    Frequency: 1Hz and on change
    Data: initial heading
The initial heading of the Origin with respect to magnetic North in radians determined at boot time. Note that the accuracy of this heading estimate is heavily influenced by magnetic disturbances in the environment and/or changes in the magnetic field. If the Origin is used at a location far from where the calibration was performed (Eindhoven by default), it is recommended to perform a new magnetometer calibration procedure.

Camera

The topics /robot/camera/color/camera_info and /robot/camera/depth/camera_info have the following characteristics:
    Message type: sensor_msgs/CameraInfo
    Frame: n/a
    Frequency: 6 FPS
    Data: image height, image width, distortion and parameters of the camera's intrinsic matrix, rectification matrix and projection matrix,

The topics /robot/camera/color/image_raw and /robot/camera/depth/image_raw have the following characteristics:
    Message type: sensor_msgs/Image
    Frame: camera_link
    Frequency: 6 FPS
    Data: image height, image width, encoding and actual image data,

The topics /robot/camera/color/meta_data and /robot/camera/depth/meta_data have the following characteristics:
    Message type: realsense2_camera_msgs/MetaData
    Frame: n/a
    Frequency: 6 FPS
    Data: json
The metadata messages store the camera's available metadata in a json format. To learn more, a dedicated script for echoing a metadata topic in runtime is attached. For instance, use the following command to echo the camera/depth/metadata topic:
python3 src/realsense-ros/realsense2_camera/scripts/echo_metadada.py /camera/camera/depth/metadata

Example on how to use the Sensing data topics

In the next example, we want to read out the omodmetry of the Origin. For this you'll have to ssh into the Origin, enter the pioneers-prod container, and source the ros2 workspace as is all shown below from the ssh-connection onwards:

avular@pioneers-2:~$ avular compose enter pioneers-prod
Entering pioneers-prod container

[~]
docker@pioneers-2 $ source ~/avular/system/install/setup.bash

[~]
docker@pioneers-2 $ ros2 topic echo /robot/odom
header:
  stamp:
    sec: 1727789137
    nanosec: 654711766
  frame_id: odom
child_frame_id: base_link
pose:
  pose:
    position:

Robot management

The Origin One can be managed either to wait or to prepare for operation. Furthermore, the robot also shows the status of its battery, onboard computers and collision avoidance. These interfaces are meant for managing the robot, before and during operation.

A first important topic that is acquired by the robot, and thus can be set by the user, is to /set_collision_avoidance, by which one may set all ultrasonic sensors to respond to obstacles, only the front sensors, only the rear sensors or disable collision avoidance completely.

Further, the Origin One can be set to LOW_POWER mode using a service /set_low_power_mode, which is a mode during which the Origin is saving power and is not powering most of its sensors and actuators. It will return 0 if the Origin successfully entered low power mode, and a non-zero error code if it did not. The external power ports on the robot are also disabled. In this mode, the Origin will not be able to move. This is useful for saving power when the Origin is not in use, for example when a mission has been scheduled for a later time (as you may also specify a wake-up time when calling the service). In order to prevent all kinds of edge cases the LOW_POWER mode implies that all regular ROS 2 nodes will not be running, apart from a very basic ROS 2 node for calling this service and the service to exit the LOW_POWER mode, i.e., /exit_low_power_mode.

Also, the shutdown sequence of the Origin can be initiated by calling the service /shutdown. This will trigger the same shutdown sequence as manually triggering the shutdown using the onboard button. It is important to realize that the robot cannot be booted, or started, with a service call. If that is desired one should make use of the LOW_POWER related service calls.

Robot management topics

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

Topic Format Type Function
robot/set_collision_avoidance_mode origin_msgs/CollisionAvoidanceMode subscriber Topic to set the manner of collision avoidance
robot/battery/info origin_msgs/BatteryInfo publisher Battery Information
robot/mode_of_operation std_msgs/UInt8 publisher Robot supervisor state
robot/safety_supervisor/emergency_brake_active std_msgs/Bool publisher Emergency brake status
robot/safety_supervisor/velocity_limits origin_msgs/LongitudalVelocityLimits publisher Maximum allowed longitudinal velocity setpoints
origin_system_bringup/network_telemetry/telemetry origin_msgs/msg/NetworkTelemetry publisher Status of the different network interfaces and connections

The topic /robot/set_collision_avoidance_mode has the following characteristics:
    Message type: origin_msgs/CollisionAvoidanceMode
    Frame: n/a
    Frequency: depends on the publisher
    Data: mode
This topic can be used to set which set of ultrasonic sensors should be used for collision avoidance, 0 for all sensors, 1 for only the front sensors and 2 for only the rear sensors. It is recommended to turn off the collision avoidance functionality completely (mode=3) in outdoor or other uneven environments, due to false positive ultrasonic detections, resulting in the Origin being unable to move or not driving smoothly.

Warning

The /set_collision_avoidance contains a minor bug. If the user desires to set the mode to 0 for the first time after powering on the robot, then the system will respond successful without setting the collision avoidance mode to front & rear. To mitigate this behavior, first set the /set_collision_avoidance to a non-zero value i.e. 1, 2 or 3 and right thereafter set the mode to 0.

The correct format to change the status of the collision avoidance is for example to set it to front collision avoidance only: ros2 topic pub /robot/set_collision_avoidance origin_msgs/msg/CollisionAvoidanceMode "{ mode: 1}" --once.

The topic /robot/battery/info has the following characteristics:
    Message type: origin_msgs/BatteryInfo
    Frame: n/a
    Frequency: 1Hz and on change
    Data: voltage, state of charge
The battery voltage goes from 32V to 50V, while the state of charge is in percentage.

The topic /robot/mode_of_operation has the following characteristics:
    Message type: std_msgs/UInt8
    Frame: n/a
    Frequency: 1Hz and on change
    Data: mode of operation
The mode of operation indicates whether the robot is booting up or whether it is ready to be operated. The mode is defined according to the table below.

Message Mode of operation Information
0 None The Origin is not ready for use yet, it is still booting
1 Jetson The Origin can be controlled using the /robot/cmd_vel topic

The topic /robot/safety_supervisor/emergency_brake_active has the following characteristics:
    Message type: std_msgs/Bool
    Frame: n/a
    Frequency: 1Hz and on change
    Data: emergency brake active
The data of this topic is a Boolean indicating whether any of the emergency brakes are active (the remote e-stop or the physical e-stop buttons on the Origin itself). True = emergency brake is active, Origin is unable to move.

The topic /robot/safety_supervisor/velocity_limits has the following characteristics:
    Message type: origin_msgs/LongitudalVelocityLimits
    Frame: n/a
    Frequency: 1Hz and on change
    Data: max forward velocity, max backward velocity
The data of this topic is the maximum forward and backward longitudinal velocity setpoints for the Origin. Any command velocities sent beyond these values are saturated. Values can change in real time due to (for instance) ultrasonic collision avoidance that limits the velocity.

The topic /origin_system_bringup/network_telemetry/telemetry has the following characteristics:
    Message type: origin_msgs/msg/NetworkTelemetry
    Frame: n/a
    Frequency: 1Hz and on change
    Data: cellular strength and operator, wifi strength and wifi ssid and ip
The data of this topic provides information about the network interfaces, and the network connection status. The table below present the meaning of the enums for cellular strength and Wifi strength.

cellular strength Wifi strength Meaning
4 3 excellent
3 n/a good
2 2 fair
1 1 poor
0 0 disconnected
-1 -1 unknown

Robot management services

Service Format Request variable Function
/origin_system_bringup/set_low_power_mode origin_msgs/srv/EnterLowPowerMode schedule_wakeup [Bool] Service to call for a switch to low power mode.
/origin_system_bringup/exit_low_power_mode std_msgs/srv/Trigger n/a Service to call to exit low power mode.
/origin_power_management/shutdown std_msgs/srv/Trigger n/a Service to call to trigger a shutdown.

The first service call will return an enum for no error (0) or rejected (1), while the latter two service calls return a success bool to indicate whether the requested transition has been completed successfully.