Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Set mode #53

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open

Set mode #53

wants to merge 3 commits into from

Conversation

zhangirisz
Copy link
Contributor

Got the current mode of the plane as a string and set it in the telemetry overview protobuf message.

const MAV_CMD_DO_SET_MODE = 176;
const MAV_RESULT_ACCEPTED = 0;
const MAV_RESULT_TEMPORARILY_REJECTED = 1;
const MAV_RESULT_IN_PROGRESS = 5;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Frankly, I don't know what to do with all these constants

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}`);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These error messages are swapped

await cleanupObj.wait();
}

async function _sendCommandLong(mav, modeNumber, confirmation) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The name of this function is a little misleading since it's hardcoded to set MAV_CMD_DO_SET_MODE.
We should just abstract the whole COMMAND_LONG procedure to its own function, and then have sendMode call that procedure.

|| fields.result === MAV_RESULT_IN_PROGRESS) {
return;
} else {
let err = Error('COMMAND_ACK returned CMD ID ' + fields.result);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
let err = Error('COMMAND_ACK returned CMD ID ' + fields.result);
let err = Error('COMMAND_ACK returned CMD ID ' + fields.result);
const err = new Error(`Plane responded to mode request with error code ${fields.result}`);

@@ -193,6 +194,7 @@ test('get overview telemetry', async () => {

expect(res.status).toEqual(200);
expect(res.body.pos.lat).toBeTruthy();
expect(res.body.mode.name).toEqual('MANUAL');
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We need test coverage for setting the mode

6: 'FBWB',
7: 'CRUISE',
8: 'AUTOTUNE',
10: 'AUTO',
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

what did they do to mode 9... o_o

@oldmud0
Copy link
Member

oldmud0 commented Jun 9, 2019

This may destabilize telemetry and is not currently needed by any services, so I will merge this after competition.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants