Skip to content

ReferenceFrames

Connor Jakubik edited this page Jan 30, 2024 · 14 revisions
Home → Reference Frames

Up to date for Platform 0.18.0.

Written by Connor Jakubik.


ReferenceFrames Frame Transformation Engine

In order to greatly reduce the vector math code required to do dynamics work that involves lots of rotating and accelerating reference frames, the SC_Math::ReferenceFrames::Frame class was made. This class presents an interface to transform a Location, Velocity, Acceleration, Rotation, Angular Velocity, or (unitless) Vector from an original frame to the frame represented by the Frame object. With this interface, you can do things like get an Entity's acceleration with respect to an entirely separate entity's rotating and accelerating body-fixed frame. This is particularly useful for dynamics modeling and sensor space transformations.

All entities in a Platform simulation have a body-fixed frame and a body-centered frame. All entities hold an EntityRef param ("Dynamics"/"ResidentFrame") for their ResidentFrame, which points to an Entity to use the body-fixed frame of. An entity's ResidentFrame is the frame the state parameters like Location and Velocity are expressed in.

Transforming frames includes effects from 2nd derivative Transport Theorem. For example, all of this is applied for transforming an acceleration:

  • rotation
  • relative acceleration
  • Euler acceleration (alpha x r term) from Transport Theorem
  • Coriolis accel (2*omega x v term) from 2nd derivative Transport Theorem
  • Centripetal accel (omega x (omega x r) term) from 2nd derivative Transport Theorem

Sim Base Frame

