Move all floats to doubles

The code was developed initially around a pid loop implemented using
floats.  Therefore, the code was converting back and forth between
double for sensor values as inputs and outputs from this PID loop.

Change-Id: I2d2919e1165103040729c9f16bb84fde3dd6b81b
Signed-off-by: Patrick Venture <venture@google.com>
diff --git a/conf.hpp b/conf.hpp
index 6e2dc32..c251efc 100644
--- a/conf.hpp
+++ b/conf.hpp
@@ -30,7 +30,7 @@
 {
     std::string type;                // fan or margin or temp?
     std::vector<std::string> inputs; // one or more sensors.
-    float setpoint;                  // initial setpoint for thermal.
+    double setpoint;                 // initial setpoint for thermal.
     union
     {
         ec::pidinfo pidInfo; // pid details
@@ -46,10 +46,10 @@
 struct ZoneConfig
 {
     /* The minimum RPM value we would ever want. */
-    float minthermalrpm;
+    double minthermalrpm;
 
     /* If the sensors are in fail-safe mode, this is the percentage to use. */
-    float failsafepercent;
+    double failsafepercent;
 };
 
 using PIDConf = std::map<std::string, struct ControllerInfo>;
diff --git a/dbus/dbusconfiguration.cpp b/dbus/dbusconfiguration.cpp
index 9d62643..78cc4e4 100644
--- a/dbus/dbusconfiguration.cpp
+++ b/dbus/dbusconfiguration.cpp
@@ -294,9 +294,9 @@
 
             auto& details = zoneDetailsConfig[index];
             details.minthermalrpm = variant_ns::apply_visitor(
-                VariantToFloatVisitor(), zone.at("MinThermalRpm"));
+                VariantToDoubleVisitor(), zone.at("MinThermalRpm"));
             details.failsafepercent = variant_ns::apply_visitor(
-                VariantToFloatVisitor(), zone.at("FailSafePercent"));
+                VariantToDoubleVisitor(), zone.at("FailSafePercent"));
         }
         auto findBase = configuration.second.find(pidConfigurationInterface);
         if (findBase != configuration.second.end())
@@ -402,29 +402,29 @@
                 else
                 {
                     info.setpoint = variant_ns::apply_visitor(
-                        VariantToFloatVisitor(), base.at("SetPoint"));
+                        VariantToDoubleVisitor(), base.at("SetPoint"));
                 }
                 info.pidInfo.ts = 1.0; // currently unused
                 info.pidInfo.p_c = variant_ns::apply_visitor(
-                    VariantToFloatVisitor(), base.at("PCoefficient"));
+                    VariantToDoubleVisitor(), base.at("PCoefficient"));
                 info.pidInfo.i_c = variant_ns::apply_visitor(
-                    VariantToFloatVisitor(), base.at("ICoefficient"));
+                    VariantToDoubleVisitor(), base.at("ICoefficient"));
                 info.pidInfo.ff_off = variant_ns::apply_visitor(
-                    VariantToFloatVisitor(), base.at("FFOffCoefficient"));
+                    VariantToDoubleVisitor(), base.at("FFOffCoefficient"));
                 info.pidInfo.ff_gain = variant_ns::apply_visitor(
-                    VariantToFloatVisitor(), base.at("FFGainCoefficient"));
+                    VariantToDoubleVisitor(), base.at("FFGainCoefficient"));
                 info.pidInfo.i_lim.max = variant_ns::apply_visitor(
-                    VariantToFloatVisitor(), base.at("ILimitMax"));
+                    VariantToDoubleVisitor(), base.at("ILimitMax"));
                 info.pidInfo.i_lim.min = variant_ns::apply_visitor(
-                    VariantToFloatVisitor(), base.at("ILimitMin"));
+                    VariantToDoubleVisitor(), base.at("ILimitMin"));
                 info.pidInfo.out_lim.max = variant_ns::apply_visitor(
-                    VariantToFloatVisitor(), base.at("OutLimitMax"));
+                    VariantToDoubleVisitor(), base.at("OutLimitMax"));
                 info.pidInfo.out_lim.min = variant_ns::apply_visitor(
-                    VariantToFloatVisitor(), base.at("OutLimitMin"));
+                    VariantToDoubleVisitor(), base.at("OutLimitMin"));
                 info.pidInfo.slew_neg = variant_ns::apply_visitor(
-                    VariantToFloatVisitor(), base.at("SlewNeg"));
+                    VariantToDoubleVisitor(), base.at("SlewNeg"));
                 info.pidInfo.slew_pos = variant_ns::apply_visitor(
-                    VariantToFloatVisitor(), base.at("SlewPos"));
+                    VariantToDoubleVisitor(), base.at("SlewPos"));
             }
         }
         auto findStepwise =
