Coordinate Frames Convention
Warning
The frames of reference convention has changed in v23.04 to comply with ROS conventions REP-103 and REP-105. New SLAM runs will generate trajectories using a new axes convention which may impact existing integrations. Please see the Coordinate Frames of Reference Convention Change section of our migration guide for more information.
When using Slamcore SLAM, the user should be aware of the following coordinate frames of reference:
SensorThis is the frame that the SLAM tracks. For the RealSense D435i this frame is rigidly attached to the device IMU chip with the positive X axis pointing to the right, the positive Y axis pointing down and the positive Z axis pointing forward.
Fig. 79 RealSense Camera Sensor Frame as illustrated on RealSense’s tutorial page
BodyThis is the frame of reference whose pose the SLAM reports. This pose is reported against the
Worldframe of reference, i.e., theT_WBtransform. This frame is located in the same position as theSensorframe, however, it uses a different axis orientation convention to comply with REP-103. In this case, the positive X axis is pointing forward, the positive Y axis is pointing left and the positive Z axis is pointing up.
Fig. 80 Slamcore Body Frame
WorldThis is the frame of reference that the SLAM pose is estimated against. To comply with REP-103 and REP-105, this frame is initialised based on the
Bodyframe and the gravity direction - with the camera parallel to the ground and facing forward, theWorldZ axis will be initialised pointing up, opposite to the gravity direction. TheWorldX axis will be initialised to match theBodyX axis direction and theWorldY axis will be initialised pointing to the left of thisWorldX axis.
With the convention defined above, if you start up the RealSense, parallel to the ground and start moving it forwards, you will notice our X estimate increasing. Similarly, if you move it upwards, you will notice a positive increase in the Z coordinate.
Fig. 81 Frames of reference during a forward motion of the camera
Coordinate Frames in ROS - map, odom and base_link
In ROS, REP-105 specifies the following coordinate frame conventions:
base_link - Frame rigidly attached to the mobile robot base.
odom - World-fixed frame in which the pose of a mobile platform can drift over time.
map - World-fixed frame, with Z axis pointing upwards, in which the pose of a mobile platform should not significantly drift over time. This frame is not continuous and may contain pose jumps.
When using the Slamcore ROS Wrappers, the map frame and odom frame are
equivalent to the Slamcore World frame and the base_link frame is
equivalent to the Slamcore Body frame. Therefore, the reported pose will be
that of the Body frame, attached to the camera.
Many popular ROS frameworks, like the navigation stack abide to this ROS Coordinate Frames convention, and thus expect two transformations from which they can get pose information:
map\(\rightarrow\)base_linkodom\(\rightarrow\)base_link
where base_link is the main frame of reference of the robot platform in use.
This way a ROS node that’s interested in the pose of the robot can query either
map \(\rightarrow\) base_link or odom \(\rightarrow\) base_link. If it queries the former, it will get the most accurate
estimation of the robot pose, however, that may include discontinuities or
jumps due to, for example, loop closures (e.g. Slamcore’s SLAM mode). On the
other hand, the odom \(\rightarrow\) base_link transform is guaranteed to change smoothly but may
accumulate drift over time (e.g. Slamcore’s VIO mode).
In a traditional robot setup, the localisation module, for example slam_toolbox,
will ingest lidar sensor data and the latest odom \(\rightarrow\) base_link transform, as published by an
odometry node (e.g. dead reckoning via wheel odometry) to calculate map \(\rightarrow\) base_link and
eventually publish the map \(\rightarrow\) odom transform to abide to REP-105.
To abide to this standard and also increase the overall accuracy of these
transforms, the Slamcore ROS Wrappers incorporate the latest odometry
information and publish both the map \(\rightarrow\) odom and odom \(\rightarrow\) base_link transforms. This way the
user can access the map \(\rightarrow\) odom transform, as well as, a smooth odom \(\rightarrow\) base_link transform that
uses information from the visual and inertial sensors and wheel odometry (if a
VIK calibration has been generated). This is preferred over just using the odom \(\rightarrow\) base_link
transform provided by a wheel odometry node, which would be less accurate and
robust.
Fig. 82 Main ROS frames of reference during a forward motion of the camera using Slamcore
Fig. 83 Full ROS TF tree and frames of reference during a forward motion of the camera using Slamcore