Extract calibration management into SeeCalHelper

Move calibration-related code out of SeeHelper and into a new class
called SeeCalHelper, and allow multiple instances of SeeHelper to share
the same SeeCalHelper object. This allows us to handle calibration
updates within the micro-image instance of SeeHelper, and used the
cached data to apply calibration to raw samples received in both
instances, avoiding the need to transition to big image each time
calibration data is updated.

Bug: 79257265
Test: with additional logging enabled, confirm that we stay in
micro-image when calibration updates are generated for accel at 1 Hz,
and SensorWorld running in big image receives samples with the offsets
applied
Change-Id: I123175063eac7388834ceadc775df6cd84191083
diff --git a/platform/platform.mk b/platform/platform.mk
index 2fc11af..40227c0 100644
--- a/platform/platform.mk
+++ b/platform/platform.mk
@@ -131,6 +131,7 @@
 SLPI_SEE_SRCS += platform/slpi/see/island_vote_client.cc
 SLPI_SEE_SRCS += platform/slpi/see/platform_sensor.cc
 SLPI_SEE_SRCS += platform/slpi/see/power_control_manager.cc
+SLPI_SEE_SRCS += platform/slpi/see/see_cal_helper.cc
 SLPI_SEE_SRCS += platform/slpi/see/see_helper.cc
 
 SLPI_SEE_SRCS += $(SLPI_PREFIX)/ssc/framework/cm/pb/sns_client.pb.c
diff --git a/platform/slpi/include/chre/platform/slpi/see/see_cal_helper.h b/platform/slpi/include/chre/platform/slpi/see/see_cal_helper.h
new file mode 100644
index 0000000..9015649
--- /dev/null
+++ b/platform/slpi/include/chre/platform/slpi/see/see_cal_helper.h
@@ -0,0 +1,144 @@
+/*
+ * Copyright (C) 2018 The Android Open Source Project
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *      http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+
+#ifndef CHRE_PLATFORM_SLPI_SEE_SEE_CAL_HELPER_H_
+#define CHRE_PLATFORM_SLPI_SEE_SEE_CAL_HELPER_H_
+
+extern "C" {
+
+#include "sns_client.h"
+
+}  // extern "C"
+
+#include "sns_suid.pb.h"
+
+#include "chre/core/sensor_type.h"
+#include "chre/platform/mutex.h"
+#include "chre/util/non_copyable.h"
+#include "chre/util/optional.h"
+
+namespace chre {
+
+class SeeHelper;
+
+/**
+ * Helps manage and apply sensor calibration data provided through SEE.
+ */
+class SeeCalHelper : public NonCopyable {
+ public:
+  /**
+   * Applies cached calibration (if any) to raw 3-axis sensor readings.
+   * Thread-safe.
+   *
+   * @param sensorType Type of sensor that generated the sample
+   * @param input 3-axis raw sample {x,y,z}
+   * @param output Location to store sample with calibration applied (can be
+   *               same as input)
+   */
+  void applyCalibration(SensorType sensorType, const float input[3],
+                        float output[3]) const;
+
+  /**
+   * Get the cached SUID of a calibration sensor that corresponds to the
+   * specified sensorType.
+   *
+   * @param sensorType The sensor type of the calibration sensor.
+   *
+   * @return A constant reference to the calibration sensor's SUID if present.
+   *         Otherwise, a reference to sns_suid_sensor_init_zero is returned.
+   */
+  const sns_std_suid& getCalSuidFromSensorType(SensorType sensorType) const;
+
+  /**
+   * Uses the supplied SeeHelper instance to register for updates to all
+   * supported SEE calibration sensors. The SeeHelper instance should then pass
+   * decoded calibration data to updateCalibration() and use applyCalibration()
+   * as needed.
+   *
+   * @param seeHelper SeeHelper instance to use when looking up calibration
+   *                  sensor SUIDs and registering for their output
+   *
+   * @return true if all SEE calibration sensors were successfully registered
+   */
+  bool registerForCalibrationUpdates(SeeHelper& seeHelper);
+
+  /**
+   * Updates the cached calibration data used in subsequent calls to
+   * applyCalibration. Thread-safe.
+   *
+   * @param suid Sensor UID associated with the incoming calibration data
+   * @param hasBias true if bias was decoded from the proto
+   * @param bias 3-axis bias; only valid if hasBias is true
+   * @param hasScale true if scale was decoded from the proto
+   * @param scale 3-axis scale factor; only valid if hasScale is true
+   * @param hasMatrix true if matrix was decoded from the proto
+   * @param matrix 3x3 compensation matrix; only valid if hasMatrix is true
+   * @param accuracy Android accuracy rating of the calibration quality (see
+   *                 sns_std_sensor_sample_status)
+   */
+  void updateCalibration(const sns_std_suid& suid, bool hasBias, float bias[3],
+                         bool hasScale, float scale[3], bool hasMatrix,
+                         float matrix[9], uint8_t accuracy);
+
+ private:
+  //! A struct to store a sensor's calibration data
+  struct SeeCalData {
+    float bias[3];
+    float scale[3];
+    float matrix[9];
+    bool hasBias;
+    bool hasScale;
+    bool hasMatrix;
+    uint8_t accuracy;
+  };
+
+  //! A struct to store a cal sensor's UID and its cal data.
+  struct SeeCalInfo {
+    Optional<sns_std_suid> suid;
+    SeeCalData cal;
+  };
+
+  //! The list of SEE cal sensors supported.
+  enum class SeeCalSensor : size_t {
+    AccelCal,
+    GyroCal,
+    MagCal,
+    NumCalSensors,
+  };
+
+  //! A convenience constant.
+  static constexpr size_t kNumSeeCalSensors = static_cast<size_t>(
+      SeeCalSensor::NumCalSensors);
+
+  //! Protects access to calibration data, which may be used in multiple threads
+  mutable Mutex mMutex;
+
+  //! Cal info of all the cal sensors.
+  SeeCalInfo mCalInfo[kNumSeeCalSensors] = {};
+
+  //! Map SensorType to associated index in mCalInfo
+  static size_t getCalIndexFromSensorType(SensorType sensorType);
+
+  //! Map index in mCalInfo to SEE sensor data type string
+  static const char *getDataTypeForCalSensorIndex(size_t calSensorIndex);
+
+  //! Map SUID to associated index in mCalInfo
+  size_t getCalIndexFromSuid(const sns_std_suid& suid) const;
+};
+
+}  // namespace chre
+
+#endif  // CHRE_PLATFORM_SLPI_SEE_SEE_CAL_HELPER_H_
diff --git a/platform/slpi/include/chre/platform/slpi/see/see_helper.h b/platform/slpi/include/chre/platform/slpi/see/see_helper.h
index 072984f..0c5ab47 100644
--- a/platform/slpi/include/chre/platform/slpi/see/see_helper.h
+++ b/platform/slpi/include/chre/platform/slpi/see/see_helper.h
@@ -23,12 +23,15 @@
 
 }  // extern "C"
 
+#include "sns_suid.pb.h"
+
 #include "chre/core/sensor_type.h"
 #include "chre/platform/condition_variable.h"
 #include "chre/platform/mutex.h"
-#include "chre/platform/slpi/see/see_helper_internal.h"
+#include "chre/platform/slpi/see/see_cal_helper.h"
 #include "chre/util/dynamic_vector.h"
 #include "chre/util/non_copyable.h"
+#include "chre/util/optional.h"
 #include "chre/util/time.h"
 #include "chre/util/unique_ptr.h"
 
@@ -117,11 +120,37 @@
   };
 
   /**
+   * Constructor for a SeeHelper that manages its own SeeCalHelper
+   */
+  SeeHelper();
+
+  /**
+   * Constructor for a SeeHelper that uses the supplied SeeCalHelper object
+   * rather than creating its own. Caller must ensure that the lifetime of the
+   * SeeCalHelper object exceeds the lifetime of this SeeHelper instance.
+   *
+   * TODO: this would be a good case for a shared ptr implementation
+   *
+   * @param calHelper Non-null pointer to a calibration helper object to use
+   */
+  SeeHelper(SeeCalHelper *calHelper);
+
+  /**
    * Deinits clients before destructing this object.
    */
   ~SeeHelper();
 
   /**
+   * Makes a request to SEE to enable an on-change sensor, with no additional
+   * payload. Can be used for registering a calibration sensor, for example.
+   *
+   * @param suid Sensor UID, usually determined via findSuidSync()
+   *
+   * @return true on success
+   */
+  bool configureOnChangeSensor(const sns_std_suid& suid, bool enable);
+
+  /**
    * A synchronous call to discover SUID(s) that supports the specified data
    * type. This API will clear the provided dynamic vector before populating it.
    *
@@ -165,6 +194,13 @@
   bool getAttributesSync(const sns_std_suid& suid, SeeAttributes *attr);
 
   /**
+   * @return the SeeCalHelper instance used by this SeeHelper
+   */
+  SeeCalHelper *getCalHelper() {
+    return mCalHelper;
+  }
+
+  /**
    * Initializes and waits for the sensor client service to become available,
    * and obtains remote_proc and cal sensors' info for future operations. This
    * function must be called first to initialize the object and be called only
@@ -174,11 +210,15 @@
    *             handle all async requests with callback data type defined in
    *             the interface.
    * @param timeout The wait timeout in microseconds.
+   * @param skipDefaultSensorInit If true, don't register remote proc status and
+   *                              calibration sensors (e.g. if another SeeHelper
+   *                              instance will manage these)
    *
    * @return true if all initialization steps succeeded.
    */
   bool init(SeeHelperCallbackInterface *cbIf,
-            Microseconds timeout = kDefaultSeeWaitTimeout);
+            Microseconds timeout = kDefaultSeeWaitTimeout,
+            bool skipDefaultSensorInit = false);
 
   /**
    * Makes a sensor request to SEE.
@@ -238,7 +278,9 @@
    * @return A constant reference to the calibration sensor's SUID if present.
    *         Otherwise, a reference to sns_suid_sensor_init_zero is returned.
    */
-  const sns_std_suid& getCalSuidFromSensorType(SensorType sensorType) const;
+  const sns_std_suid& getCalSuidFromSensorType(SensorType sensorType) const {
+    return mCalHelper->getCalSuidFromSensorType(sensorType);
+  }
 
   /**
    * A convenience method to send a request and wait for the indication if it's
@@ -310,15 +352,11 @@
   //! The SUID for the remote_proc sensor.
   Optional<sns_std_suid> mRemoteProcSuid;
 
-  //! Cal info of all the cal sensors.
-  SeeCalInfo mCalInfo[kNumSeeCalSensors];
+  //! Handles sensor calibration data
+  SeeCalHelper *mCalHelper;
 
-  /**
-   * Initializes SEE calibration sensors and makes data request.
-   *
-   * @return true if cal sensor have been succcessfully initialized.
-   */
-  bool initCalSensors();
+  //! true if we own the memory to mCalHelper and should free it when done
+  bool mOwnsCalHelper;
 
   /**
    * Initializes the SEE remote processor sensor and makes a data request.
@@ -427,11 +465,6 @@
                       Microseconds timeout = kDefaultSeeWaitTimeout);
 
   /**
-   * Obtains the pointer to cal data by SensorType
-   */
-  SeeCalData *getCalDataFromSensorType(SensorType sensorType);
-
-  /**
    * @return SensorInfo instance found in mSensorInfos with the given
    *         SensorType, or nullptr if not found
    */
