AP_AccelCal: use vehicle position values from MAVLink enum

This commit is contained in:
Francisco Ferreira 2016-11-12 22:49:17 +00:00 committed by Tom Pittenger
parent c07f377eb1
commit bc661f013e
1 changed files with 6 additions and 6 deletions

View File

@ -71,22 +71,22 @@ void AP_AccelCal::update()
const char *msg; const char *msg;
switch (step) { switch (step) {
case 1: case ACCELCAL_VEHICLE_POS_LEVEL:
msg = "level"; msg = "level";
break; break;
case 2: case ACCELCAL_VEHICLE_POS_LEFT:
msg = "on its LEFT side"; msg = "on its LEFT side";
break; break;
case 3: case ACCELCAL_VEHICLE_POS_RIGHT:
msg = "on its RIGHT side"; msg = "on its RIGHT side";
break; break;
case 4: case ACCELCAL_VEHICLE_POS_NOSEDOWN:
msg = "nose DOWN"; msg = "nose DOWN";
break; break;
case 5: case ACCELCAL_VEHICLE_POS_NOSEUP:
msg = "nose UP"; msg = "nose UP";
break; break;
case 6: case ACCELCAL_VEHICLE_POS_BACK:
msg = "on its BACK"; msg = "on its BACK";
break; break;
default: default: