Skip to content

Latest commit

 

History

History
190 lines (127 loc) · 4.22 KB

rep-0103.rst

File metadata and controls

190 lines (127 loc) · 4.22 KB

REP: 103 Title: Standard Units of Measure and Coordinate Conventions Author: Tully Foote Status: Active Type: Informational Content-Type: text/x-rst Created: 07-Oct-2010 Post-History: 30-Aug-2002

Abstract

This REP provides a reference for the units and coordinate conventions used within ROS.

Rationale

Inconsistency in units and conventions is a common source of integration issues for developers and can also lead to software bugs. It can also create unnecessary computation due to data conversion. This REP documents the standard conventions for ROS in order to lessen these issues.

Exceptions

The scope of potential robotics software is too broad to require all ROS software to follow the guidelines of this REP. However, choosing different conventions should be well justified and well documented.

For example, there are domains where the default conventions are not appropriate. Interstellar lengths are not appropriately measured in meters, and space-oriented libraries may wish to choose a different convention. There are other exceptions that different domains may wish to address.

Units

We have chosen to standardize on SI units. These units are the most consistent international standard. SI units are maintained by Bureau International des Poids et Mesures. [1] There is good documentation on Wikipedia for International System Of Units

Base Units

These are the base units which are commonly used

Quantity Unit
length meter
mass kilogram
time second
current ampere

Derived Units

SI defines seven base units and many derived units. If you are not using SI base units, you should use SI-derived units.

Good documentation can be found on Wikipedia about SI derived units

Commonly used SI-derived units in ROS are:

Quantity Unit
angle radian
frequency hertz
force newton
power watt
voltage volt
temperature celsius

Coordinate Frame Conventions

All coordinate frames should follow these conventions.

Chirality

All systems are right handed. This means they comply with the right hand rule.

Axis Orientation

In relation to a body the standard is :

  • x forward
  • y left
  • z up

In the case of cameras, there is often a second frame defined with a "_optical" suffix. This uses a slightly different convention:

  • z forward
  • x right
  • y down

Rotation Representation

There are many ways to represent rotations. The preferred order is listed below, along with rationale.

  1. quaternion
  • Compact representation
  • No singularities
  1. rotation matrix
  • No singularities
  1. fixed axis roll, pitch, yaw about X, Y, Z axes respectively
  • No ambiguity on order
  • Used for angular velocities
  1. euler angles yaw, pitch, and roll about Z, Y, X axes respectively
  • Euler angles are generally discouraged due to having 24 'valid' conventions with different domains using different conventions by default.

Covariance Representation

Linear

float64[9] linear_acceleration_covariance # 3x3 row major matrix in x, y, z order

Angular

float64[9] angular_velocity_covariance # 3x3 row major matrix about x, y, z order with fixed axes

Six Dimensional

# Row-major representation of the 6x6 covariance matrix
# The orientation parameters use a fixed-axis representation.
# In order, the parameters are:
# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
float64[36] covariance

References

[1]Bureau International des Poids et Mesures (http://www.bipm.org/en/home/)

Copyright

This document has been placed in the public domain.