/
Buoyancy.cc
275 lines (238 loc) · 8.97 KB
/
Buoyancy.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
/*
* Copyright (C) 2020 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#include <ignition/msgs/wrench.pb.h>
#include <mutex>
#include <string>
#include <vector>
#include <ignition/common/Mesh.hh>
#include <ignition/common/MeshManager.hh>
#include <ignition/common/Profiler.hh>
#include <ignition/plugin/Register.hh>
#include <ignition/math/Helpers.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/math/Vector3.hh>
#include <ignition/msgs/Utility.hh>
#include <sdf/sdf.hh>
#include "ignition/gazebo/components/CenterOfVolume.hh"
#include "ignition/gazebo/components/Collision.hh"
#include "ignition/gazebo/components/Gravity.hh"
#include "ignition/gazebo/components/Inertial.hh"
#include "ignition/gazebo/components/Link.hh"
#include "ignition/gazebo/components/Pose.hh"
#include "ignition/gazebo/components/Volume.hh"
#include "ignition/gazebo/components/World.hh"
#include "ignition/gazebo/Link.hh"
#include "ignition/gazebo/Model.hh"
#include "ignition/gazebo/Util.hh"
#include "Buoyancy.hh"
using namespace ignition;
using namespace gazebo;
using namespace systems;
class ignition::gazebo::systems::BuoyancyPrivate
{
/// \brief Get the fluid density based on a pose. This function can be
/// used to adjust the fluid density based on the pose of an object in the
/// world. This function currently returns a constant value, see the todo
/// in the function implementation.
/// \param[in] _pose The pose to use when computing the fluid density. The
/// pose frame is left undefined because this function currently returns
/// a constant value, see the todo in the function implementation.
/// \return The fluid density at the givein pose.
public: double FluidDensity(const math::Pose3d &_pose) const;
/// \brief Model interface
public: Entity world{kNullEntity};
/// \brief The density of the fluid in which the object is submerged in
/// kg/m^3. Defaults to 1000, the fluid density of water.
public: double fluidDensity{1000};
};
//////////////////////////////////////////////////
double BuoyancyPrivate::FluidDensity(const math::Pose3d & /*_pose*/) const
{
// \todo(nkoenig) Adjust the fluid density based on the provided pose.
// This could take into acount:
// 1. Transition from water to air. Currently this function is used for
// a whole link, but when transitioning between mediums a link may span
// both mediums. Surface tension could also be a factor.
// 2. Fluid density changes based on depth below the water surface and
// height above water surface.
return this->fluidDensity;
}
//////////////////////////////////////////////////
Buoyancy::Buoyancy()
: dataPtr(std::make_unique<BuoyancyPrivate>())
{
}
//////////////////////////////////////////////////
void Buoyancy::Configure(const Entity &_entity,
const std::shared_ptr<const sdf::Element> &_sdf,
EntityComponentManager &_ecm,
EventManager &/*_eventMgr*/)
{
// Store the world.
this->dataPtr->world = _entity;
// Get the gravity (defined in world frame)
const components::Gravity *gravity = _ecm.Component<components::Gravity>(
this->dataPtr->world);
if (!gravity)
{
ignerr << "Unable to get the gravity vector. Make sure this plugin is "
<< "attached to a <world>, not a <model>." << std::endl;
return;
}
if (_sdf->HasElement("uniform_fluid_density"))
{
this->dataPtr->fluidDensity = _sdf->Get<double>("uniform_fluid_density");
}
}
//////////////////////////////////////////////////
void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info,
ignition::gazebo::EntityComponentManager &_ecm)
{
IGN_PROFILE("Buoyancy::PreUpdate");
const components::Gravity *gravity = _ecm.Component<components::Gravity>(
this->dataPtr->world);
if (!gravity)
{
ignerr << "Unable to get the gravity vector. Has gravity been defined?"
<< std::endl;
return;
}
// Compute the volume and center of volume for each new link
_ecm.EachNew<components::Link, components::Inertial>(
[&](const Entity &_entity,
const components::Link *,
const components::Inertial *) -> bool
{
// Skip if the entity already has a volume and center of volume
if (_ecm.EntityHasComponentType(_entity,
components::CenterOfVolume().TypeId()) &&
_ecm.EntityHasComponentType(_entity,
components::Volume().TypeId()))
{
return true;
}
Link link(_entity);
std::vector<Entity> collisions = _ecm.ChildrenByComponents(
_entity, components::Collision());
double volumeSum = 0;
ignition::math::Vector3d weightedPosSum =
ignition::math::Vector3d::Zero;
// Compute the volume of the link by iterating over all the collision
// elements and storing each geometry's volume.
for (const Entity &collision : collisions)
{
double volume = 0;
const components::CollisionElement *coll =
_ecm.Component<components::CollisionElement>(collision);
if (!coll)
{
ignerr << "Invalid collision pointer. This shouldn't happen\n";
continue;
}
switch (coll->Data().Geom()->Type())
{
case sdf::GeometryType::BOX:
volume = coll->Data().Geom()->BoxShape()->Shape().Volume();
break;
case sdf::GeometryType::SPHERE:
volume = coll->Data().Geom()->SphereShape()->Shape().Volume();
break;
case sdf::GeometryType::CYLINDER:
volume = coll->Data().Geom()->CylinderShape()->Shape().Volume();
break;
case sdf::GeometryType::PLANE:
// Ignore plane shapes. They have no volume and are not expected
// to be buoyant.
break;
case sdf::GeometryType::MESH:
{
std::string file = asFullPath(
coll->Data().Geom()->MeshShape()->Uri(),
coll->Data().Geom()->MeshShape()->FilePath());
if (common::MeshManager::Instance()->IsValidFilename(file))
{
const common::Mesh *mesh =
common::MeshManager::Instance()->Load(file);
if (mesh)
volume = mesh->Volume();
else
ignerr << "Unable to load mesh[" << file << "]\n";
}
else
{
ignerr << "Invalid mesh filename[" << file << "]\n";
}
break;
}
default:
ignerr << "Unsupported collision geometry["
<< static_cast<int>(coll->Data().Geom()->Type()) << "]\n";
break;
}
volumeSum += volume;
math::Pose3d pose = worldPose(collision, _ecm);
weightedPosSum += volume * pose.Pos();
}
if (volumeSum > 0)
{
// Store the center of volume
math::Pose3d linkWorldPose = worldPose(_entity, _ecm);
_ecm.CreateComponent(_entity, components::CenterOfVolume(
weightedPosSum / volumeSum - linkWorldPose.Pos()));
// Store the volume
_ecm.CreateComponent(_entity, components::Volume(volumeSum));
}
return true;
});
// Only update if not paused.
if (_info.paused)
return;
_ecm.Each<components::Link,
components::Volume,
components::CenterOfVolume>(
[&](const Entity &_entity,
const components::Link *,
const components::Volume *_volume,
const components::CenterOfVolume *_centerOfVolume) -> bool
{
// World pose of the link.
math::Pose3d linkWorldPose = worldPose(_entity, _ecm);
// By Archimedes' principle,
// buoyancy = -(mass*gravity)*fluid_density/object_density
// object_density = mass/volume, so the mass term cancels.
math::Vector3d buoyancy =
-this->dataPtr->FluidDensity(linkWorldPose) *
_volume->Data() * gravity->Data();
// Convert the center of volume to the world frame
math::Vector3d offsetWorld = linkWorldPose.Rot().RotateVector(
_centerOfVolume->Data());
// Compute the torque that should be applied due to buoyancy and
// the center of volume.
math::Vector3d torque = offsetWorld.Cross(buoyancy);
// Apply the wrench to the link. This wrench is applied in the
// Physics System.
Link link(_entity);
link.AddWorldWrench(_ecm, buoyancy, torque);
return true;
});
}
IGNITION_ADD_PLUGIN(Buoyancy,
ignition::gazebo::System,
Buoyancy::ISystemConfigure,
Buoyancy::ISystemPreUpdate)
IGNITION_ADD_PLUGIN_ALIAS(Buoyancy,
"ignition::gazebo::systems::Buoyancy")