mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
SITL: fixed frame_property build error with older C++ compilers
This commit is contained in:
parent
c72f2e57b0
commit
9257d29717
@ -93,7 +93,7 @@ void Submarine::calculate_forces(const struct sitl_input &input, Vector3f &rot_a
|
||||
*/
|
||||
float Submarine::calculate_buoyancy_acceleration()
|
||||
{
|
||||
float below_water_level = position.z - frame_proprietary.height/2;
|
||||
float below_water_level = position.z - frame_property.height/2;
|
||||
|
||||
// Completely above water level
|
||||
if (below_water_level < 0) {
|
||||
@ -101,12 +101,12 @@ float Submarine::calculate_buoyancy_acceleration()
|
||||
}
|
||||
|
||||
// Completely below water level
|
||||
if (below_water_level > frame_proprietary.height/2) {
|
||||
return frame_proprietary.bouyancy_acceleration;
|
||||
if (below_water_level > frame_property.height/2) {
|
||||
return frame_property.bouyancy_acceleration;
|
||||
}
|
||||
|
||||
// bouyant force is proportional to fraction of height in water
|
||||
return frame_proprietary.bouyancy_acceleration * below_water_level/frame_proprietary.height;
|
||||
return frame_property.bouyancy_acceleration * below_water_level/frame_property.height;
|
||||
};
|
||||
|
||||
/*
|
||||
|
@ -45,9 +45,7 @@ public:
|
||||
protected:
|
||||
const float water_density = 1023.6; // (kg/m^3) At a temperature of 25 °C, salinity of 35 g/kg and 1 atm pressure
|
||||
|
||||
const class FrameConfig {
|
||||
public:
|
||||
FrameConfig() = default;
|
||||
const struct {
|
||||
float length = 0.457; // x direction (meters)
|
||||
float width = 0.338; // y direction (meters)
|
||||
float height = 0.254; // z direction (meters)
|
||||
@ -55,7 +53,7 @@ protected:
|
||||
float net_bouyancy = 2.0; // (N)
|
||||
|
||||
float bouyancy_acceleration = GRAVITY_MSS + net_bouyancy/weight;
|
||||
} frame_proprietary;
|
||||
} frame_property;
|
||||
|
||||
bool on_ground() const override;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user