@@ -448,7 +481,7 @@
  */
 class BigImageSeeHelper : public SeeHelper {
  public:
-  BigImageSeeHelper() {
+  BigImageSeeHelper(SeeCalHelper *calHelper) : SeeHelper(calHelper) {
     mSnsClientApi = &kQmiApi;
   }
 
diff --git a/platform/slpi/include/chre/platform/slpi/see/see_helper_internal.h b/platform/slpi/include/chre/platform/slpi/see/see_helper_internal.h
deleted file mode 100644
index c1537e8..0000000
--- a/platform/slpi/include/chre/platform/slpi/see/see_helper_internal.h
+++ /dev/null
@@ -1,60 +0,0 @@
-/*
- * Copyright (C) 2018 The Android Open Source Project
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- *      http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-
-#ifndef CHRE_PLATFORM_SLPI_SEE_SEE_HELPER_INTERNAL_H_
-#define CHRE_PLATFORM_SLPI_SEE_SEE_HELPER_INTERNAL_H_
-
-#include <stddef.h>
-#include <stdint.h>
-
-#include "sns_suid.pb.h"
-
-#include "chre/util/optional.h"
-
-namespace chre {
-
-//! A struct to store a sensor's calibration data
-struct SeeCalData {
-  float bias[3];
-  float scale[3];
-  float matrix[9];
-  bool hasBias;
-  bool hasScale;
-  bool hasMatrix;
-  uint8_t accuracy;
-};
-
-//! A struct to store a cal sensor's UID and its cal data.
-struct SeeCalInfo {
-  Optional<sns_std_suid> suid;
-  SeeCalData cal;
-};
-
-//! The list of SEE cal sensors supported.
-enum class SeeCalSensor {
-  AccelCal,
-  GyroCal,
-  MagCal,
-  NumCalSensors,
-};
-
-//! A convenience constant.
-constexpr size_t kNumSeeCalSensors = static_cast<size_t>(
-    SeeCalSensor::NumCalSensors);
-
-}  // namespace chre
-
-#endif  // CHRE_PLATFORM_SLPI_SEE_SEE_HELPER_INTERNAL_H_
diff --git a/platform/slpi/see/platform_sensor.cc b/platform/slpi/see/platform_sensor.cc
index 0149f5b..b9b62fc 100644
--- a/platform/slpi/see/platform_sensor.cc
+++ b/platform/slpi/see/platform_sensor.cc
@@ -506,8 +506,9 @@
   }
 
 #ifdef CHRE_SLPI_UIMG_ENABLED
-  BigImageSeeHelperSingleton::init();
-  if (!getBigImageSeeHelper()->init(&seeHelperCallback)) {
+  BigImageSeeHelperSingleton::init(getSeeHelper()->getCalHelper());
+  if (!getBigImageSeeHelper()->init(&seeHelperCallback, kDefaultSeeWaitTimeout,
+                                    true /* skipDefaultSensorInit */)) {
     FATAL_ERROR("Failed to init bimg SEE helper");
   }
 #endif  // CHRE_SLPI_UIMG_ENABLED
