ObjectDisposalPlugin.cc
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2016 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #include <limits>
19 #include <string>
20 
21 #include "ObjectDisposalPlugin.hh"
22 #include <gazebo/transport/Node.hh>
23 
24 using namespace gazebo;
26 
29 {
30 }
31 
34 {
35  event::Events::DisconnectWorldUpdateBegin(this->updateConnection);
36  this->parentSensor.reset();
37  this->world.reset();
38 }
39 
41 void ObjectDisposalPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
42 {
43  SideContactPlugin::Load(_model, _sdf);
44  this->centerOfGravityCheck = false;
45  if (_sdf->HasElement("center_of_gravity_check"))
46  {
47  this->centerOfGravityCheck = _sdf->Get<bool>("center_of_gravity_check");
48  }
49 }
50 
52 void ObjectDisposalPlugin::OnUpdate(const common::UpdateInfo &/*_info*/)
53 {
55  this->ActOnContactingModels();
56 }
57 
60 {
61  // Only remove models if their center of gravity is "above" the link
62  // TODO: make more general than just z axis
63  auto linkBox = this->parentLink->GetBoundingBox();
64  auto linkBoxMax = linkBox.max;
65  auto linkBoxMin = linkBox.min;
66  linkBoxMin.z = std::numeric_limits<double>::lowest();
67  linkBoxMax.z = std::numeric_limits<double>::max();
68  auto disposalBox = math::Box(linkBoxMin, linkBoxMax);
69 
70  for (auto model : this->contactingModels) {
71  if (model) {
72  bool removeModel = true;
73  if (this->centerOfGravityCheck)
74  {
75  // Calculate the center of gravity of the model
76  math::Vector3 modelCog = math::Vector3::Zero;
77  double modelMass = 0.0;
78  for (auto modelLink : model->GetLinks())
79  {
80  double linkMass = modelLink->GetInertial()->GetMass();
81  modelCog += modelLink->GetWorldCoGPose().pos * linkMass;
82  modelMass += linkMass;
83  }
84  if (modelMass > 0.0)
85  {
86  modelCog /= modelMass;
87  }
88  removeModel = disposalBox.Contains(modelCog);
89  }
90  if (removeModel)
91  {
92  gzdbg << "[" << this->model->GetName() << "] Removing model: " << model->GetName() << "\n";
93  this->world->RemoveModel(model);
94  }
95  }
96  }
97 }
physics::WorldPtr world
Pointer to the world.
void OnUpdate(const common::UpdateInfo &_info)
Callback that receives the world update event.
void ActOnContactingModels()
Act on models that are ontop of the sensor&#39;s link.
virtual void CalculateContactingModels()
Determine which models are in contact with the side of the parent link.
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Load the sensor plugin.
std::set< physics::ModelPtr > contactingModels
Set of pointers to models that have collisions with the parent link&#39;s side.
A plugin for a contact sensor attached to a model disposal unit.
A plugin for a model with a contact sensor that only monitors collisions on one of its sides...
sensors::ContactSensorPtr parentSensor
Pointer to the contact sensor.
virtual ~ObjectDisposalPlugin()
Destructor.
event::ConnectionPtr updateConnection
Pointer to the update event connection.
physics::LinkPtr parentLink
Pointer to the sensor&#39;s parent&#39;s link.
physics::ModelPtr model
Pointer to the model.
bool centerOfGravityCheck
If true, only delete models if their CoG is within the bounding box of the link.
GZ_REGISTER_MODEL_PLUGIN(GazeboRosP3D)
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Load the model plugin.


osrf_gear
Author(s):
autogenerated on Wed Sep 7 2016 03:48:12