@@ -494,13 +494,13 @@
                 if (findPosHyst != base.end())
                 {
                     info.stepwiseInfo.positiveHysteresis =
-                        variant_ns::apply_visitor(VariantToFloatVisitor(),
+                        variant_ns::apply_visitor(VariantToDoubleVisitor(),
                                                   findPosHyst->second);
                 }
                 if (findNegHyst != base.end())
                 {
                     info.stepwiseInfo.positiveHysteresis =
-                        variant_ns::apply_visitor(VariantToFloatVisitor(),
+                        variant_ns::apply_visitor(VariantToDoubleVisitor(),
                                                   findNegHyst->second);
                 }
                 std::vector<double> readings =
@@ -519,7 +519,7 @@
                 if (readings.size() < ec::maxStepwisePoints)
                 {
                     info.stepwiseInfo.reading[readings.size()] =
-                        std::numeric_limits<float>::quiet_NaN();
+                        std::numeric_limits<double>::quiet_NaN();
                 }
                 std::vector<double> outputs =
                     variant_ns::get<std::vector<double>>(base.at("Output"));
@@ -533,7 +533,7 @@
                 if (outputs.size() < ec::maxStepwisePoints)
                 {
                     info.stepwiseInfo.output[outputs.size()] =
-                        std::numeric_limits<float>::quiet_NaN();
+                        std::numeric_limits<double>::quiet_NaN();
                 }
             }
         }