diff --git a/platform/slpi/see/see_cal_helper.cc b/platform/slpi/see/see_cal_helper.cc
new file mode 100644
index 0000000..4a234aa
--- /dev/null
+++ b/platform/slpi/see/see_cal_helper.cc
@@ -0,0 +1,146 @@
+/*
+ * Copyright (C) 2018 The Android Open Source Project
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *      http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+
+#include "chre/platform/slpi/see/see_cal_helper.h"
+
+#include "chre/platform/assert.h"
+#include "chre/platform/log.h"
+#include "chre/platform/slpi/see/see_helper.h"
+#include "chre/util/lock_guard.h"
+
+namespace chre {
+
+void SeeCalHelper::applyCalibration(SensorType sensorType, const float input[3],
+                                    float output[3]) const {
+  size_t index = getCalIndexFromSensorType(sensorType);
+  if (index < ARRAY_SIZE(mCalInfo)) {
+    LockGuard<Mutex> lock(mMutex);
+
+    // TODO: Support compensation matrix and scaling factor calibration
+    if (mCalInfo[index].cal.hasBias) {
+      for (size_t i = 0; i < 3; i++) {
+        output[i] = input[i] - mCalInfo[index].cal.bias[i];
+      }
+    }
+  }
+}
+
+const sns_std_suid& SeeCalHelper::getCalSuidFromSensorType(
+    SensorType sensorType) const {
+  static sns_std_suid suid = sns_suid_sensor_init_zero;
+
+  // Mutex not needed, SUID is not modified after init
+  size_t calIndex = getCalIndexFromSensorType(sensorType);
+  if (calIndex < ARRAY_SIZE(mCalInfo) && mCalInfo[calIndex].suid.has_value()) {
+    suid = mCalInfo[calIndex].suid.value();
+  }
+  return suid;
+}
+
+bool SeeCalHelper::registerForCalibrationUpdates(SeeHelper& seeHelper) {
+  bool success = true;
+
+  // Find the cal sensor's SUID, assign it to mCalInfo, and make cal sensor data
+  // request.
+  DynamicVector<sns_std_suid> suids;
+  for (size_t i = 0; i < ARRAY_SIZE(mCalInfo); i++) {
+    const char *calType = getDataTypeForCalSensorIndex(i);
+    if (!seeHelper.findSuidSync(calType, &suids)) {
+      success = false;
+      LOGE("Failed to find sensor '%s'", calType);
+    } else {
+      mCalInfo[i].suid = suids[0];
+      if (!seeHelper.configureOnChangeSensor(suids[0], true /* enable */)) {
+        success = false;
+        LOGE("Failed to request '%s' data", calType);
+      }
+    }
+  }
+
+  return success;
+}
+
+void SeeCalHelper::updateCalibration(
+    const sns_std_suid& suid, bool hasBias, float bias[3], bool hasScale,
+    float scale[3], bool hasMatrix, float matrix[9], uint8_t accuracy) {
+  size_t index = getCalIndexFromSuid(suid);
+  if (index < ARRAY_SIZE(mCalInfo)) {
+    LockGuard<Mutex> lock(mMutex);
+    SeeCalData& calData = mCalInfo[index].cal;
+
+    calData.hasBias = hasBias;
+    if (hasBias) {
+      memcpy(calData.bias, bias, sizeof(calData.bias));
+    }
+
+    calData.hasScale = hasScale;
+    if (hasScale) {
+      memcpy(calData.scale, scale, sizeof(calData.scale));
+    }
+
+    calData.hasMatrix = hasMatrix;
+    if (hasMatrix) {
+      memcpy(calData.matrix, matrix, sizeof(calData.matrix));
+    }
+
+    calData.accuracy = accuracy;
+  }
+}
+
+size_t SeeCalHelper::getCalIndexFromSensorType(SensorType sensorType) {
+  SeeCalSensor index;
+  switch (sensorType) {
+    case SensorType::Accelerometer:
+      index = SeeCalSensor::AccelCal;
+      break;
+    case SensorType::Gyroscope:
+      index = SeeCalSensor::GyroCal;
+      break;
+    case SensorType::GeomagneticField:
+      index = SeeCalSensor::MagCal;
+      break;
+    default:
+      index = SeeCalSensor::NumCalSensors;
+  }
+  return static_cast<size_t>(index);
+}
+
+const char *SeeCalHelper::getDataTypeForCalSensorIndex(size_t calSensorIndex) {
+  switch (static_cast<SeeCalSensor>(calSensorIndex)) {
+    case SeeCalSensor::AccelCal:
+      return "accel_cal";
+    case SeeCalSensor::GyroCal:
+      return "gyro_cal";
+    case SeeCalSensor::MagCal:
+      return "mag_cal";
+    default:
+      CHRE_ASSERT(false);
+  }
+  return nullptr;
+}
+
+size_t SeeCalHelper::getCalIndexFromSuid(const sns_std_suid& suid) const {
+  size_t i = 0;
+  for (; i < ARRAY_SIZE(mCalInfo); i++) {
+    if (mCalInfo[i].suid.has_value()
+        && suidsMatch(suid, mCalInfo[i].suid.value())) {
+      break;
+    }
+  }
+  return i;
+}
+
+}  // namespace chre
diff --git a/platform/slpi/see/see_helper.cc b/platform/slpi/see/see_helper.cc
index c6200ac..6b8e881 100644
--- a/platform/slpi/see/see_helper.cc
+++ b/platform/slpi/see/see_helper.cc
@@ -97,7 +97,6 @@
   size_t totalSamples;
   UniquePtr<uint8_t> event;
   UniquePtr<SeeHelperCallbackInterface::SamplingStatusData> status;
