Skip to content

Commit

Permalink
add gas mass and eff_v/m; comment units; use buoy_utils/constants.h i…
Browse files Browse the repository at this point in the history
…n spring

Signed-off-by: Michael Anderson <[email protected]>
  • Loading branch information
andermi committed Sep 10, 2023
1 parent f85f14b commit dadcc18
Show file tree
Hide file tree
Showing 5 changed files with 24 additions and 6 deletions.
5 changes: 5 additions & 0 deletions buoy_gazebo/src/ElectroHydraulicPTO/ElectroHydraulicPTO.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -376,6 +376,9 @@ 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));

VBus = std::min(VBus, this->dataPtr->MaxTargetVoltage);
double BusPower = this->dataPtr->functor.BusPower;

Expand Down Expand Up @@ -436,6 +439,8 @@ void ElectroHydraulicPTO::PreUpdate(
latent_data.electro_hydraulic.motor_drive_switching_loss = pto_loss.motor_drive_switching_loss;
latent_data.electro_hydraulic.motor_drive_friction_loss = pto_loss.motor_drive_friction_loss;
latent_data.electro_hydraulic.battery_i2r_loss = pto_loss.battery_i2r_loss;
latent_data.electro_hydraulic.eff_m = eff_m;
latent_data.electro_hydraulic.eff_v = eff_v;

_ecm.SetComponentData<buoy_gazebo::components::BatteryState>(
this->dataPtr->PrismaticJointEntity,
Expand Down
10 changes: 6 additions & 4 deletions buoy_gazebo/src/LatentData/LatentData/LatentData.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,10 +106,12 @@ struct ElectroHydraulic
double inst_power{0.0}; // Watts
double rpm{0.0};
double force{0.0}; // Newtons
double motor_drive_i2r_loss{0.0};
double motor_drive_friction_loss{0.0};
double motor_drive_switching_loss{0.0};
double battery_i2r_loss{0.0};
double motor_drive_i2r_loss{0.0}; // Watts
double motor_drive_friction_loss{0.0}; // Watts
double motor_drive_switching_loss{0.0}; // Watts
double battery_i2r_loss{0.0}; // Watts
double eff_m{0.0}; // mechanical efficiency
double eff_v{0.0}; // volumetric efficiency

bool operator==(const ElectroHydraulic & that) const
{
Expand Down
6 changes: 6 additions & 0 deletions buoy_gazebo/src/LatentData/LatentData/LatentDataPublisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -279,6 +279,12 @@ void LatentDataPublisher::PostUpdate(
latent_data.electro_hydraulic.motor_drive_friction_loss;
this->dataPtr->latent_data_.electro_hydraulic.battery_i2r_loss =
latent_data.electro_hydraulic.battery_i2r_loss;
this->dataPtr->latent_data_.electro_hydraulic.eff_m =
latent_data.electro_hydraulic.eff_m;
this->dataPtr->latent_data_.electro_hydraulic.eff_v =
latent_data.electro_hydraulic.eff_v;



this->dataPtr->latent_data_.wave_body.buoyancy.force.x =
latent_data.wave_body.buoyant_force.X();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@
#include "SpringState.hpp"
#include <LatentData/LatentData.hpp>

#include <buoy_utils/Constants.hpp>


using namespace std::chrono_literals;

Expand Down Expand Up @@ -528,8 +530,8 @@ void PolytropicPneumaticSpring::PreUpdate(
const int dt_nano =
static_cast<int>(std::chrono::duration_cast<std::chrono::nanoseconds>(_info.dt).count());

static const double PASCAL_TO_PSI = 1.450377e-4; // PSI/Pascal
const double pressure_diff = (spring_state.lower_psi - spring_state.upper_psi) / PASCAL_TO_PSI;
const double pressure_diff =
(spring_state.lower_psi - spring_state.upper_psi) * buoy_utils::PASCAL_PER_PSI;

if (spring_state.valve_command) {
openValve(
Expand Down Expand Up @@ -597,13 +599,15 @@ void PolytropicPneumaticSpring::PreUpdate(
latent_data.upper_spring.dQ_dt = this->dataPtr->Q_rate;
latent_data.upper_spring.piston_position = x;
latent_data.upper_spring.piston_velocity = v;
latent_data.upper_spring.mass = this->dataPtr->mass;
} else {
latent_data.lower_spring.valid = true;
latent_data.lower_spring.force = this->dataPtr->F;
latent_data.lower_spring.T = this->dataPtr->T;
latent_data.lower_spring.dQ_dt = this->dataPtr->Q_rate;
latent_data.lower_spring.piston_position = this->dataPtr->config_->stroke - x;
latent_data.lower_spring.piston_velocity = -v;
latent_data.lower_spring.mass = this->dataPtr->mass;
}

_ecm.SetComponentData<buoy_gazebo::components::LatentData>(
Expand Down
1 change: 1 addition & 0 deletions buoy_gazebo/src/buoy_utils/Constants.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ static constexpr double NM_PER_INLB{0.112984829};
static constexpr double INLB_PER_NM{8.851};
static constexpr double INCHES_PER_METER{39.4};
static constexpr double NEWTONS_PER_LB{4.4482};
static constexpr double PASCAL_PER_PSI = 6894.757; // Pascal/PSI
} // namespace buoy_utils


Expand Down

0 comments on commit dadcc18

Please sign in to comment.