Skip to content

Frame conventions

Rhys edited this page Sep 20, 2021 · 2 revisions

Gazebo versus ArduPilot frame conventions

Gazebo and ArduPilot use different conventions to orient the inertial reference frames of the worlds and the body frames of the vehicles. Care is required to ensure that the data measured by the IMU sensor and the pose and velocity information from the physics engine is correctly oriented.

ArduPilot assumes an aircraft convention for body and world frames:

  • ArduPilot world frame is: x-north, y-east, z-down (NED),
  • ArduPilot body frame is: x-forward, y-right, z-down.

Gazebo assumes a frame convention:

  • Gazebo world frame is: x-north, y-west, z-up,
  • Gazebo body frame is: x-forward, y-left, z-up.

In some cases the Gazebo body frame may use a non-standard convention, for example the Zephyr delta wing model has x-left, y-back, z-up.

The position and orientation provided to ArduPilot must be given as the transform from the Aircraft world frame to the Aircraft body frame. We denote this pose as:

wldABdyA = ,

by which we mean that a vector expressed in Aircraft body frame coordinates may be represented in Aircraft world frame coordinates by the transform:

.

i.e. a rotation from the world to body frame followed by a translation.

Combining transforms

Gazebo supplies us with the transform from the Gazebo world frame to the Gazebo body frame (which we recall may have a non-standard orientation)

wldGToBdyG = .

The transform from the Aircraft world frame to the Gazebo world frame is fixed:

wldAToWldG = = Pose3d(0, 0, 0, -PI, 0, 0).

Note that this is the inverse of the plugin parameter

<gazeboXYZToNED>0, 0, 0, PI, 0, 0</gazeboXYZToNED>, 

which tells us how to rotate a Gazebo world frame into an Aircraft world frame.

The transform from the Aircraft body frame to the Gazebo body frame is denoted:

bdyAToBdyG = .

This will typically be Pose3d(0, 0, 0, -PI, 0, 0), but in some instances a different convention will be chosen: for instance the Zephyr uses the transform Pose3d(0, 0, 0, -PI, 0, PI/2). Note that bdyAToBdyG is the inverse of the plugin parameter <modelXYZToAirplaneXForwardZDown> which tells us how to rotate a Gazebo model frame into an Aircraft body frame.

Finally we compose the transforms to get the one required for the ArduPilot JSON interface:

wldAToBdyA = ,

where we use:

.

In the plugin using C++ variables names and Pose3d operations this appears as:

wldAToBdyA = wldAToWldG * wldGToBdyG * bdyAToBdyG.Inverse()
Clone this wiki locally