-  SeeCalData *cal;
   SensorType sensorType;
   bool isHostWakeSuspendEvent;
   bool isHostAwake;
@@ -112,7 +111,7 @@
   SeeDataArg *data;
   bool decodeMsgIdOnly;
   Optional<sns_std_suid> *remoteProcSuid;
-  SeeCalInfo *calInfo;
+  SeeCalHelper *calHelper;
 };
 
 //! A struct to facilitate decoding sensor attributes.
@@ -129,49 +128,6 @@
   bool initialized;
 };
 
-size_t getCalIndexFromSensorType(SensorType sensorType) {
-  SeeCalSensor index;
-  switch (sensorType) {
-    case SensorType::VendorType3:
-    case SensorType::Accelerometer:
-      index = SeeCalSensor::AccelCal;
-      break;
-    case SensorType::Gyroscope:
-      index = SeeCalSensor::GyroCal;
-      break;
-    case SensorType::GeomagneticField:
-      index = SeeCalSensor::MagCal;
-      break;
-    default:
-      index = SeeCalSensor::NumCalSensors;
-  }
-  return static_cast<size_t>(index);
-}
-
-size_t getCalIndexFromDataType(const char *dataType) {
-  SensorType sensorType = SensorType::Unknown;
-  if (strcmp(dataType, "accel_cal") == 0) {
-    sensorType = SensorType::Accelerometer;
-  } else if (strcmp(dataType, "gyro_cal") == 0) {
-    sensorType = SensorType::Gyroscope;
-  } else if (strcmp(dataType, "mag_cal") == 0) {
-    sensorType = SensorType::GeomagneticField;
-  }
-  return getCalIndexFromSensorType(sensorType);
-}
-
-size_t getCalIndexFromSuid(const sns_std_suid& suid,
-                           const SeeCalInfo *calInfo) {
-  size_t i = 0;
-  for (; i < kNumSeeCalSensors; i++) {
-    if (calInfo[i].suid.has_value()
-        && suidsMatch(suid, calInfo[i].suid.value())) {
-      break;
-    }
-  }
-  return i;
-}
-
 /**
  * Copy an encoded pb message to a wrapper proto's field.
  */
@@ -732,20 +688,8 @@
   return success;
 }
 
-// TODO: Support compensation matrix and scaling factor calibration
-void applyThreeAxisCalibration(
-    chreSensorThreeAxisData::chreSensorThreeAxisSampleData *sample,
-    const float *val, const SeeCalData *cal) {
-  float bias[3] = {};
-  if (cal != nullptr && cal->hasBias) {
-    memcpy(bias, cal->bias, sizeof(bias));
-  }
-  sample->x = val[0] - bias[0];
-  sample->y = val[1] - bias[1];
-  sample->z = val[2] - bias[2];
-}
-
-void populateEventSample(SeeDataArg *data, const float *val) {
+void populateEventSample(SeeInfoArg *info, const float *val) {
+  SeeDataArg *data = info->data;
   size_t index = data->sampleIndex;
   if (!data->event.isNull() && index < data->totalSamples) {
     SensorSampleType sampleType = getSensorSampleTypeFromSensorType(
@@ -756,7 +700,8 @@
       case SensorSampleType::ThreeAxis: {
         auto *event = reinterpret_cast<chreSensorThreeAxisData *>(
             data->event.get());
-        applyThreeAxisCalibration(&event->readings[index], val, data->cal);
+        info->calHelper->applyCalibration(
+            data->sensorType, val, event->readings[index].values);
         timestampDelta = &event->readings[index].timestampDelta;
         break;
       }
@@ -926,7 +871,7 @@
     LOG_NANOPB_ERROR(stream);
   } else {
     auto *info = static_cast<SeeInfoArg *>(*arg);
-    populateEventSample(info->data, sample.val);
+    populateEventSample(info, sample.val);
   }
   return success;
 }
@@ -973,31 +918,16 @@
     LOG_NANOPB_ERROR(stream);
   } else {
     auto *info = static_cast<SeeInfoArg *>(*arg);
-    SeeCalInfo *calInfo = info->calInfo;
-    size_t calIndex = getCalIndexFromSuid(info->suid, calInfo);
-    if (calIndex >= kNumSeeCalSensors) {
-      LOGW("Cal sensor index out of bounds 0x%" PRIx64 " %" PRIx64,
-           info->suid.suid_high, info->suid.suid_low);
-    } else {
-      SeeCalData *cal = &calInfo[calIndex].cal;
+    SeeCalHelper *calHelper = info->calHelper;
 
-      cal->hasBias = (offset.index == 3);
-      if (cal->hasBias) {
-        memcpy(cal->bias, offset.val, sizeof(cal->bias));
-      }
+    bool hasBias = (offset.index == 3);
+    bool hasScale = (scale.index == 3);
+    bool hasMatrix = (matrix.index == 9);
+    uint8_t accuracy = static_cast<uint8_t>(event.status);
 
-      cal->hasScale = (scale.index == 3);
-      if (cal->hasScale) {
-        memcpy(cal->scale, scale.val, sizeof(cal->scale));
-      }
-
-      cal->hasMatrix = (matrix.index == 9);
-      if (cal->hasScale) {
-        memcpy(cal->matrix, matrix.val, sizeof(cal->matrix));
-      }
-
-      cal->accuracy = static_cast<uint8_t>(event.status);
-    }
+    calHelper->updateCalibration(
+        info->suid, hasBias, offset.val, hasScale, scale.val,
+        hasMatrix, matrix.val, accuracy);
   }
   return success;
 }
