From 63e3bbde07257d68dca6731eec31a523237932dd Mon Sep 17 00:00:00 2001
From: David Sidrane <david_s5@nscdg.com>
Date: Tue, 24 Jan 2017 18:19:34 -1000
Subject: [PATCH] gyro_calibration is using board_get_uuid_raw32 instead of
 mcu_unique_id

---
 src/modules/commander/gyro_calibration.cpp | 6 +++---
 1 file changed, 3 insertions(+), 3 deletions(-)

diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
index 394a60be34..8c72384c26 100644
--- a/src/modules/commander/gyro_calibration.cpp
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -37,6 +37,7 @@
  * Gyroscope calibration routine
  */
 
+#include <px4_config.h>
 #include "gyro_calibration.h"
 #include "calibration_messages.h"
 #include "calibration_routines.h"
@@ -57,7 +58,6 @@
 #include <systemlib/mavlink_log.h>
 #include <systemlib/param/param.h>
 #include <systemlib/err.h>
-#include <systemlib/mcu_version.h>
 
 static const char *sensor_name = "gyro";
 
@@ -358,8 +358,8 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
 	}
 
 	/* store board ID */
-	uint32_t mcu_id[3];
-	mcu_unique_id(&mcu_id[0]);
+	raw_uuid_uint32_t mcu_id;
+	board_get_uuid_raw32(mcu_id, NULL);
 
 	/* store last 32bit number - not unique, but unique in a given set */
 	(void)param_set(param_find("CAL_BOARD_ID"), &mcu_id[2]);
-- 
GitLab