Mandala variables
All parameters of the vehicle state are organized in structured tree of values. The definition of the structure, called mandala is described in this section.
Data items are shared between node modules and other nodes by means of publisher/subscriber framework, which is managed by mdb broker.
The tree consists of the following levels:
class:sns,ctr,est,cmd(2 bits);type:nav,env(1 bit);subsystem: up to 15 subsystems (4 bits);field: up to 15 fields (4 bits);
The unique identifier of any value consists of 11 bits. Each packet in the network uses mandala uid to address pub/sub values.
Data access
Mandala tree is available in GCS Java Script context and facts tree and created for every recognized vehicle.
GCS UI and JS context have simplified structure, where
typecomponent is omitted. Moreover, on GCS side - radians are converted to degrees.
F.ex., in GCS Terminal, which evaluates in JS context, any mandala value item, of the current selected vehicle, can be accessed as class.subsystem.field reference:
cmd.pos.altitude=800will set commanded altitude to 800m;ctr.wing.flaps=0.8extracts flaps to 80%;cmd.proc.mode = proc_mode_TAXIwill enter TAXI procedure;cmd.proc.action = proc_action_nextwill trigger the next stage of the current procedure;
The examples above are using shortcuts with pre-defined getters/setters of the
Factobject’svalueproperty.
Another way to access mandala field Fact of a vehicle form the JS context is to use the following reference form:
apx.vehicles.current.mandala.cmd.pos.altitude.value=800will set commanded altitude of the current selected vehicle to 800m;
Data synchronization
Since GCS has dedicated mandala tree for every detected vehicle, the data in this tree (values) is synchronized with the current vehicle state by means of:
- telemetry stream (usually this is the only data source);
- any data packets received and decoded from interfaces;
On the onboard network and between nodes the data is synchronized by mdb module.
Some special mandala fields are synchronized by bundles. This happens when to have atomic data packages is required. F.ex., for IMU sensors data packages or to set commanded position vector (lat,lon).
The fields beyond cmd.env group do not have any value associated with them, but are used as UIDs of data packets to implement different protocols for data transfer.
Data structure
-
SensorsRead only data sources, measured by sensors from physical parameters.
-
NavigationSensors used for vehicle navigation and controls. Used as input for position and attitude estimators and for filters to supply aerodynamic controls.
-
GyroGyro bundle status shared with GCS
-
srcGyro sourcereal[unknown,local,primary,secondary,failsafe,auxillary] -
cntGyro devicesbyte -
tempGyro temperaturereal[C] -
clipGyro clip countbyte -
vibGyro vibrationbyte[%] -
coningGyro coning vibrationreal[rad^2]
-
-
Accelerometer-
srcAccelerometer sourcereal[unknown,local,primary,secondary,failsafe,auxillary] -
cntAccelerometer devicesbyte -
tempAccelerometer temperaturereal[C] -
clipAccelerometer clip countbyte -
vibAccelerometer vibrationbyte[%]
-
-
Magnetometer-
srcMagnetometer sourcereal[unknown,local,primary,secondary,failsafe,auxillary] -
cntMagnetometer devicesbyte -
tempMagnetometer temperaturereal[C] -
vibMagnetometer vibrationbyte[%] -
normMagnetometer magnitudereal[u] -
declMagnetometer declinationreal[rad] -
biasMagnetometer biasreal[u] -
bvalMagnetometer bias validityreal[%]
-
-
GPS-
srcGps sourcereal[unknown,local,primary,secondary,failsafe,auxillary] -
cntGps devicesbyte -
fixGps fix typereal[none,2D,3D,DIFF,RTK] -
emiGps emi statusreal[unknown,ok,warning,critical,spoofing] -
haccGps horizontal position accuracyreal[m] -
vaccGps vertical position accuracyreal[m] -
saccGps speed accuracyreal[m/s] -
pdopGps position dilution of precisionreal -
svGps visible satellitesword -
suGps used satellitesword -
tempGps temperaturereal[C]
-
-
Static pressure-
srcStatic pressure sourcereal[unknown,local,primary,secondary,failsafe,auxillary] -
cntStatic pressure devicesbyte -
statusBaroreal[unknown,available,warning,critical,failure] -
mbarAbsolute pressurereal[mbar] -
tempBarometer temperaturereal[C]
-
-
Dynamic pressure-
srcDynamic pressure sourcereal[unknown,local,primary,secondary,failsafe,auxillary] -
cntDynamic pressure devicesbyte -
validDynamic pressure validated devicesbyte -
statusPitotreal[unknown,available,warning,critical,failure] -
airspeedAirspeedreal[m/s] -
accAirspeed derivativereal[m/s^2] -
tempPitot probe temperaturereal[C] -
rawDynamic pressurereal[kPa]
-
-
Altitude above ground sensors-
srcAgl sourcereal[none,laser,radio,sonic] -
statusAglreal[off,valid] -
laserLaser agl altitudereal[m] -
radioRadio agl altitudereal[m] -
sonicUltrasonic agl altitudereal[m] -
groundGroundreal[unknown,landed,flying]
-
-
Aerodynamic sensors-
slipSlipreal[rad] -
aoaAngle of attackreal[rad] -
tempAmbient air temperaturereal[C] -
buoBlimp ballonet pressurereal[kPa]
-
-
RTK-
rollRtk rollreal[rad] -
pitchRtk pitchreal[rad] -
yawRtk yawreal[rad]
-
-
Landing Assistance sensorsUsed for approach correction.
-
statusLas statusreal[ok,holdon,cancel] -
dxRelative distance xreal[m] -
dyRelative distance yreal[m] -
dzRelative distance zreal[m] -
vxRelative velocity xreal[m/s] -
vyRelative velocity yreal[m/s] -
vzRelative velocity zreal[m/s]
-
-
PlatformUsed for landing to a moving platform with las.
-
latPlatform latitudedword[gps] -
lonPlatform longitudedword[gps] -
hmslPlatform altitude mslreal[m] -
vnPlatform velocity northreal[m/s] -
vePlatform velocity eastreal[m/s] -
vdPlatform velocity downreal[m/s] -
rollPlatform rollreal[rad] -
pitchPlatform pitchreal[rad] -
yawPlatform yawreal[rad]
-
-
Visual navigationUsed for global position estimation and dead-reckoning.
-
vxVisual velocity xreal[m/s] -
vyVisual velocity yreal[m/s] -
vzVisual velocity zreal[m/s] -
dxVisual delta xreal[m] -
dyVisual delta yreal[m] -
dzVisual delta zreal[m] -
rollVisual rollreal[rad] -
pitchVisual pitchreal[rad] -
yawVisual yawreal[rad] -
latVisual latitudedword[gps] -
lonVisual longitudedword[gps] -
hmslVisual altitude mslreal[m] -
altitudeVisual altitudereal[m]
-
-
Collision avoidance-
distDistance to targetreal[m] -
hdgHeading to targetreal[rad] -
elvElevation to targetreal[rad] -
velVelocity of targetreal[m/s]
-
-
-
EnvironmentEnvironmental sensors. Data used as inputs for filters to estimate vehicle state and safety conditions.
-
Engine-
rpmEngine rpmreal[rpm] -
torqueEngine torquereal[Nm] -
tempEngine temperaturereal[C] -
otOil temperaturereal[C] -
egtExhaust temperaturereal[C] -
egtdExhaust delta temperaturereal[C] -
opOil pressurereal[bar] -
mapManifold absolute pressurereal[Pa] -
iapIntake air box pressurereal[kPa] -
voltageEngine ecu voltagereal[V] -
currentEngine ecu currentreal[A] -
healthEngine health statusreal[unknown,idle,running,warning,failure] -
tcTurbochargerreal[unknown,off,active,warning,critical,failure]
-
-
Gearbox-
statusGearbox statusreal[unknown,ok,warning,failure] -
rpmGearbox rpmreal[rpm] -
tempGearbox temperaturereal[C] -
clutchClutchreal[on,off,busy]
-
-
Prop-
statusProp statusreal[unknown,ok,warning,failure] -
rpmProp rpmreal[rpm] -
pitchProp pitch positionreal[su] -
thrustProp thrustreal[N]
-
-
Generator-
statusGenerator statusreal[unknown,ok,idle,free,warning,failure] -
rpmGenerator rpmreal[rpm] -
voltageGenerator voltagereal[V] -
currentGenerator currentreal[A] -
tempGenerator temperaturereal[C]
-
-
Fuel-
levelFuel levelbyte[%] -
rateFuel flow ratereal[%/h] -
tempFuel temperaturereal[C] -
psFuel pressurereal[bar]
-
-
Battery-
statusBatreal[unknown,ok,charging,shutdown,warning,failure] -
voltageBattery voltagereal[V] -
currentBattery currentreal[A] -
capacityBattery capacityreal[Ah] -
tempBattery temperaturereal[C]
-
-
Power-
statusPower statusreal[unknown,ok,shutdown,warning,failure] -
vsysSystem voltagereal[V] -
isysSystem currentreal[A] -
vsrvServo voltagereal[V] -
isrvServo currentreal[A] -
vpldPayload voltagereal[V] -
ipldPayload currentreal[A]
-
-
Datalink-
statusDatalink statusreal[unknown,ok,muted,busy,warning,failure] -
rssReceived signal strengthbyte[%] -
snrSignal to noise ratioreal[u] -
tempModem temperaturereal[C] -
voltageModem voltagereal[V] -
currentModem currentreal[A] -
hdgRadio headingreal[rad] -
dmeRadio distancereal[m] -
rollAntenna rollreal[rad] -
pitchAntenna pitchreal[rad] -
yawAntenna yawreal[rad]
-
-
Auxillary sensors-
srvMaintenance service switchreal[off,on] -
rtRoom temperaturereal[C] -
gearLanding gearreal[down,retracted] -
fgearLanding gear forcereal[u]
-
-
Emergency Rescue System-
statusErs statusreal[unknown,ok,disarmed,busy,failure] -
blockErs disable switchreal[off,on]
-
-
Servo-
posEncoder positionreal[su] -
dposDelta positionreal[su] -
powerPowerreal[su]
-
-
Camera sensors-
rollCam rollreal[rad] -
pitchCam pitchreal[rad] -
yawCam yawreal[rad] -
drollDelta rollreal[rad] -
dpitchDelta pitchreal[rad] -
dyawDelta yawreal[rad] -
fovCam field of viewreal[rad] -
rangePayload rangereal[m]
-
-
Turret sensors-
rollTurret rollreal[rad] -
pitchTurret pitchreal[rad] -
yawTurret yawreal[rad] -
statusTurret statusreal[ready,shooting,reloading] -
capacityPayload capacitybyte
-
-
-
-
ControlsControls for vehicle drives and servos. Published by regulators.
-
NavigationControls used for vehicle stabilization. Data published by controllers for aerodynamic controls.
-
Attitude controls-
ailAileronsreal[su] -
elvElevatorreal[su] -
rudRudderreal[su]
-
-
Engine controls-
thrThrottlereal[u] -
propProp pitchreal[su] -
chokeChokereal[u] -
tuneEngine tuningreal[su] -
tvecThrust vectorreal[su] -
starterEngine starterreal[off,on] -
ign1Ignition 1real[off,on] -
ign2Ignition 2real[off,on] -
fpumpFuel pumpreal[off,on]
-
-
Wing mechanization-
flapsFlapsreal[u] -
airbrkAirbrakesreal[u] -
slatsSlatsreal[u] -
sweepSweepreal[su] -
buoBuoyancyreal[su]
-
-
Steering controls-
brakeBrakereal[u] -
rudSteeringreal[su] -
gearLanding gearreal[down,retract]
-
-
-
EnvironmentEnvironmental controls. Data generated by internal logic.
-
Power-
apPower avionicsreal[off,on] -
servoPower servoreal[off,on] -
engPower enginereal[off,on] -
payloadPower payloadreal[off,on] -
aglPower aglreal[off,on] -
xpdrPower xpdrreal[off,on] -
satcomPower satcomreal[off,on] -
rfampPower rf amplifierreal[off,on] -
icePower anti-icereal[off,on] -
lasPower landing assistancereal[off,on]
-
-
Emergency Recovery-
launchErs launchreal[off,on] -
relErs releasereal[locked,released]
-
-
Lighting-
navNavigation lightsreal[off,on] -
taxiTaxi lightsreal[off,on] -
beaconBeacon lightreal[off,on] -
landingLanding lightsreal[off,on] -
strobeStrobe lightsreal[off,on]
-
-
Doors and latches-
mainMain doorreal[locked,open] -
dropDrop-offreal[locked,open]
-
-
Auxillary-
hornHorn signalreal[off,on]
-
-
User switches-
sw1Switch 1real[off,on] -
sw2Switch 2real[off,on] -
sw3Switch 3real[off,on] -
sw4Switch 4real[off,on] -
sw5Switch 5real[off,on] -
sw6Switch 6real[off,on] -
sw7Switch 7real[off,on] -
sw8Switch 8real[off,on] -
sw9Switch 9real[off,on] -
sw10Switch 10real[off,on] -
sw11Switch 11real[off,on] -
sw12Switch 12real[off,on] -
sw13Switch 13real[off,on] -
sw14Switch 14real[off,on] -
sw15Switch 15real[off,on]
-
-
User tuning-
t1Tuning 1real[su] -
t2Tuning 2real[su] -
t3Tuning 3real[su] -
t4Tuning 4real[su] -
t5Tuning 5real[su] -
t6Tuning 6real[su] -
t7Tuning 7real[su] -
t8Tuning 8real[su] -
t9Tuning 9real[su] -
t10Tuning 10real[su] -
t11Tuning 11real[su] -
t12Tuning 12real[su] -
t13Tuning 13real[su] -
t14Tuning 14real[su] -
t15Tuning 15real[su]
-
-
Camera-
rollCamera ctr rollreal[su] -
pitchCamera ctr pitchreal[su] -
yawCamera ctr yawreal[su] -
recCamera recordreal[off,on] -
shotCamera shotreal[off,single,series] -
armCamera arm focusreal[off,on] -
zinCamera zoom inreal[off,on] -
zoutCamera zoom outreal[off,on] -
auxCamera auxillary controlbyte
-
-
ATS controls-
rollAts ctr rollreal[su] -
pitchAts ctr pitchreal[su] -
yawAts ctr yawreal[su]
-
-
Turret controls-
rollTurret ctr rollreal[su] -
pitchTurret ctr pitchreal[su] -
yawTurret ctr yawreal[su] -
opTurret opreal[off,arm,shoot,shooting,reload]
-
-
-
-
EstimatorsCurrent vehicle state. Estimated values of sensors and current navigator status.
-
NavigationEstimated data used for vehicle regulators. Filtered sensor data.
-
Angular rate-
validAngular rate validityreal[no,yes] -
xAngular rate xreal[rad/s] -
yAngular rate yreal[rad/s] -
zAngular rate zreal[rad/s] -
axAngular acceleration xreal[rad/s^2] -
ayAngular acceleration yreal[rad/s^2] -
azAngular acceleration zreal[rad/s^2] -
turnTurn ratereal[rad/s]
-
-
Acceleration-
validAcceleration validityreal[no,yes] -
xAcceleration xreal[m/s^2] -
yAcceleration yreal[m/s^2] -
zAcceleration zreal[m/s^2]
-
-
Attitude-
statusAttitude statusreal[unknown,ok,busy,warning,critical,failure] -
validAttitude validityreal[no,yes] -
rollAttitude rollreal[rad] -
pitchAttitude pitchreal[rad] -
yawAttitude yawreal[rad]
-
-
Global Position-
statusGlobal position statusreal[unknown,ok,busy,warning,critical,failure] -
validGlobal position validityreal[no,yes] -
latLatitudedword[gps] -
lonLongitudedword[gps] -
hmslAltitude mslreal[m] -
bearingMoving directionreal[rad] -
speedGround speedreal[m/s] -
altitudeFlight altitudereal[m] -
vspeedVertical speedreal[m/s] -
aglAltitude above groundreal[m]
-
-
Local position-
statusLocal position statusreal[unknown,ok,busy,warning,critical,failure] -
axLinear acceleration xreal[m/s^2] -
ayLinear acceleration yreal[m/s^2] -
azLinear acceleration zreal[m/s^2] -
vxVelocity xreal[m/s] -
vyVelocity yreal[m/s] -
vzVelocity zreal[m/s] -
nNorthreal[m] -
eEastreal[m] -
dDownreal[m]
-
-
Ref point-
statusRef point statusreal[unavailable,initialized] -
latReference latitudedword[gps] -
lonReference longitudedword[gps] -
hmslMsl altitude offsetreal[m]
-
-
Air data-
airspeedAirspeedreal[m/s] -
slipSlip anglereal[rad] -
aoaAngle of attackreal[rad] -
ldGlide ratioreal[L/D] -
vseEnergy variometer correctionreal[m/s] -
rhoAir densityreal[kg/m^3] -
ktasEas to tas multiplierreal[K] -
keasIas to eas multiplierreal[K] -
stabStabilityreal[u] -
stallStallreal[unknown,ok,warning,critical]
-
-
AHRS status-
restAt restreal[no,yes] -
magMagnetometerreal[unknown,3D,HDG,blocked,warning,failure] -
hrefHeight referencereal[none,baro,gps,range,vision] -
ephEstimated horizontal position errorreal[m] -
epvEstimated vertical position errorreal[m] -
dnDelta northreal[m] -
deDelta eastreal[m] -
dhDelta heightreal[m]
-
-
Wind estimator-
statusWindreal[unknown,available] -
speedWind speedreal[m/s] -
headingWind headingreal[rad]
-
-
EngineEngine estimated and filtered values
-
statusEngine statusreal[idle,ok,warning,failure] -
rpmEngine rpmreal[rpm] -
drpmEngine rpm ratereal[rpm/s]
-
-
Mission navigation-
statusManeuver statusreal[ongoing,ok] -
etaEstimated time of arrivalword[s] -
xtrackCrosstrack errorreal[m] -
deltaTouchdown errorreal[m] -
distDistance to waypointreal[m] -
hdgWaypoint headingreal[rad] -
thdgTangent headingreal[rad]
-
-
-
EnvironmentProcessed data of current vehicle conditions. Can be overridden by GCS uplink.
-
System-
modeSystem modereal[busy,ground,check,taxi,ready,airborne] -
healthSystem healthreal[unknown,normal,warning,critical] -
timeSystem timedword[s]GPS time or when not available - system CPU time.
-
uptimeUptimedword[ms]Number of milliseconds passed since system powered on. Value updated by
telemetrymodule. Used for telemetry purposes only. -
fuelFuel capacitybyte[%] -
weightVehicle weightword[kg] -
ttlTime to liveword[min] -
rangeMaximum rangeword[km] -
corrCorrelator outputreal[K]
-
-
ATS-
rollAts rollreal[rad] -
pitchAts pitchreal[rad] -
yawAts yawreal[rad] -
latAts latitudedword[gps] -
lonAts longitudedword[gps] -
hmslAts altitude mslreal[m]
-
-
CamCamera axis est
-
rollCam rollreal[rad] -
pitchCam pitchreal[rad] -
yawCam yawreal[rad] -
latCam latitudedword[gps] -
lonCam longitudedword[gps] -
hmslCam altitude mslreal[m]
-
-
TurretTurret axis est
-
rollTurret rollreal[rad] -
pitchTurret pitchreal[rad] -
yawTurret yawreal[rad] -
latTurret latitudedword[gps] -
lonTurret longitudedword[gps] -
hmslTurret altitude mslreal[m]
-
-
HAPS-
shapeHaps dihedral anglereal[rad] -
cshapeHaps cmd dihedral anglereal[rad] -
rollHaps central rollreal[rad] -
roll1Haps roll1real[rad] -
roll2Haps roll2real[rad] -
pitch1Haps pitch1real[rad] -
pitch2Haps pitch2real[rad] -
cpitch1Haps cmd pitch1real[rad] -
cpitch2Haps cmd pitch2real[rad] -
spd1Haps airspeed1real[m/s] -
spd2Haps airspeed2real[m/s] -
ail1Haps aileron1real[su] -
ail2Haps aileron2real[su]
-
-
User values (float 16 bits)-
u1Usr 1real -
u2Usr 2real -
u3Usr 3real -
u4Usr 4real -
u5Usr 5real -
u6Usr 6real -
u7Usr 7real -
u8Usr 8real -
u9Usr 9real -
u10Usr 10real -
u11Usr 11real -
u12Usr 12real -
u13Usr 13real -
u14Usr 14real -
u15Usr 15real
-
-
User bytes (8 bits)-
b1Usrb 1byte -
b2Usrb 2byte -
b3Usrb 3byte -
b4Usrb 4byte -
b5Usrb 5byte -
b6Usrb 6byte -
b7Usrb 7byte -
b8Usrb 8byte -
b9Usrb 9byte -
b10Usrb 10byte -
b11Usrb 11byte -
b12Usrb 12byte -
b13Usrb 13byte -
b14Usrb 14byte -
b15Usrb 15byte
-
-
User words (16 bits)-
w1Usrw 1word -
w2Usrw 2word -
w3Usrw 3word -
w4Usrw 4word -
w5Usrw 5word -
w6Usrw 6word -
w7Usrw 7word -
w8Usrw 8word -
w9Usrw 9word -
w10Usrw 10word -
w11Usrw 11word -
w12Usrw 12word -
w13Usrw 13word -
w14Usrw 14word -
w15Usrw 15word
-
-
User precision values (float 32 bits)-
f1Usrf 1real -
f2Usrf 2real -
f3Usrf 3real -
f4Usrf 4real -
f5Usrf 5real -
f6Usrf 6real -
f7Usrf 7real -
f8Usrf 8real -
f9Usrf 9real -
f10Usrf 10real -
f11Usrf 11real -
f12Usrf 12real -
f13Usrf 13real -
f14Usrf 14real -
f15Usrf 15real
-
-
User double words (32 bits)-
x1Usrx 1dword -
x2Usrx 2dword -
x3Usrx 3dword -
x4Usrx 4dword -
x5Usrx 5dword -
x6Usrx 6dword -
x7Usrx 7dword -
x8Usrx 8dword -
x9Usrx 9dword -
x10Usrx 10dword -
x11Usrx 11dword -
x12Usrx 12dword -
x13Usrx 13dword -
x14Usrx 14dword -
x15Usrx 15dword
-
-
-
-
CommandsCommanded values. Received from the GCS or provided by navigator as commands for regulators.
-
NavigationCommanded values generated by controllers.
-
Procedures-
modeProcedurereal[EMG,RPV,UAV,WPT,STBY,TAXI,TAKEOFF,LANDING] -
stageProcedure stagebyte -
wpSelected waypointword -
rwSelected runwayword -
piSelected point of interestword -
actionProcedure actionreal[idle,next,reset,inc,dec] -
adjManeuver adjustreal[m] -
loopsRemaining loopsword -
timeoutProcedure timeoutword[s]
-
-
Regulators configuration-
attAttitude controlreal[off,on] -
posPosition controlreal[off,hdg,direct,track,loiter,hover] -
spdAirspeed controlreal[off,on] -
altAltitude controlreal[off,on,rate] -
engEngine controlreal[off,on] -
yawYaw controlreal[off,hdg,slip,taxi,track] -
strSteering controlreal[off,on] -
taxiTaxi track controlreal[off,on] -
brkBrakes controlreal[off,on] -
flapsFlaps controlreal[off,on] -
airbrkAirbrakes controlreal[off,on]
-
-
AHRS options-
inairAhrs airdatareal[no,yes] -
nogpsBlock gpsreal[no,yes] -
nomagBlock magnetometerreal[no,yes] -
hselSelect height sourcereal[baro,gps,range,vision] -
haglAgl altitudereal[no,yes]
-
-
Attitude regulators-
rollCmd rollreal[rad] -
pitchCmd pitchreal[rad] -
yawCmd yawreal[rad] -
slipCmd slipreal[rad]
-
-
Position regulators-
latCmd latitudedword[gps] -
lonCmd latitudedword[gps] -
hmslCmd altitude mslreal[m] -
bearingCmd bearingreal[rad] -
airspeedCmd airspeedreal[m/s] -
altitudeCmd altitudereal[m] -
vspeedCmd vspeedreal[m/s] -
tecsTecs weighting factorreal[u] -
radiusLoiter radiusreal[m]
-
-
Engine regulators-
modeEngine modereal[auto,start,spin] -
rpmCmd rpmreal[rpm] -
cutThrottle cutreal[off,on] -
ovrThrottle overridereal[off,on] -
hglHeli gliderreal[off,on]
-
-
Remote Control-
modeRc modereal[auto,manual] -
rollRc rollreal[su] -
pitchRc pitchreal[su] -
yawRc yawreal[su] -
thrRc throttlereal[u] -
propRc propreal[su]
-
-
Camera-
zoomCam zoom levelreal[u] -
focusCam focusreal[u] -
chVideo channelbyte -
rangeRangefinderreal[off,on] -
modeShotting modereal[off,single,distance,time] -
dshotShotting distanceword[m] -
tshotShotting timeword[ms] -
pfPicture flipreal[off,on] -
nirNir filterreal[off,on] -
fmFocus modereal[auto,infinity] -
ftFocus typereal[auto,manual]
-
-
Gimbal cmd-
modeGimbal cmd modereal[off,stab,pos,speed,target,fixed,track] -
rollGimbal cmd rollreal[rad] -
pitchGimbal cmd pitchreal[rad] -
yawGimbal cmd yawreal[rad] -
brollGimbal cmd bias rollreal[rad/s] -
bpitchGimbal cmd bias pitchreal[rad/s] -
byawGimbal cmd bias yawreal[rad/s] -
latGimbal cmd latitudedword[gps] -
lonGimbal cmd latitudedword[gps] -
hmslGimbal cmd altitude mslreal[m]
-
-
ATS cmd-
modeAts cmd modereal[off,track,manual,search] -
rollAts cmd rollreal[rad] -
pitchAts cmd pitchreal[rad] -
yawAts cmd yawreal[rad] -
pAts cmd roll ratereal[rad/s] -
qAts cmd pitch ratereal[rad/s] -
rAts cmd yaw ratereal[rad/s]
-
-
Turret cmd-
modeTurret cmd modereal[off,fixed,stab,position,speed] -
rollTurret cmd rollreal[rad] -
pitchTurret cmd pitchreal[rad] -
yawTurret cmd yawreal[rad] -
pTurret cmd roll ratereal[rad/s] -
qTurret cmd pitch ratereal[rad/s] -
rTurret cmd yaw ratereal[rad/s] -
brollTurret cmd bias rollreal[rad/s] -
bipitchTurret cmd bias pitchreal[rad/s] -
byawTurret cmd bias yawreal[rad/s]
-
-
-
System data identifiersSpecial protocols and data wrappers.
-
Vehicle object data-
identVehicle identificationbytesquawkuid[ident] -
downlinkData packet from vehicle to gcsbytesquawkuid_seqpiddata... -
uplinkData packet from gcs to vehiclebytesquawk[piddata...] or empty for heartbeat -
telemetryTelemetry databytesquawkpacked data -
xpdrTransponder databytesquawkdata
-
-
Telemetry stream-
dataTelemetry databytetimehash feedfmt feedpacked data... -
formatTelemetry format arraybytereq
part, repartparts_cntformat feed block 256 bytes -
xpdrTransponder databytedata
-
-
Data streams-
vcpVirtual comm port channel databytevcp_idraw data -
calibCalibration databytesensor uidraw sensor data -
pldPayload databyte
-
-
Simulator data-
snsSensors databyte -
ctrControlsbyte -
cfgControls assignmentsbyte -
displayVisualizationbyte
-
-
Scripting commands-
vmexecExecute vm script onboardbytefunction name -
jsexecExecute js script on gcsbytescript text
-
-
Auxillary data-
gcsGcs databyteuiddata -
pldPayload databyteuiddata -
hidHuman interfacebyteuiddata
-
-
Redundancy data-
aliveAutopilot alive notifybyte
-
-
Formation data-
hapsHaps shared databyte -
leftLeft wing databyte -
rightRight wing databyte -
centerCenter wing databyte
-
-
Network Management-
searchSearch nodesbyteBroadcast request, re
-
identNode identificationbyteident_sstrings:name+version+hardwarefilenames -
fileFile operationsbytenamefop_e[data] -
rebootSystem rebootbytetype_e -
msgText messagebytetype_estring -
updUpdate parameterbytefid_tdata -
modModules treebyteop_e -
usrNode specific commandbytecmd_s[data] -
treeTrace packet routebyteuid1[uid2..uidN] -
debugDebug databytedata
-
-
-