diff --git a/dbus/dbuswrite.cpp b/dbus/dbuswrite.cpp
index fab9b4a..dff11d6 100644
--- a/dbus/dbuswrite.cpp
+++ b/dbus/dbuswrite.cpp
@@ -61,12 +61,12 @@
 
 void DbusWritePercent::write(double value)
 {
-    float minimum = getMin();
-    float maximum = getMax();
+    double minimum = getMin();
+    double maximum = getMax();
 
-    float range = maximum - minimum;
-    float offset = range * value;
-    float ovalue = offset + minimum;
+    double range = maximum - minimum;
+    double offset = range * value;
+    double ovalue = offset + minimum;
 
     if (oldValue == static_cast<int64_t>(ovalue))
     {
diff --git a/dbus/util.hpp b/dbus/util.hpp
index 1b3a95b..719bb1d 100644
--- a/dbus/util.hpp
+++ b/dbus/util.hpp
@@ -85,23 +85,6 @@
 std::string getMatch(const std::string& type, const std::string& id);
 bool validType(const std::string& type);
 
-struct VariantToFloatVisitor
-{
-    template <typename T>
-    std::enable_if_t<std::is_arithmetic<T>::value, float>
-        operator()(const T& t) const
-    {
-        return static_cast<float>(t);
-    }
-
-    template <typename T>
-    std::enable_if_t<!std::is_arithmetic<T>::value, float>
-        operator()(const T& t) const
-    {
-        throw std::invalid_argument("Cannot translate type to float");
-    }
-};
-
 struct VariantToDoubleVisitor
 {
     template <typename T>
diff --git a/pid/builderconfig.cpp b/pid/builderconfig.cpp
index 665e2dd..f85e1c1 100644
--- a/pid/builderconfig.cpp
+++ b/pid/builderconfig.cpp
@@ -92,10 +92,10 @@
 
                 /*
                  * Mysteriously if you use lookupValue on these, and the type
-                 * is float.  It won't work right.
+                 * is double.  It won't work right.
                  *
                  * If the configuration file value doesn't look explicitly like
-                 * a float it won't let you assign it to one.
+                 * a double it won't let you assign it to one.
                  */
                 name = pid.lookup("name").c_str();
                 info.type = pid.lookup("type").c_str();
diff --git a/pid/controller.hpp b/pid/controller.hpp
index bf79937..5530843 100644
--- a/pid/controller.hpp
+++ b/pid/controller.hpp
@@ -15,9 +15,9 @@
 {
     virtual ~Controller() = default;
 
-    virtual float inputProc(void) = 0;
+    virtual double inputProc(void) = 0;
 
-    virtual void outputProc(float value) = 0;
+    virtual void outputProc(double value) = 0;
 
     virtual void process(void) = 0;
 
diff --git a/pid/ec/pid.cpp b/pid/ec/pid.cpp
index c2236c2..1ded7ac 100644
--- a/pid/ec/pid.cpp
+++ b/pid/ec/pid.cpp
@@ -23,7 +23,7 @@
  *  clamp
  *
  */
-static float clamp(float x, float min, float max)
+static double clamp(double x, double min, double max)
 {
     if (x < min)
     {
@@ -40,15 +40,15 @@
  *  pid code
  *  Note: Codes assumes the ts field is non-zero
  */
-float pid(pid_info_t* pidinfoptr, float input, float setpoint)
+double pid(pid_info_t* pidinfoptr, double input, double setpoint)
 {
-    float error;
+    double error;
 
-    float p_term;
-    float i_term = 0.0f;
-    float ff_term = 0.0f;
+    double p_term;
+    double i_term = 0.0f;
+    double ff_term = 0.0f;
 
-    float output;
+    double output;
 
     // calculate P, I, D, FF
 
@@ -79,7 +79,7 @@
         if (pidinfoptr->slew_neg != 0.0f)
         {
             // Don't decrease too fast
-            float min_out =
+            double min_out =
                 pidinfoptr->last_output + pidinfoptr->slew_neg * pidinfoptr->ts;
             if (output < min_out)
             {
@@ -89,7 +89,7 @@
         if (pidinfoptr->slew_pos != 0.0f)
         {
             // Don't increase too fast
-            float max_out =
+            double max_out =
                 pidinfoptr->last_output + pidinfoptr->slew_pos * pidinfoptr->ts;
             if (output > max_out)
             {
diff --git a/pid/ec/pid.hpp b/pid/ec/pid.hpp
index 6b1030a..779ced5 100644
--- a/pid/ec/pid.hpp
+++ b/pid/ec/pid.hpp
@@ -7,8 +7,8 @@
 
 typedef struct
 {
-    float min;
-    float max;
+    double min;
+    double max;
 } limits_t;
 
 /* Note: If you update these structs you need to update the copy code in
@@ -18,35 +18,35 @@
 {
     bool initialized; // has pid been initialized
 
-    float ts;          // sample time in seconds
-    float integral;    // intergal of error
-    float last_output; // value of last output
+    double ts;          // sample time in seconds
+    double integral;    // intergal of error
+    double last_output; // value of last output
 
-    float p_c;     // coeff for P
-    float i_c;     // coeff for I
-    float ff_off;  // offset coeff for feed-forward term
-    float ff_gain; // gain for feed-forward term
+    double p_c;     // coeff for P
+    double i_c;     // coeff for I
+    double ff_off;  // offset coeff for feed-forward term
+    double ff_gain; // gain for feed-forward term
 
     limits_t i_lim;   // clamp of integral
     limits_t out_lim; // clamp of output
-    float slew_neg;
-    float slew_pos;
+    double slew_neg;
+    double slew_pos;
 } pid_info_t;
 
-float pid(pid_info_t* pidinfoptr, float input, float setpoint);
+double pid(pid_info_t* pidinfoptr, double input, double setpoint);
 
 /* Condensed version for use by the configuration. */
 struct pidinfo
 {
-    float ts;             // sample time in seconds
-    float p_c;            // coeff for P
-    float i_c;            // coeff for I
-    float ff_off;         // offset coeff for feed-forward term
-    float ff_gain;        // gain for feed-forward term
+    double ts;            // sample time in seconds
+    double p_c;           // coeff for P
+    double i_c;           // coeff for I
+    double ff_off;        // offset coeff for feed-forward term
+    double ff_gain;       // gain for feed-forward term
     ec::limits_t i_lim;   // clamp of integral
     ec::limits_t out_lim; // clamp of output
-    float slew_neg;
-    float slew_pos;
+    double slew_neg;
+    double slew_pos;
 };
 
 } // namespace ec
diff --git a/pid/ec/stepwise.cpp b/pid/ec/stepwise.cpp
index 4a71532..0a5c0b0 100644
--- a/pid/ec/stepwise.cpp
+++ b/pid/ec/stepwise.cpp
@@ -22,10 +22,10 @@
 
 namespace ec
 {
-float stepwise(const ec::StepwiseInfo& info, float input)
+double stepwise(const ec::StepwiseInfo& info, double input)
 {
-    float value = info.output[0]; // if we are below the lowest
-                                  // point, we set the lowest value
+    double value = info.output[0]; // if we are below the lowest
+                                   // point, we set the lowest value
 
     for (size_t ii = 1; ii < ec::maxStepwisePoints; ii++)
     {
diff --git a/pid/ec/stepwise.hpp b/pid/ec/stepwise.hpp
index 4034b47..bc7c204 100644
--- a/pid/ec/stepwise.hpp
+++ b/pid/ec/stepwise.hpp
@@ -26,13 +26,13 @@
 
 struct StepwiseInfo
 {
-    float ts; // sample time in seconds
-    float reading[maxStepwisePoints];
-    float output[maxStepwisePoints];
-    float positiveHysteresis;
-    float negativeHysteresis;
+    double ts; // sample time in seconds
+    double reading[maxStepwisePoints];
+    double output[maxStepwisePoints];
+    double positiveHysteresis;
+    double negativeHysteresis;
 };
 
-float stepwise(const ec::StepwiseInfo& info, float value);
+double stepwise(const ec::StepwiseInfo& info, double value);
 
 } // namespace ec
\ No newline at end of file
diff --git a/pid/fancontroller.cpp b/pid/fancontroller.cpp
index ce08185..4a61def 100644
--- a/pid/fancontroller.cpp
+++ b/pid/fancontroller.cpp
@@ -39,7 +39,7 @@
     return fan;
 }
 
-float FanController::inputProc(void)
+double FanController::inputProc(void)
 {
     double value = 0;
     std::vector<int64_t> values;
@@ -82,15 +82,15 @@
         value = *result;
     }
 
-    return static_cast<float>(value);
+    return value;
 }
 
-float FanController::setptProc(void)
+double FanController::setptProc(void)
 {
-    float maxRPM = _owner->getMaxRPMRequest();
+    double maxRPM = _owner->getMaxRPMRequest();
 
     // store for reference, and check if more or less.
-    float prev = getSetpoint();
+    double prev = getSetpoint();
 
     if (maxRPM > prev)
     {
@@ -110,9 +110,9 @@
     return (maxRPM);
 }
 
-void FanController::outputProc(float value)
+void FanController::outputProc(double value)
 {
-    float percent = value;
+    double percent = value;
 
     /* If doing tuning logging, don't go into failsafe mode. */
 #ifndef __TUNING_LOGGING__
@@ -133,7 +133,7 @@
     for (const auto& it : _inputs)
     {
         auto sensor = _owner->getSensor(it);
-        sensor->write(static_cast<double>(percent));
+        sensor->write(percent);
     }
 
     return;
diff --git a/pid/fancontroller.hpp b/pid/fancontroller.hpp
index 821c900..f3d3f4e 100644
--- a/pid/fancontroller.hpp
+++ b/pid/fancontroller.hpp
@@ -28,9 +28,9 @@
     {
     }
 
-    float inputProc(void) override;
-    float setptProc(void) override;
-    void outputProc(float value) override;
+    double inputProc(void) override;
+    double setptProc(void) override;
+    void outputProc(double value) override;
 
     FanSpeedDirection getFanDirection(void) const
     {
diff --git a/pid/pidcontroller.cpp b/pid/pidcontroller.cpp
index cbe2452..7be6ceb 100644
--- a/pid/pidcontroller.cpp
+++ b/pid/pidcontroller.cpp
@@ -28,9 +28,9 @@
 
 void PIDController::process(void)
 {
-    float input;
-    float setpt;
-    float output;
+    double input;
+    double setpt;
+    double output;
 
     // Get setpt value
     setpt = setptProc();
diff --git a/pid/pidcontroller.hpp b/pid/pidcontroller.hpp
index b7aaba6..9ed3be2 100644
--- a/pid/pidcontroller.hpp
+++ b/pid/pidcontroller.hpp
@@ -25,9 +25,9 @@
     {
     }
 
-    virtual float inputProc(void) override = 0;
-    virtual float setptProc(void) = 0;
-    virtual void outputProc(float value) override = 0;
+    virtual double inputProc(void) override = 0;
+    virtual double setptProc(void) = 0;
+    virtual void outputProc(double value) override = 0;
 
     void process(void) override;
 
@@ -35,11 +35,11 @@
     {
         return _id;
     }
-    float getSetpoint(void)
+    double getSetpoint(void)
     {
         return _setpoint;
     }
-    void setSetpoint(float setpoint)
+    void setSetpoint(double setpoint)
     {
         _setpoint = setpoint;
     }
@@ -55,6 +55,6 @@
   private:
     // parameters
     ec::pid_info_t _pid_info;
-    float _setpoint;
+    double _setpoint;
     std::string _id;
 };
diff --git a/pid/stepwisecontroller.cpp b/pid/stepwisecontroller.cpp
index 875a470..b81f8b1 100644
--- a/pid/stepwisecontroller.cpp
+++ b/pid/stepwisecontroller.cpp
@@ -32,11 +32,11 @@
 void StepwiseController::process(void)
 {
     // Get input value
-    float input = inputProc();
+    double input = inputProc();
 
     ec::StepwiseInfo info = get_stepwise_info();
 
-    float output = lastOutput;
+    double output = lastOutput;
 
     // Calculate new output if hysteresis allows
     if (std::isnan(output))
@@ -81,13 +81,13 @@
     return thermal;
 }
 
-float StepwiseController::inputProc(void)
+double StepwiseController::inputProc(void)
 {
     double value = _owner->getCachedValue(_inputs.at(0));
-    return static_cast<float>(value);
+    return value;
 }
 
-void StepwiseController::outputProc(float value)
+void StepwiseController::outputProc(double value)
 {
     _owner->addRPMSetPoint(value);
 
diff --git a/pid/stepwisecontroller.hpp b/pid/stepwisecontroller.hpp
index 37606c3..4aa8116 100644
--- a/pid/stepwisecontroller.hpp
+++ b/pid/stepwisecontroller.hpp
@@ -26,9 +26,9 @@
     {
     }
 
-    float inputProc(void) override;
+    double inputProc(void) override;
 
-    void outputProc(float value) override;
+    void outputProc(double value) override;
 
     void process(void) override;
 
@@ -50,6 +50,6 @@
     ec::StepwiseInfo _stepwise_info;
     std::string _id;
     std::vector<std::string> _inputs;
-    float lastInput = std::numeric_limits<float>::quiet_NaN();
-    float lastOutput = std::numeric_limits<float>::quiet_NaN();
+    double lastInput = std::numeric_limits<double>::quiet_NaN();
+    double lastOutput = std::numeric_limits<double>::quiet_NaN();
 };
diff --git a/pid/thermalcontroller.cpp b/pid/thermalcontroller.cpp
index 5388823..485688a 100644
--- a/pid/thermalcontroller.cpp
+++ b/pid/thermalcontroller.cpp
@@ -21,7 +21,7 @@
 
 std::unique_ptr<PIDController> ThermalController::createThermalPid(
     ZoneInterface* owner, const std::string& id,
-    const std::vector<std::string>& inputs, float setpoint,
+    const std::vector<std::string>& inputs, double setpoint,
     const ec::pidinfo& initial)
 {
     // ThermalController currently only supports precisely one input.
@@ -40,21 +40,21 @@
     return thermal;
 }
 
-// bmc_host_sensor_value_float
-float ThermalController::inputProc(void)
+// bmc_host_sensor_value_double
+double ThermalController::inputProc(void)
 {
     /*
      * This only supports one thermal input because it doesn't yet know how to
      * handle merging them, probably max?
      */
     double value = _owner->getCachedValue(_inputs.at(0));
-    return static_cast<float>(value);
+    return value;
 }
 
 // bmc_get_setpt
-float ThermalController::setptProc(void)
+double ThermalController::setptProc(void)
 {
-    float setpoint = getSetpoint();
+    double setpoint = getSetpoint();
 
     /* TODO(venture): Thermal setpoint invalid? */
 #if 0
@@ -71,7 +71,7 @@
 }
 
 // bmc_set_pid_output
-void ThermalController::outputProc(float value)
+void ThermalController::outputProc(double value)
 {
     _owner->addRPMSetPoint(value);
 
diff --git a/pid/thermalcontroller.hpp b/pid/thermalcontroller.hpp
index 040b222..8089da1 100644
--- a/pid/thermalcontroller.hpp
+++ b/pid/thermalcontroller.hpp
@@ -16,8 +16,8 @@
   public:
     static std::unique_ptr<PIDController>
         createThermalPid(ZoneInterface* owner, const std::string& id,
-                         const std::vector<std::string>& inputs, float setpoint,
-                         const ec::pidinfo& initial);
+                         const std::vector<std::string>& inputs,
+                         double setpoint, const ec::pidinfo& initial);
 
     ThermalController(const std::string& id,
                       const std::vector<std::string>& inputs,
@@ -27,9 +27,9 @@
     {
     }
 
-    float inputProc(void) override;
-    float setptProc(void) override;
-    void outputProc(float value) override;
+    double inputProc(void) override;
+    double setptProc(void) override;
+    void outputProc(double value) override;
 
   private:
     std::vector<std::string> _inputs;
diff --git a/pid/zone.cpp b/pid/zone.cpp
index f04a68d..cc135bf 100644
--- a/pid/zone.cpp
+++ b/pid/zone.cpp
@@ -35,7 +35,7 @@
 using tstamp = std::chrono::high_resolution_clock::time_point;
 using namespace std::literals::chrono_literals;
 
-float PIDZone::getMaxRPMRequest(void) const
+double PIDZone::getMaxRPMRequest(void) const
 {
     return _maximumRPMSetPt;
 }
@@ -61,7 +61,7 @@
     return _zoneId;
 }
 
-void PIDZone::addRPMSetPoint(float setpoint)
+void PIDZone::addRPMSetPoint(double setpoint)
 {
     _RPMSetPoints.push_back(setpoint);
 }
@@ -71,12 +71,12 @@
     _RPMSetPoints.clear();
 }
 
-float PIDZone::getFailSafePercent(void) const
+double PIDZone::getFailSafePercent(void) const
 {
     return _failSafePercent;
 }
 
-float PIDZone::getMinThermalRPMSetpoint(void) const
+double PIDZone::getMinThermalRPMSetpoint(void) const
 {
     return _minThermalRpmSetPt;
 }
@@ -108,8 +108,8 @@
 
 void PIDZone::determineMaxRPMRequest(void)
 {
-    float max = 0;
-    std::vector<float>::iterator result;
+    double max = 0;
+    std::vector<double>::iterator result;
 
     if (_RPMSetPoints.size() > 0)
     {
@@ -140,7 +140,7 @@
             ifs >> value;
 
             /* expecting RPM set-point, not pwm% */
-            max = static_cast<float>(value);
+            max = static_cast<double>(value);
         }
     }
     catch (const std::exception& e)
diff --git a/pid/zone.hpp b/pid/zone.hpp
index 32b6e22..223f3cb 100644
--- a/pid/zone.hpp
+++ b/pid/zone.hpp
@@ -27,10 +27,10 @@
     virtual ~ZoneInterface() = default;
 
     virtual double getCachedValue(const std::string& name) = 0;
-    virtual void addRPMSetPoint(float setpoint) = 0;
-    virtual float getMaxRPMRequest() const = 0;
+    virtual void addRPMSetPoint(double setpoint) = 0;
+    virtual double getMaxRPMRequest() const = 0;
     virtual bool getFailSafeMode() const = 0;
-    virtual float getFailSafePercent() const = 0;
+    virtual double getFailSafePercent() const = 0;
     virtual Sensor* getSensor(const std::string& name) = 0;
 };
 
@@ -42,7 +42,7 @@
 class PIDZone : public ZoneInterface, public ModeObject
 {
   public:
-    PIDZone(int64_t zone, float minThermalRpm, float failSafePercent,
+    PIDZone(int64_t zone, double minThermalRpm, double failSafePercent,
             const SensorManager& mgr, sdbusplus::bus::bus& bus,
             const char* objPath, bool defer) :
         ModeObject(bus, objPath, defer),
@@ -54,7 +54,7 @@
 #endif
     }
 
-    float getMaxRPMRequest(void) const override;
+    double getMaxRPMRequest(void) const override;
     bool getManualMode(void) const;
 
     /* Could put lock around this since it's accessed from two threads, but
@@ -63,10 +63,10 @@
     void setManualMode(bool mode);
     bool getFailSafeMode(void) const override;
     int64_t getZoneID(void) const;
-    void addRPMSetPoint(float setpoint) override;
+    void addRPMSetPoint(double setpoint) override;
     void clearRPMSetPoints(void);
-    float getFailSafePercent(void) const override;
-    float getMinThermalRPMSetpoint(void) const;
+    double getFailSafePercent(void) const override;
+    double getMinThermalRPMSetpoint(void) const;
 
     Sensor* getSensor(const std::string& name) override;
     void determineMaxRPMRequest(void);
@@ -99,14 +99,14 @@
 #endif
 
     const int64_t _zoneId;
-    float _maximumRPMSetPt = 0;
+    double _maximumRPMSetPt = 0;
     bool _manualMode = false;
-    const float _minThermalRpmSetPt;
-    const float _failSafePercent;
+    const double _minThermalRpmSetPt;
+    const double _failSafePercent;
 
     std::set<std::string> _failSafeSensors;
 
-    std::vector<float> _RPMSetPoints;
+    std::vector<double> _RPMSetPoints;
     std::vector<std::string> _fanInputs;
     std::vector<std::string> _thermalInputs;
     std::map<std::string, double> _cachedValuesByName;
diff --git a/scripts/pid-example.txt b/scripts/pid-example.txt
index 3549c8d..3627196 100644
--- a/scripts/pid-example.txt
+++ b/scripts/pid-example.txt
@@ -4,21 +4,21 @@
     inputs:   /* Sensor names that are inputs for the PID */
       fan2
       fan6
-    /* For temp/margin PIDs this is the set-point, ignored otherwise (float) */
+    /* For temp/margin PIDs this is the set-point, ignored otherwise (double) */
     set-point: 90.0
     pid: /* The PID calculation configuration. */
-      sampleperiod: 0.1        /* The input sample period. (float) */
-      p_coefficient: 0.01      /* The proportional coefficient. (float) */
-      i_coefficient: 0.001     /* The integral coefficient. (float) */
-      /* The feed-forward offset coefficient. (float) */
+      sampleperiod: 0.1        /* The input sample period. (double) */
+      p_coefficient: 0.01      /* The proportional coefficient. (double) */
+      i_coefficient: 0.001     /* The integral coefficient. (double) */
+      /* The feed-forward offset coefficient. (double) */
       ff_off_coefficient: 0.0
-      /* The feed-forward gain coefficient. (float) */
+      /* The feed-forward gain coefficient. (double) */
       ff_gain_coefficient: 0.0
-      i_limit:   /* The integral limit clamp, min, max (float) */
+      i_limit:   /* The integral limit clamp, min, max (double) */
         min: 0
         max: 100
-      out_limit: /* the PID output clamp, min, max (float) */
+      out_limit: /* the PID output clamp, min, max (double) */
         min: 0
         max: 100
-      slew_neg: -100 /* The slew negative value. (float) */
-      slew_pos: 0 /* The slew positive value. (float) */
+      slew_neg: -100 /* The slew negative value. (double) */
+      slew_pos: 0 /* The slew positive value. (double) */
diff --git a/scripts/zone-example.txt b/scripts/zone-example.txt
index 752fc01..88adc26 100644
--- a/scripts/zone-example.txt
+++ b/scripts/zone-example.txt
@@ -1,4 +1,4 @@
 0x01: /* The zone ID */
-  minthermalrpm: 3000.0 /* The minimum thermal RPM value. (float) */
-  /* The percent to use when the zone is in fail-safe mode. (float) */
+  minthermalrpm: 3000.0 /* The minimum thermal RPM value. (double) */
+  /* The percent to use when the zone is in fail-safe mode. (double) */
   failsafepercent: 90.0
diff --git a/sysfs/sysfswrite.cpp b/sysfs/sysfswrite.cpp
index 1ea4c4d..6ca9b25 100644
--- a/sysfs/sysfswrite.cpp
+++ b/sysfs/sysfswrite.cpp
@@ -21,12 +21,12 @@
 
 void SysFsWritePercent::write(double value)
 {
-    float minimum = getMin();
-    float maximum = getMax();
+    double minimum = getMin();
+    double maximum = getMax();
 
-    float range = maximum - minimum;
-    float offset = range * value;
-    float ovalue = offset + minimum;
+    double range = maximum - minimum;
+    double offset = range * value;
+    double ovalue = offset + minimum;
 
     std::ofstream ofs;
     ofs.open(_writepath);
diff --git a/test/controller_mock.hpp b/test/controller_mock.hpp
index c0af859..94c7cb5 100644
--- a/test/controller_mock.hpp
+++ b/test/controller_mock.hpp
@@ -14,7 +14,7 @@
     {
     }
 
-    MOCK_METHOD0(inputProc, float());
-    MOCK_METHOD0(setptProc, float());
-    MOCK_METHOD1(outputProc, void(float));
+    MOCK_METHOD0(inputProc, double());
+    MOCK_METHOD0(setptProc, double());
+    MOCK_METHOD1(outputProc, void(double));
 };
diff --git a/test/pid_fancontroller_unittest.cpp b/test/pid_fancontroller_unittest.cpp
index 57932c9..ad646bf 100644
--- a/test/pid_fancontroller_unittest.cpp
+++ b/test/pid_fancontroller_unittest.cpp
@@ -234,9 +234,9 @@
     // Grab pointer for mocking.
     SensorMock* sm1 = reinterpret_cast<SensorMock*>(s1.get());
 
-    // Converting from float to double for expectation.
-    float percent = 80;
-    double value = static_cast<double>(percent / 100);
+    // Converting from double to double for expectation.
+    double percent = 80;
+    double value = percent / 100;
 
     EXPECT_CALL(z, getSensor(StrEq("fan0"))).WillOnce(Return(s1.get()));
     EXPECT_CALL(*sm1, write(value));
diff --git a/test/pid_stepwisecontroller_unittest.cpp b/test/pid_stepwisecontroller_unittest.cpp
index 880864d..e3c4f09 100644
--- a/test/pid_stepwisecontroller_unittest.cpp
+++ b/test/pid_stepwisecontroller_unittest.cpp
@@ -24,7 +24,7 @@
     initial.positiveHysteresis = 2.0;
     initial.reading[0] = 20.0;
     initial.reading[1] = 30.0;
-    initial.reading[2] = std::numeric_limits<float>::quiet_NaN();
+    initial.reading[2] = std::numeric_limits<double>::quiet_NaN();
     initial.output[0] = 40.0;
     initial.output[1] = 60.0;
 
@@ -59,7 +59,7 @@
     initial.positiveHysteresis = 2.0;
     initial.reading[0] = 20.0;
     initial.reading[1] = 30.0;
-    initial.reading[2] = std::numeric_limits<float>::quiet_NaN();
+    initial.reading[2] = std::numeric_limits<double>::quiet_NaN();
     initial.output[0] = 40.0;
     initial.output[1] = 60.0;
 
diff --git a/test/pid_thermalcontroller_unittest.cpp b/test/pid_thermalcontroller_unittest.cpp
index 97550f8..6da309f 100644
--- a/test/pid_thermalcontroller_unittest.cpp
+++ b/test/pid_thermalcontroller_unittest.cpp
@@ -19,7 +19,7 @@
     ZoneMock z;
 
     std::vector<std::string> inputs = {"fleeting0"};
-    float setpoint = 10.0;
+    double setpoint = 10.0;
     ec::pidinfo initial;
 
     std::unique_ptr<PIDController> p = ThermalController::createThermalPid(
@@ -35,7 +35,7 @@
     ZoneMock z;
 
     std::vector<std::string> inputs = {};
-    float setpoint = 10.0;
+    double setpoint = 10.0;
     ec::pidinfo initial;
 
     std::unique_ptr<PIDController> p = ThermalController::createThermalPid(
@@ -51,7 +51,7 @@
     ZoneMock z;
 
     std::vector<std::string> inputs = {"fleeting0", "asdf"};
-    float setpoint = 10.0;
+    double setpoint = 10.0;
     ec::pidinfo initial;
 
     std::unique_ptr<PIDController> p = ThermalController::createThermalPid(
@@ -66,7 +66,7 @@
     ZoneMock z;
 
     std::vector<std::string> inputs = {"fleeting0"};
-    float setpoint = 10.0;
+    double setpoint = 10.0;
     ec::pidinfo initial;
 
     std::unique_ptr<PIDController> p = ThermalController::createThermalPid(
@@ -85,7 +85,7 @@
     ZoneMock z;
 
     std::vector<std::string> inputs = {"fleeting0"};
-    float setpoint = 10.0;
+    double setpoint = 10.0;
     ec::pidinfo initial;
 
     std::unique_ptr<PIDController> p = ThermalController::createThermalPid(
@@ -102,14 +102,14 @@
     ZoneMock z;
 
     std::vector<std::string> inputs = {"fleeting0"};
-    float setpoint = 10.0;
+    double setpoint = 10.0;
     ec::pidinfo initial;
 
     std::unique_ptr<PIDController> p = ThermalController::createThermalPid(
         &z, "therm1", inputs, setpoint, initial);
     EXPECT_FALSE(p == nullptr);
 
-    float value = 90.0;
+    double value = 90.0;
     EXPECT_CALL(z, addRPMSetPoint(value));
 
     p->outputProc(value);
diff --git a/test/pid_zone_unittest.cpp b/test/pid_zone_unittest.cpp
index 0b9aa9f..239a04a 100644
--- a/test/pid_zone_unittest.cpp
+++ b/test/pid_zone_unittest.cpp
@@ -42,8 +42,8 @@
     bool defer = true;
     const char* objPath = "/path/";
     int64_t zone = 1;
-    float minThermalRpm = 1000.0;
-    float failSafePercent = 0.75;
+    double minThermalRpm = 1000.0;
+    double failSafePercent = 0.75;
 
     int i;
     std::vector<std::string> properties;
@@ -92,8 +92,8 @@
     sdbusplus::SdBusMock sdbus_mock_host;
     sdbusplus::SdBusMock sdbus_mock_mode;
     int64_t zoneId = 1;
-    float minThermalRpm = 1000.0;
-    float failSafePercent = 0.75;
+    double minThermalRpm = 1000.0;
+    double failSafePercent = 0.75;
     bool defer = true;
     const char* objPath = "/path/";
     SensorManager mgr;
@@ -125,7 +125,7 @@
 
     // At least one value must be above the minimum thermal setpoint used in
     // the constructor otherwise it'll choose that value
-    std::vector<float> values = {100, 200, 300, 400, 500, 5000};
+    std::vector<double> values = {100, 200, 300, 400, 500, 5000};
     for (auto v : values)
     {
         zone->addRPMSetPoint(v);
@@ -148,7 +148,7 @@
     // Tests adding several RPM setpoints, however, they're all lower than the
     // configured minimal thermal set-point RPM value.
 
-    std::vector<float> values = {100, 200, 300, 400, 500};
+    std::vector<double> values = {100, 200, 300, 400, 500};
     for (auto v : values)
     {
         zone->addRPMSetPoint(v);
diff --git a/test/zone_mock.hpp b/test/zone_mock.hpp
index 79947fb..35a6b32 100644
--- a/test/zone_mock.hpp
+++ b/test/zone_mock.hpp
@@ -12,9 +12,9 @@
     virtual ~ZoneMock() = default;
 
     MOCK_METHOD1(getCachedValue, double(const std::string&));
-    MOCK_METHOD1(addRPMSetPoint, void(float));
-    MOCK_CONST_METHOD0(getMaxRPMRequest, float());
+    MOCK_METHOD1(addRPMSetPoint, void(double));
+    MOCK_CONST_METHOD0(getMaxRPMRequest, double());
     MOCK_CONST_METHOD0(getFailSafeMode, bool());
-    MOCK_CONST_METHOD0(getFailSafePercent, float());
+    MOCK_CONST_METHOD0(getFailSafePercent, double());
     MOCK_METHOD1(getSensor, Sensor*(const std::string&));
 };