@@ -1031,7 +961,7 @@
   } else {
     float value = static_cast<float>(event.proximity_event_type);
     auto *info = static_cast<SeeInfoArg *>(*arg);
-    populateEventSample(info->data, &value);
+    populateEventSample(info, &value);
   }
   return success;
 }
@@ -1326,6 +1256,17 @@
 };
 #endif  // CHRE_SLPI_UIMG_ENABLED
 
+SeeHelper::SeeHelper() {
+  mCalHelper = memoryAlloc<SeeCalHelper>();
+  if (mCalHelper == nullptr) {
+    FATAL_ERROR("Failed to allocate SeeCalHelper");
+  }
+  mOwnsCalHelper = true;
+}
+
+SeeHelper::SeeHelper(SeeCalHelper *calHelper)
+    : mCalHelper(calHelper), mOwnsCalHelper(false) {}
+
 SeeHelper::~SeeHelper() {
   for (auto *client : mSeeClients) {
     int status = mSnsClientApi->sns_client_deinit(client);
@@ -1333,6 +1274,11 @@
       LOGE("Failed to release sensor client: %d", status);
     }
   }
+
+  if (mOwnsCalHelper) {
+    mCalHelper->~SeeCalHelper();
+    memoryFree(mCalHelper);
+  }
 }
 
 void SeeHelper::handleSnsClientEventMsg(
@@ -1362,7 +1308,7 @@
     data->info.data = &data->dataArg;
     data->info.decodeMsgIdOnly = true;
     data->info.remoteProcSuid = &mRemoteProcSuid;
-    data->info.calInfo = &mCalInfo[0];
+    data->info.calHelper = mCalHelper;
     data->event.events.funcs.decode = decodeSnsClientEventMsg;
     data->event.events.arg = &data->info;
 
@@ -1374,8 +1320,6 @@
       data->info.decodeMsgIdOnly = false;
       data->info.data->sensorType = getSensorTypeFromSensorInfo(
           data->info.client, data->info.suid, mSensorInfos);
-      data->info.data->cal = getCalDataFromSensorType(
-          data->info.data->sensorType);
 
       mMutex.lock();
       bool synchronizedDecode = mWaitingOnInd;
@@ -1507,7 +1451,8 @@
   return success;
 }
 
