Skip to content

Commit d515a03

Browse files
committed
GCS_MAVLink: use new PREFLIGHT_CALIBRATION_* enum values
new enumeration values, fewer magic numbers
1 parent 2652409 commit d515a03

File tree

1 file changed

+5
-5
lines changed

1 file changed

+5
-5
lines changed

libraries/GCS_MAVLink/GCS_Common.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -4928,7 +4928,7 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_comm
49284928
#endif
49294929

49304930
#if HAL_INS_ACCELCAL_ENABLED
4931-
if (packet.x == 1) {
4931+
if (packet.x == PREFLIGHT_CALIBRATION_ACCELEROMETER_FULL) {
49324932
// start with gyro calibration
49334933
if (!AP::ins().calibrate_gyros()) {
49344934
return MAV_RESULT_FAILED;
@@ -4942,12 +4942,12 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_comm
49424942

49434943
#if AP_INERTIALSENSOR_ENABLED
49444944
#if AP_AHRS_ENABLED
4945-
if (packet.x == 2) {
4945+
if (packet.x == PREFLIGHT_CALIBRATION_ACCELEROMETER_TRIM) {
49464946
return AP::ins().calibrate_trim();
49474947
}
49484948
#endif
49494949

4950-
if (packet.x == 4) {
4950+
if (packet.x == PREFLIGHT_CALIBRATION_ACCELEROMETER_SIMPLE) {
49514951
// simple accel calibration
49524952
return AP::ins().simple_accel_cal();
49534953
}
@@ -4957,15 +4957,15 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_comm
49574957
compass to be written as valid. This is useful when reloading
49584958
parameters after a full parameter erase
49594959
*/
4960-
if (packet.x == 76) {
4960+
if (packet.x == PREFLIGHT_CALIBRATION_ACCELEROMETER_FORCE_SAVE) {
49614961
// force existing accel calibration to be accepted as valid
49624962
AP::ins().force_save_calibration();
49634963
ret = MAV_RESULT_ACCEPTED;
49644964
}
49654965
#endif // AP_INERTIALSENSOR_ENABLED
49664966

49674967
#if AP_COMPASS_ENABLED
4968-
if (is_equal(packet.param2,76.0f)) {
4968+
if (is_equal(packet.param2, static_cast<float>(PREFLIGHT_CALIBRATION_MAGNETOMETER_FORCE_SAVE))) {
49694969
// force existing compass calibration to be accepted as valid
49704970
AP::compass().force_save_calibration();
49714971
ret = MAV_RESULT_ACCEPTED;

0 commit comments

Comments
 (0)