The default reference frame for the simulation is the Sim Base Frame (SimGlobals::GetBaseFrame()). For convenience, the body-fixed frame of the SimEntity corresponds to the Sim Base Frame. If no ResidentFrame is set for an Entity (the param doesn't exist), the Entity's state parameters are expressed in Sim Base Frame.

The physical significance of the Sim Base Frame depends on the simulation. Commonly, the Spicy system is used to drive celestial body motion. Whatever NAIF Object ID the "observer" is set to will determine the origin of the Sim Base Frame, and the "observerframe" will determine the basis vectors (rotation).

Typical Spicy listing in "Systems" on a Sim Config:

{
	"Nametag": "Spicy",
	"Source": "Spicy/bin/Spicy",
	"Type": "Normal",
	"Active": true,
	"Frequency": 200.0,
	"Inst_Parameters": {
		"observer": "SSB",
		"observerframe": "J2000"
	}
}

This shows Spicy being configured with the Solar System Barycenter (SSB) as the coordinate origin for the Sim Base Frame, and the J2000 frame as the coordinate basis vectors ("J2000" in SPICE coincides exactly with the International Celestial Reference Frame (ICRF)). Some related SPICE documentation: https://naif.jpl.nasa.gov/pub/naif/toolkit_docs/Tutorials/pdf/individual_docs/17_frames_and_coordinate_systems.pdf.

GraphicsFrame

GraphicsFrame (#Pawn/GraphicsFrame), an EntityRef parameter on each Pawn, defines the frame that Unreal uses for its coordinate origin (before rebasing happens). The GraphicsFrame is determined by checking the currently-possessed pawn, so it can be unique per Unreal client. The parameter value for "GraphicsFrame" in the sim config only holds the initial value; the parameter can be updated through the ReevaluateGraphicsFrame Blueprint function, which changes the frame based on the pawn's proximity to something like an Entity_Planet. ReevaluateResidentFrame works in a similar way.

Entity frame-based getters/setters

These functions are declared in Entity_Base.h:

	// Get time-extrapolated location of this entity (meters, right handed coordinates).
	SC_Math::ReferenceFrames::FramedLoc getLocation(sc_tai_time simtime = SimGlobals::GetTimeInContext()) const;
	// Get the orientation of this entity's body frame (right handed coordinates).
	SC_Math::ReferenceFrames::FramedRot getRotation(sc_tai_time simtime = SimGlobals::GetTimeInContext()) const;
	// Get time-extrapolated location and velocity of this entity (meters, meters/second, right handed coordinates).
	SC_Math::ReferenceFrames::FramedLocVel getRV(sc_tai_time simtime = SimGlobals::GetTimeInContext()) const;
	// Get time-extrapolated velocity of this entity (meters/second, right handed coordinates).
	SC_Math::ReferenceFrames::FramedLocVel getVelocity(sc_tai_time simtime = SimGlobals::GetTimeInContext()) const;
	// Get time-extrapolated angular velocity of this entity (rad/second, right handed coordinates).
	// The vector direction is the axis of rotation, and the magnitude of the vector is the
	// speed of the right-handed rotation around that axis.
	SC_Math::ReferenceFrames::FramedAngVel getAngVelocity(sc_tai_time simtime = SimGlobals::GetTimeInContext()) const;

	// Get time-extrapolated location, velocity, and acceleration of this entity (meters, meters/second, meters/second^2, right handed coordinates).
	SC_Math::ReferenceFrames::FramedLocVelAcc getRVA(sc_tai_time simtime = SimGlobals::GetTimeInContext()) const;

	// Get time-extrapolated acceleration of this entity (meters/second^2, right handed coordinates).
	SC_Math::ReferenceFrames::FramedLocVelAcc getAcceleration(sc_tai_time simtime = SimGlobals::GetTimeInContext()) const;
	// Get time-extrapolated angular acceleration of this entity (rad/second^2, right handed coordinates).
	SC_Math::ReferenceFrames::FramedAngAcc getAngAcceleration(sc_tai_time simtime = SimGlobals::GetTimeInContext()) const;

// .....

        // Set Entity Location (meters, right handed coordinates).
	void setLocation(Eigen::Vector3d loc, SC_Math::ReferenceFrames::Frame::owned fromFrame = SimGlobals::GetBaseFrame());
	// Set Entity Rotation (passive quaternion, right handed coordinates).
	void setRotation(Eigen::Quaterniond rot, SC_Math::ReferenceFrames::Frame::owned fromFrame = SimGlobals::GetBaseFrame());
	// Set Entity Rotation (passive DCM, right handed coordinates).
	void setRotation(SC_Math::ReferenceFrames::DCM rot, SC_Math::ReferenceFrames::Frame::owned fromFrame = SimGlobals::GetBaseFrame());
	// Set Entity Rotation (3-1-3 Euler angles (phi,theta,psi), radians, right handed coordinates).
	void setRotation_Euler313(Eigen::Vector3d rot, SC_Math::ReferenceFrames::Frame::owned fromFrame = SimGlobals::GetBaseFrame());
	// Set Entity Rotation (3-1-3 Euler angles (phi,theta,psi), radians, right handed coordinates).
	void setRotation_DCM(Eigen::Matrix3d rot, SC_Math::ReferenceFrames::Frame::owned fromFrame = SimGlobals::GetBaseFrame());
	// Set Entity Velocity (meters/second, right handed coordinates).
	void setVelocity(Eigen::Vector3d vel, SC_Math::ReferenceFrames::Frame::owned fromFrame = SimGlobals::GetBaseFrame());
	// Set Entity Angular Velocity (rad/second inertial frame rates, right handed coordinates).
	// The vector direction is the axis of rotation, and the magnitude of the vector is the
	// speed of the right-handed rotation around that axis.
	// (TODO may change specification)
	void setAngVelocity(Eigen::Vector3d angvel, SC_Math::ReferenceFrames::Frame::owned fromFrame = SimGlobals::GetBaseFrame());
	// Set Entity Acceleration (meters/second^2, right handed coordinates).
	void setAcceleration(Eigen::Vector3d acc, SC_Math::ReferenceFrames::Frame::owned fromFrame = SimGlobals::GetBaseFrame());
	//TODO setAngAcceleration?


	// Offset Entity Location (meters, right handed coordinates).
	void addLocationOffset(Eigen::Vector3d delta_loc, SC_Math::ReferenceFrames::Frame::owned fromFrame = SimGlobals::GetBaseFrame());
	// Set Entity Velocity (meters/second, right handed coordinates).
	void addVelocityOffset(Eigen::Vector3d delta_vel, SC_Math::ReferenceFrames::Frame::owned fromFrame = SimGlobals::GetBaseFrame());

These are the main way one should be interfacing with Entity dynamics. Using these functions, you can get and set state parameters with an arbitrary frame. You can typically ignore the simtime parameter; see Timekeeping wiki page for more info on how there might be special cases where you use a different time context for computations.

Framed State Values

The return value of the get_ functions are of type FramedLoc, FramedLocVel, FramedLocVelAcc, FramedRot, FramedAngVel, or FramedAngAcc. These classes contain a meaningful "state value" (from the dynamics term State Vector) for the body by storing a vector value and a "with-respect-to" frame. To express a state value as a 3-vector (or DCM), you need to use the .WRT(some_frame) to specify a which frame to transform the state value to. This transformation within WRT() is where the actual frame transformations happen, which take into account transport theorem (which is why for Acceleration we require a known Location and Velocity as well). The output of .WRT() is a FramedVector, which holds a vector quantity and a frame which has no remaining physical significance other than the orientation of its coordinate basis. To get a vector quantity out of a FramedVector, use the ExprIn(some_frame) function. This function only rotates the vector quantity to use a different coordinate basis (the directions of the x,y,z unit vectors).

TODO:

  • describe differences between .WRT(), .loc_WRT()/.vel_WRT()/.acc_WRT(), and how angular forms of this don't need Transport Theorem.
  • Python API

The result of this design is a very natural way to interact with dynamics transformation code. To get the state vector of an entity, FramedLocVelAcc entity_rva = entity->getRVA() or entity->getAcceleration(). To transform that state vector to be with respect to another frame, and express it in a third frame, Eigen::Vector3d acceleration = entity_rva.acc_WRT(frame_1).ExprIn(frame_2).

Usage example: moving an Entity 10 meters in the +x direction in Moon-fixed frame.

auto moon_fixed = GetBodyFixedFrame(moon_en);
auto loc_wrt_moon = en->getLocation().WRT(moon_fixed).ExprIn(moon_fixed);
loc_wrt_moon += Vector3d{10,0,0};
en->setLocation(loc_wrt_moon, moon_fixed);

This particular example can also be achieved with the addLocationOffset() function.

Physics Functions

	// Get Entity Mass (kilograms).
	double getMass() const;
	// Get Entity Inertia Tensor (kilogram * meters^2, 3x3 symmetric matrix, right handed coordinates).
	Eigen::Matrix3d getInertiaTensor(SC_Math::ReferenceFrames::Frame::owned inFrame = SimGlobals::GetBaseFrame(),
		sc_tai_time simtime = SimGlobals::GetTimeInContext()) const;
	// Get Entity Force (Newtons, right handed coordinates).
	// Interim solution for modular propagators before we have PhysicalEffects.
	Eigen::Vector3d getForce(SC_Math::ReferenceFrames::Frame::owned inFrame = SimGlobals::GetBaseFrame(),
		sc_tai_time simtime = SimGlobals::GetTimeInContext()) const;
	// Get Entity Torque (Newton-meters, right handed coordinates).
	// Interim solution for modular propagators before we have PhysicalEffects.
	Eigen::Vector3d getTorque(SC_Math::ReferenceFrames::Frame::owned inFrame = SimGlobals::GetBaseFrame(),
		sc_tai_time simtime = SimGlobals::GetTimeInContext()) const;
//.....
	
        // Set Entity Force (Newtons, right handed coordinates).
	// Interim solution for modular propagators before we have PhysicalEffects.
	void setForce(Eigen::Vector3d force, SC_Math::ReferenceFrames::Frame::owned fromFrame = SimGlobals::GetBaseFrame());
	// Set Entity Torque (Newton-meters, right handed coordinates).
	// Interim solution for modular propagators before we have PhysicalEffects.
	void setTorque(Eigen::Vector3d torque, SC_Math::ReferenceFrames::Frame::owned fromFrame = SimGlobals::GetBaseFrame());

There are a few more standardized Dynamics parameters besides the state variables. These define a common interface for piping force and torque values (and mass properties) into the RigidBodyPropagator System and other compatible things. RigidBodyPropagator relies on the Force and Torque values being set externally by, for example, a thruster firing System. In the RigidBodyPropagator loop it uses one of a few propagators (Free Body, Two-Body Gravity, etc) to propagate a body with the Force and Torque values taken as "control" input (in Dynamics terms).

ReferenceFrames Internals

These are nitty-gritty details that you probably don't need to be concerned about unless you're troubleshooting frame math or making your own frame.

Each Frame subclass overrides these virtual functions:

virtual Eigen::Vector3d transform_loc_from_parent(Eigen::Vector3d r_P_parent) = 0;
virtual Eigen::Vector3d transform_loc_to_parent(Eigen::Vector3d r_P_Q_this) = 0;
virtual rv_struct transform_vel_from_parent(rv_struct rv_P_parent) = 0;
virtual rv_struct transform_vel_to_parent(rv_struct rv_P_Q_this) = 0;
virtual rva_struct transform_acc_from_parent(rva_struct rva_P_parent) = 0;
virtual rva_struct transform_acc_to_parent(rva_struct rva_P_Q_this) = 0;
virtual DCM transform_rot_from_parent(DCM rot) = 0;
virtual DCM transform_rot_to_parent(DCM rot) = 0;
virtual Eigen::Vector3d transform_angvel_from_parent(Eigen::Vector3d angvel) = 0;
virtual Eigen::Vector3d transform_angvel_to_parent(Eigen::Vector3d angvel) = 0;
virtual Eigen::Vector3d transform_vec_from_parent(Eigen::Vector3d vec) = 0;
virtual Eigen::Vector3d transform_vec_to_parent(Eigen::Vector3d vec) = 0;

The from_parent functions take in a value expressed-in and with-respect-to the parent frame, and apply the proper transformations to return that value expressed-in and with-respect-to this frame. The to_parent functions take in a value expressed-in and with-respect-to this frame, and apply the proper transformations to return that value expressed-in and with-respect-to the parent frame.

OperateFrameToFrame_UpThenDown can then do arbitrary frame-to-frame transformations by getting the common parent frame in the tree of frames, transforming to-parent until at the common parent, then transforming from-parent until at the destination frame.

DynamicFrame

For simple frames like StaticFrame, this is easy; there is a quick solution for the from_/to_parent functions. For frames that are dynamically defined (DynamicFrame), this is made more difficult. The DynamicFrame class implements a translation layer for the from_/to_parent functions to these:

// Get location of this frame wrt the parent frame, expressed in the parent frame.
virtual Eigen::Vector3d get_rel_location() = 0;
// Get velocity of this frame wrt the parent frame, expressed in the parent frame.
virtual Eigen::Vector3d get_rel_velocity() = 0;
// Get acceleration of this frame wrt the parent frame, expressed in the parent frame.
virtual Eigen::Vector3d get_rel_acceleration() = 0;
// Get the passive rotation transformation matrix from parent frame to this frame.
virtual DCM get_rel_rotation() = 0;
// Get angular velocity of this frame wrt the parent frame, expressed in the parent frame.
virtual Eigen::Vector3d get_rel_ang_velocity() = 0;
// Get angular acceleration of this frame wrt the parent frame, expressed in the parent frame.
virtual Eigen::Vector3d get_rel_ang_acceleration() = 0;

DynamicFrame implements the from_/to_parent functions internally, and those functions constitute the full 2nd derivative Transport Theorem. Subclasses of DynamicFrame are only required to implement the above getter functions for individual relative state parameters of the frame with respect to its parent frame.

Making your own Frame class

For most applications, you'll probably be able to define your custom Frame class as a subclass of DynamicFrame. There are a few examples of this in Entity_Base.h. Read the DynamicFrame get_rel_ comments carefully and fill out these functions. To do this properly often requires engineering masters-level dynamics knowledge or more. You will need to make many (5+) passing unit tests of transforming locations, velocities, rotations, etc before you should start to trust the new frame you made for engineering work.

Issues of continuing concern

  • We are limited to assumed-inertial frames for the Graphics Frame if we want to allow the Unreal Client to perform physics calculations as it is accustomed to.
  • Should we, instead of a boolean for AssumedInertial, have some sort of rating factor for "how inertial it is", maybe an approximated maximum non-inertial acceleration of the frame for both linear and angular acceleration? Such an approximated maximum could be specified in the frame definition, or possibly derived from runtime sim use.
  • AssumedInertial should probably be used as a kind of "ignore how bad this assumption is" sort of thing, with room made for a smarter calculation somewhere else for alerting when state vector calculation exceeds approximate non-inertial acceleration. We could also make a warning if angular velocity gets rather high for an inertial frame.