From 2f0f097e97480debed1a18a688872c5cb24fe408 Mon Sep 17 00:00:00 2001 From: Michael Anderson Date: Sun, 10 Sep 2023 13:27:21 -0700 Subject: [PATCH] fix last push Signed-off-by: Michael Anderson --- buoy_gazebo/src/ElectroHydraulicPTO/ElectroHydraulicPTO.cpp | 4 ++-- buoy_gazebo/src/LatentData/LatentData/LatentData.hpp | 1 + .../PolytropicPneumaticSpring/PolytropicPneumaticSpring.cpp | 4 ++-- 3 files changed, 5 insertions(+), 4 deletions(-) diff --git a/buoy_gazebo/src/ElectroHydraulicPTO/ElectroHydraulicPTO.cpp b/buoy_gazebo/src/ElectroHydraulicPTO/ElectroHydraulicPTO.cpp index 97bb8bc6..7fcdc6ca 100644 --- a/buoy_gazebo/src/ElectroHydraulicPTO/ElectroHydraulicPTO.cpp +++ b/buoy_gazebo/src/ElectroHydraulicPTO/ElectroHydraulicPTO.cpp @@ -376,8 +376,8 @@ void ElectroHydraulicPTO::PreUpdate( const double N = this->dataPtr->x[0U]; double deltaP = this->dataPtr->x[1U]; double VBus = this->dataPtr->x[2U]; - const double eff_m = this->hyd_eff_m.eval(fabs(N)); - const double eff_v = this->hyd_eff_v.eval(fabs(deltaP)); + const double eff_m = this->dataPtr->functor.hyd_eff_m.eval(fabs(N)); + const double eff_v = this->dataPtr->functor.hyd_eff_v.eval(fabs(deltaP)); VBus = std::min(VBus, this->dataPtr->MaxTargetVoltage); double BusPower = this->dataPtr->functor.BusPower; diff --git a/buoy_gazebo/src/LatentData/LatentData/LatentData.hpp b/buoy_gazebo/src/LatentData/LatentData/LatentData.hpp index 0a579158..5cb93f5f 100644 --- a/buoy_gazebo/src/LatentData/LatentData/LatentData.hpp +++ b/buoy_gazebo/src/LatentData/LatentData/LatentData.hpp @@ -88,6 +88,7 @@ struct AirSpring double dQ_dt{0.0}; // heat loss rate double piston_position{0.0}; // meters double piston_velocity{0.0}; // m/s + double mass{0.0}; // kg bool operator==(const AirSpring & that) const { diff --git a/buoy_gazebo/src/PolytropicPneumaticSpring/PolytropicPneumaticSpring.cpp b/buoy_gazebo/src/PolytropicPneumaticSpring/PolytropicPneumaticSpring.cpp index 0f995e86..bdbb5e5f 100644 --- a/buoy_gazebo/src/PolytropicPneumaticSpring/PolytropicPneumaticSpring.cpp +++ b/buoy_gazebo/src/PolytropicPneumaticSpring/PolytropicPneumaticSpring.cpp @@ -572,9 +572,9 @@ void PolytropicPneumaticSpring::PreUpdate( if (this->dataPtr->config_->is_upper) { spring_state.range_finder = x; - spring_state.upper_psi = PASCAL_TO_PSI * this->dataPtr->P; + spring_state.upper_psi = this->dataPtr->P / buoy_utils::PASCAL_PER_PSI; } else { - spring_state.lower_psi = PASCAL_TO_PSI * this->dataPtr->P; + spring_state.lower_psi = this->dataPtr->P / buoy_utils::PASCAL_PER_PSI; } _ecm.SetComponentData(