Theory¶
Modeling Technique Overview¶
The numerical modeling used in this simulator relies upon the Gazebo simulators ability to solve for the motion of a collection of rigid bodies connected by various types of joints. Gazebo can use several different physics solvers to perform this solution, and the wave-energy buoy simulator in this project uses the DART physics engine. The physics engine solves the multi-body six degree-of-freedom problem for the motion of the connected buoy, power-take-off device, and heave cone, subject to initial conditions and forces that act on the various components as the simulation progresses. In the Gazebo simulator, these forces are provided by plugin code that applies forces to each body based on the state (position and velocity) of each component in the system at each timestep.
The Gazebo simulator already includes several plugins that provide relevant forces such as buoyancy and hydrodynamic drag. Additionally, several additional plugins have been created for this simulator that provide the forcings on the system due to the electro-hydraulic power-take-off system, the pneumatic spring system, the tether connecting the PTO to the heave-cone, the mooring system that anchors the system, and the forcing on the buoy from the ocean surface waves. The sections below outline some details about how each of these forcings are modelled and computed. First however, the specific physical characteristics of the MBARI WEC are tabulated for reference.
Physical Characteristics¶
Each rigid body in the simulation has a "Link Frame" coordinate system in which all other characteristics of the body are defined in for computational purposes. This link-frame coordinate system is often selected to be at the location of a joint that connects the various bodies (which are also called links in the vernacular of Gazebo). Also, the description below includes alternative notation for added mass, e.g. , in the style of Newman.
Surface Buoy¶
Description | Units | ||
---|---|---|---|
Buoy Mass | 1400 | kg | |
Displacement (undisturbed buoy) | 2.39 | m | |
Center of Gravity in Link Frame (x,y,z) | (0.0, 0.0, 2.03) | m | |
Center of Buoyancy in Link Frame (x,y,z) | (0.0, 0.0, 2.05) | m | |
Center of Waterplane in Link Frame, including PTO and cone | (0.0, 0.0, 2.27) | m | |
Second moment of area of water plane, about roll axis | 1.37 | m | |
Second moment of area of water plane, about pitch axis | 1.37 | m | |
Roll Moment of Inertia (MOI) about center of mass | 1450 | kg m | |
Pitch Moment of Inertia about center of mass | 1450 | kg m | |
Yaw Moment of Inertia about center of mass | 670 | kg m | |
Waterplane Area (undisturbed buoy) | 5.47 | m | |
Surge Added Mass () | 260 | kg | |
Surge-Pitch Added Mass, origin at c.m. () | 150 | kg | |
Sway Added Mass ( ) | 260 | kg | |
Sway-Roll Added Mass, origin at c.m. () | -150 | kg | |
Heave Added Mass () | 3080 | kg | |
Roll Added Mass MOI, origin at c.m. () | 330 | kg m | |
Pitch Added Mass MOI, origin at c.m. () | 330 | kg m | |
Surge Quadratic Drag | -430 | kg/m | |
Sway Quadratic Drag | -430 | kg/m | |
Heave Quadratic Drag | -3280 | kg/m | |
Roll Quadratic Drag: | -880 | kg m | |
Pitch Quadratic Drag: | -880 | kg m | |
Yaw Quadratic Drag: | -50 | kg m |
- Buoy Link Frame is located at base of the buoy bridle at the pivot.
- Unspecified stability derivative values (, , , etc) are zero.
- Stability derivatives are specified about the link frame origin, i.e. the pivot.
- Mass-moments of inertia and added-mass-moments of inertia are specified about the center of mass.
- Added-mass values are infinite frequency.
- Free-Surface Hydrodynamic Coefficients and Impulse Response Functions can be found here:
Power Take-Off Device¶
Description | Units | ||
---|---|---|---|
PTO Mass | 605 | kg | |
PTO Displacement | .205 | m | |
Center of Gravity in Link Frame (x,y,z) | (0.0, 0.0, -4.0) | m | |
Center of Buoyancy in Link Frame (x,y,z) | (0.0, 0.0, -3.0) | m | |
Roll Moment of Inertia about center of mass | 3525 | kg m | |
Pitch Moment of Inertia about center of mass | 3525 | kg m | |
Yaw Moment of Inertia about center of mass | 10 | kg m | |
Surge Added Mass () | 310 | kg | |
Sway Added Mass () | 310 | kg | |
Heave Added Mass () | 10 | kg | |
Roll Added Mass MOI () | 2030 | kg m | |
Pitch Added Mass MOI () | 2030 | kg m | |
Surge Quadratic Drag | -1140 | kg/m | |
Sway Quadratic Drag | -1140 | kg/m | |
Heave Quadratic Drag | -50 | kg/m | |
Roll Quadratic Drag | -195400 | kg m | |
Pitch Quadratic Drag | -195400 | kg m | |
Yaw Quadratic Drag | -50 | kg m |
- PTO Link Frame is located at top attachment of the PTO (where connects to the buoy).
- Unspecified stability derivative values (, , , etc) are zero.
- Stability derivatives are specified about the link frame origin, i.e. the pivot.
- Mass-moments of inertia and added-mass-moments of inertia are specified about the center of mass.
Piston¶
Description | Units | ||
---|---|---|---|
Piston Mass | 48.0 | kg | |
Center of Gravity in Link Frame (x,y,z) | (0.0, 0.0, -2.58) | m | |
Roll Moment of Inertia | 100.0 | kg m | |
Pitch Moment of Inertia | 100.0 | kg m | |
Yaw Moment of Inertia | 5.0 | kg m |
- The piston is contained with the PTO housing, so it has mass and moments of inertial, but contributes no buoyancy, added mass, or quadratic fluid drag.
Heave Cone¶
Description | Units | ||
---|---|---|---|
Heave Cone Mass | 820 | kg | |
Heave Cone Displacement | .12 | m | |
Center of Gravity in Link Frame (x,y,z) | (0.0, 0.0, -1.25) | m | |
Center of Buoyancy in Link Frame (x,y,z) | (0.0, 0.0, -1.21) | m | |
Roll Moment of Inertia about the center of mass | 340 | kg m | |
Pitch Moment of Inertia about the center of mass | 340 | kg m | |
Yaw Moment of Inertia about the center of mass | 610 | kg m | |
Surge Added Mass () | 720 | kg | |
Sway Added Mass () | 720 | kg | |
Sway-Roll Added Mass MOI () | -900 | kg m | |
Heave Added Mass: Doors Closed () | 9330 | kg | |
Heave Added Mass: Doors Open | 3000 | kg | |
Roll Added Mass MOI () | 2870 | kg m | |
Pitch Added Mass MOI() | 2870 | kg m | |
Yaw Added Mass MOI () | 10 | kg m | |
Surge Quadratic Drag | -1580 | kg/m | |
Sway Quadratic Drag | -1580 | kg/m | |
Vertical Quadratic Drag: Doors Open | -3200 | kg/m | |
Vertical Quadratic Drag: Doors Closed | -3900 | kg/m | |
Roll Quadratic Drag: | -4620 | kg m | |
Pitch Quadratic Drag: | -4620 | kg m | |
Yaw Quadratic Drag: | -50 | kg m |
- Heave-Cone Link Frame is located at top attachment of the Heave Cone (where it connects to the tether).
- Unspecified stability derivative values (, , , etc) are zero.
- Stability derivatives are specified about the link frame origin, i.e. the pivot.
- Mass-moments of inertia and added-mass-moments of inertia are specified about the center of mass.
Electro-Hydraulic PTO Forces¶
Pneumatic Spring Forces¶
Definitions¶
Description | Units | |
---|---|---|
Piston position | m | |
Piston velocity | m/s | |
Mass of gas in chamber | kg | |
Temperature of gas | K | |
Gas pressure | Pa | |
Chamber volume (dependent on piston position) | m | |
Specific Gas Constant N | J/kg/K | |
Chamber dead volume (fully compressed) | m | |
Specific Heat Capacity N (constant pressure) | J/kg/K | |
Surface area of piston head | m | |
Polytropic index (Adiabatic if for N) | N/A | |
Coefficient of heat transfer (Newton's Law of Cooling) | 1/s |
Model¶
Under compression and expansion, the pressure, volume and temperature of the Nitrogen in each chamber evolves according to Ideal Gas Law:
and a polytropic process:
with hysteresis, there are two values for the polytropic index, and , to capture behavior when the gas is compressing or expanding. Using this quasi-static solution and discrete time steps, and also incorporating hysteresis, the process becomes:
where is the current time step.
Whenever the piston velocity is slow enough, the process is dominated by heat loss and modeled with Newton's Law of Cooling (using forward difference) followed by an update of pressure using Ideal Gas Law:
The mass of the Nitrogen in each chamber is determined from inputs in the SDF:
and is used for mass flow between chambers in simulating the pump/valve.
Determining Parameter Values¶
Linear regression was used to determine the polytropic indices for each chamber using empirical data from the physical system. Using pressure vs volume curves, is determined from increasing volume, and is determined from decreasing volume. The data is then preconditioned by taking the logarithm to linearize and perform regression to find the parameters. For a polytropic process:
so,
in block matrix notation where and are the arrays of volume and pressure data, respectively. The other parameters in the system are taken from CAD or empirically determined by comparing logged data from prescribed motion between simulation and the physical test bench.