Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions services/common/messages/telemetry.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ message Overview {
Velocity vel = 5;
Speed speed = 6;
Battery battery = 7;
string mode = 8;
}

// WGS84 in degrees
Expand Down
47 changes: 47 additions & 0 deletions services/telemetry/src/mode.js
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
import logger from './common/logger';

const mode_mapping_apm = {
0: 'MANUAL',
1: 'CIRCLE',
2: 'STABILIZE',
3: 'TRAINING',
4: 'ACRO',
5: 'FBWA',
6: 'FBWB',
7: 'CRUISE',
8: 'AUTOTUNE',
10: 'AUTO',
11: 'RTL',
12: 'LOITER',
14: 'LAND',
15: 'GUIDED',
16: 'INITIALISING',
17: 'QSTABILIZE',
18: 'QHOVER',
19: 'QLOITER',
20: 'QLAND',
21: 'QRTL',
22: 'QAUTOTUNE'
};

let unknownWarn = true;

const MAV_TYPE_FIXED_WING = 1;
const MAV_AUTOPILOT_ARDUPILOTMEGA = 3;

export function onHeartbeat(fields) {

let ov = this._overview;
ov.time = Date.now() / 1000;

if (fields.type == MAV_TYPE_FIXED_WING &&
fields.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
ov.mode = mode_mapping_apm[fields.custom_mode];
} else if (unknownWarn) {
unknownWarn = false;
if (fields.type !== MAV_TYPE_FIXED_WING)
logger.warn(`Unknown autopilot ${fields.autopilot}`);
if (fields.autopilot !== MAV_AUTOPILOT_ARDUPILOTMEGA)
logger.warn(`Unknown vehicle type ${fields.type}`);
}
}
7 changes: 5 additions & 2 deletions services/telemetry/src/plane.js
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ import logger from './common/logger';
import MavlinkSocket from './mavlink-socket';
import { receiveMission, sendMission, sendMissionCurrent } from './mission';
import { degrees, modDegrees360, modDegrees180 } from './util';
import { onHeartbeat } from './mode';

const ConnectionState = Object.freeze({
NOT_CONNECTED: Symbol('not_connected'),
Expand Down Expand Up @@ -39,7 +40,8 @@ export default class Plane {
alt: {},
vel: {},
speed: {},
battery: {}
battery: {},
mode: ''
});

// Will be assigned on each GLOBAL_POSITION_INT message.
Expand Down Expand Up @@ -245,7 +247,8 @@ export default class Plane {
'MISSION_CURRENT': this._onMissionCurrent.bind(this),
'MISSION_ITEM': this._onMissionItem.bind(this),
'VFR_HUD': this._onVfrHud.bind(this),
'SYS_STATUS': this._onSysStatus.bind(this)
'SYS_STATUS': this._onSysStatus.bind(this),
'HEARTBEAT': onHeartbeat.bind(this)
};

// Make every message definition .on
Expand Down
2 changes: 2 additions & 0 deletions services/telemetry/test/service.test.js
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ beforeAll(async () => {
await planeSitl.start();

planeIp = (await planeSitl.inspect()).NetworkSettings.IPAddress;

}, 10000);

// Stop the plane-sitl container.
Expand Down Expand Up @@ -193,6 +194,7 @@ test('get overview telemetry', async () => {

expect(res.status).toEqual(200);
expect(res.body.pos.lat).toBeTruthy();
expect(res.body.mode).toEqual('MANUAL');
});

// Take down the service once the other service tests are done.
Expand Down