Skip to content

Commit

Permalink
Added Shaft Mechanical Power to Latent Data
Browse files Browse the repository at this point in the history
  • Loading branch information
hamilton8415 committed Sep 13, 2023
1 parent cfd1e1a commit 1acea31
Show file tree
Hide file tree
Showing 5 changed files with 16 additions and 93 deletions.
63 changes: 0 additions & 63 deletions buoy_gazebo/src/ElectroHydraulicPTO/ElectroHydraulicLoss.hpp

This file was deleted.

39 changes: 10 additions & 29 deletions buoy_gazebo/src/ElectroHydraulicPTO/ElectroHydraulicPTO.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,6 @@

#include "ElectroHydraulicSoln.hpp"
#include "ElectroHydraulicState.hpp"
#include "ElectroHydraulicLoss.hpp"
#include "BatteryState.hpp"

#include <LatentData/LatentData.hpp>
Expand Down Expand Up @@ -265,18 +264,6 @@ void ElectroHydraulicPTO::PreUpdate(
pto_state = buoy_gazebo::ElectroHydraulicState(pto_state_comp->Data());
}

buoy_gazebo::ElectroHydraulicLoss pto_loss;
if (_ecm.EntityHasComponentType(
this->dataPtr->PrismaticJointEntity,
buoy_gazebo::components::ElectroHydraulicLoss().TypeId()))
{
auto pto_loss_comp =
_ecm.Component<buoy_gazebo::components::ElectroHydraulicLoss>(
this->dataPtr->PrismaticJointEntity);

pto_loss = buoy_gazebo::ElectroHydraulicLoss(pto_loss_comp->Data());
}

buoy_gazebo::LatentData latent_data;
if (_ecm.EntityHasComponentType(
this->dataPtr->model.Entity(),
Expand Down Expand Up @@ -421,24 +408,22 @@ void ElectroHydraulicPTO::PreUpdate(
pto_state.target_a = this->dataPtr->functor.I_Wind.I;


pto_loss.hydraulic_motor_loss += 1.0;
pto_loss.relief_valve_loss += 2.0;
pto_loss.motor_drive_i2r_loss =
this->dataPtr->functor.MotorDriveISquaredRLoss(this->dataPtr->functor.I_Wind.I);
pto_loss.motor_drive_switching_loss = this->dataPtr->functor.MotorDriveSwitchingLoss(VBus);
pto_loss.motor_drive_friction_loss = this->dataPtr->functor.MotorDriveFrictionLoss(N);
pto_loss.battery_i2r_loss = I_Batt * I_Batt * this->dataPtr->Ri;

double piston_force = -deltaP * this->dataPtr->PistonArea * buoy_utils::NEWTONS_PER_LB;

latent_data.electro_hydraulic.valid = true;
latent_data.electro_hydraulic.inst_power = VBus * (I_Batt + I_Load);
latent_data.electro_hydraulic.shaft_mech_power =
this->dataPtr->functor.ShaftMechPower;
latent_data.electro_hydraulic.rpm = N;
latent_data.electro_hydraulic.force = piston_force;
latent_data.electro_hydraulic.motor_drive_i2r_loss = pto_loss.motor_drive_i2r_loss;
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.motor_drive_i2r_loss =
this->dataPtr->functor.MotorDriveISquaredRLoss(this->dataPtr->functor.I_Wind.I);
latent_data.electro_hydraulic.motor_drive_switching_loss =
this->dataPtr->functor.MotorDriveSwitchingLoss(VBus);
latent_data.electro_hydraulic.motor_drive_friction_loss =
this->dataPtr->functor.MotorDriveFrictionLoss(N);
latent_data.electro_hydraulic.battery_i2r_loss =
I_Batt * I_Batt * this->dataPtr->Ri;
latent_data.electro_hydraulic.eff_m = eff_m;
latent_data.electro_hydraulic.eff_v = eff_v;

Expand All @@ -452,10 +437,6 @@ void ElectroHydraulicPTO::PreUpdate(

auto stampMsg = gz::sim::convert<gz::msgs::Time>(_info.simTime);

_ecm.SetComponentData<buoy_gazebo::components::ElectroHydraulicLoss>(
this->dataPtr->PrismaticJointEntity,
pto_loss);

_ecm.SetComponentData<buoy_gazebo::components::LatentData>(
this->dataPtr->model.Entity(),
latent_data);
Expand Down
3 changes: 2 additions & 1 deletion buoy_gazebo/src/ElectroHydraulicPTO/ElectroHydraulicSoln.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,7 @@ struct ElectroHydraulicSoln : Functor<double>
mutable double BusPower;
double Q;

mutable double ShaftMechPower;
private:
static const std::vector<double> Peff; // psi
static const std::vector<double> Neff; // rpm
Expand Down Expand Up @@ -170,7 +171,7 @@ struct ElectroHydraulicSoln : Functor<double>
const double T_applied =
1.375 * this->I_Wind.TorqueConstantInLbPerAmp * WindCurr;

double ShaftMechPower = T_applied * buoy_utils::NM_PER_INLB *
ShaftMechPower = T_applied * buoy_utils::NM_PER_INLB *
x[0U] * buoy_utils::RPM_TO_RAD_PER_SEC;
BusPower = -ShaftMechPower - (
MotorDriveFrictionLoss(x[0U]) +
Expand Down
2 changes: 2 additions & 0 deletions buoy_gazebo/src/LatentData/LatentData/LatentData.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,7 @@ struct AirSpring
struct ElectroHydraulic
{
bool valid{false};
double shaft_mech_power{0.0}; // Watts
double inst_power{0.0}; // Watts
double rpm{0.0};
double force{0.0}; // Newtons
Expand All @@ -120,6 +121,7 @@ struct ElectroHydraulic
bool operator==(const ElectroHydraulic & that) const
{
bool equal = (this->valid == that.valid);
equal &= fabs(this->shaft_mech_power - that.shaft_mech_power) < 1e-7F;
equal &= fabs(this->inst_power - that.inst_power) < 1e-7F;
equal &= fabs(this->force - that.force) < 1e-7F;
equal &= fabs(this->motor_drive_i2r_loss - that.motor_drive_i2r_loss) < 1e-7F;
Expand Down
2 changes: 2 additions & 0 deletions buoy_gazebo/src/LatentData/LatentData/LatentDataPublisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -265,6 +265,8 @@ void LatentDataPublisher::PostUpdate(
this->dataPtr->latent_data_.lower_spring.piston_velocity =
latent_data.lower_spring.piston_velocity;

this->dataPtr->latent_data_.electro_hydraulic.shaft_mech_power =
latent_data.electro_hydraulic.shaft_mech_power;
this->dataPtr->latent_data_.electro_hydraulic.inst_power =
latent_data.electro_hydraulic.inst_power;
this->dataPtr->latent_data_.electro_hydraulic.rpm =
Expand Down

0 comments on commit 1acea31

Please sign in to comment.