-bool SeeHelper::init(SeeHelperCallbackInterface *cbIf, Microseconds timeout) {
+bool SeeHelper::init(SeeHelperCallbackInterface *cbIf, Microseconds timeout,
+                     bool skipDefaultSensorInit) {
   CHRE_ASSERT(cbIf);
 
   mCbIf = cbIf;
@@ -1516,8 +1461,9 @@
   // Initialize cal/remote_proc_state sensors before making sensor data request.
   return (waitForService(&client, timeout)
           && mSeeClients.push_back(client)
-          && initCalSensors()
-          && initRemoteProcSensor());
+          && (skipDefaultSensorInit
+              || (mCalHelper->registerForCalibrationUpdates(*this)
+                  && initRemoteProcSensor())));
 }
 
 bool SeeHelper::makeRequest(const SeeSensorRequest& request) {
@@ -1556,15 +1502,15 @@
   return success;
 }
 
-const sns_std_suid& SeeHelper::getCalSuidFromSensorType(
-    SensorType sensorType) const {
-  static sns_std_suid suid = sns_suid_sensor_init_zero;
-
-  size_t calIndex = getCalIndexFromSensorType(sensorType);
-  if (calIndex < kNumSeeCalSensors && mCalInfo[calIndex].suid.has_value()) {
-    suid = mCalInfo[calIndex].suid.value();
-  }
-  return suid;
+bool SeeHelper::configureOnChangeSensor(const sns_std_suid& suid, bool enable) {
+  uint32_t msgId = (enable)
+      ? SNS_STD_SENSOR_MSGID_SNS_STD_ON_CHANGE_CONFIG
+      : SNS_CLIENT_MSGID_SNS_CLIENT_DISABLE_REQ;
+  return sendReq(
+      suid, nullptr /* syncData */, nullptr /* syncDataType */,
+      msgId, nullptr /* msg */, 0 /* msgLen */,
+      false /* batchValid */, 0 /* batchPeriodUs */,
+      false /* passive */, false /* waitForIndication */);
 }
 
 /**
@@ -1764,50 +1710,6 @@
   return success;
 }
 
-bool SeeHelper::initCalSensors() {
-  bool success = true;
-
-  // Zero out mCalInfo to avoid accidental suid and data match.
-  memset(mCalInfo, 0, sizeof(mCalInfo));
-
-  const char *kCalTypes[] = {
-    "accel_cal",
-    "gyro_cal",
-    "mag_cal",
-  };
-
-  // Find the cal sensor's SUID, assign it to mCalInfo, and make cal sensor data
-  // request.
-  DynamicVector<sns_std_suid> suids;
-  for (size_t i = 0; i < ARRAY_SIZE(kCalTypes); i++) {
-    const char *calType = kCalTypes[i];
-    if (!findSuidSync(calType, &suids)) {
-      success = false;
-      LOGE("Failed to find sensor '%s'", calType);
-    } else {
-      size_t index = getCalIndexFromDataType(calType);
-      if (index >= kNumSeeCalSensors) {
-        success = false;
-        LOGE("Cal sensor '%s' index out of bounds", calType);
-      } else {
-        mCalInfo[index].suid = suids[0];
-
-        if (!sendReq(suids[0], nullptr /* syncData */,
-                     nullptr /* syncDataType */,
-                     SNS_STD_SENSOR_MSGID_SNS_STD_ON_CHANGE_CONFIG,
-                     nullptr /* msg */, 0 /* msgLen */,
-                     false /* batchValid */, 0 /* batchPeriodUs */,
-                     false /* passive */, false /* waitForIndication */)) {
-          success = false;
-          LOGE("Failed to request '%s' data", calType);
-        }
-      }
-    }
-  }
-
-  return success;
-}
-
 bool SeeHelper::initRemoteProcSensor() {
   bool success = false;
 
@@ -1838,11 +1740,6 @@
   return success;
 }
 
-SeeCalData *SeeHelper::getCalDataFromSensorType(SensorType sensorType) {
-  size_t calIndex = getCalIndexFromSensorType(sensorType);
-  return (calIndex < kNumSeeCalSensors) ? &mCalInfo[calIndex].cal : nullptr;
-}
-
 const SeeHelper::SensorInfo *SeeHelper::getSensorInfo(
     SensorType sensorType) const {
   for (const auto& sensorInfo : mSensorInfos) {