ActorCollisionsPlugin.cc
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018 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 //#include <ros/ros.h>
18 #include <ignition/math/Vector3.hh>
19 
20 #include <gazebo/physics/Actor.hh>
21 #include <gazebo/physics/BoxShape.hh>
22 #include <gazebo/physics/Collision.hh>
23 #include <gazebo/physics/Link.hh>
24 #include "ActorCollisionsPlugin.hh"
25 
26 using namespace gazebo;
28 
29 
32 {
33 }
34 
36 void ActorCollisionsPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
37 {
38  // Get a pointer to the actor
39  auto actor = boost::dynamic_pointer_cast<physics::Actor>(_model);
40 
41  // Map of collision scaling factors
42  std::map<std::string, ignition::math::Vector3d> scaling;
43  std::map<std::string, ignition::math::Pose3d> offsets;
44 
45  // Read in the collision scaling factors, if present
46  if (_sdf->HasElement("scaling"))
47  {
48  auto elem = _sdf->GetElement("scaling");
49  while (elem)
50  {
51  if (!elem->HasAttribute("collision"))
52  {
53  gzwarn << "Skipping element without collision attribute" << std::endl;
54  elem = elem->GetNextElement("scaling");
55  continue;
56  }
57  auto name = elem->Get<std::string>("collision");
58 
59  if (elem->HasAttribute("scale"))
60  {
61  auto scale = elem->Get<ignition::math::Vector3d>("scale");
62  scaling[name] = scale;
63  }
64 
65  if (elem->HasAttribute("pose"))
66  {
67  auto pose = elem->Get<ignition::math::Pose3d>("pose");
68  offsets[name] = pose;
69  }
70  elem = elem->GetNextElement("scaling");
71  }
72  }
73 
74  for (const auto &link : actor->GetLinks())
75  {
76  // Init the links, which in turn enables collisions
77  link->Init();
78 
79  if (scaling.empty())
80  continue;
81 
82  // Process all the collisions in all the links
83  for (const auto &collision : link->GetCollisions())
84  {
85  auto name = collision->GetName();
86 
87  if (scaling.find(name) != scaling.end())
88  {
89  auto boxShape = boost::dynamic_pointer_cast<gazebo::physics::BoxShape>(
90  collision->GetShape());
91 
92  // Make sure we have a box shape.
93  if (boxShape)
94  boxShape->SetSize(boxShape->Size() * scaling[name]);
95  }
96 
97  if (offsets.find(name) != offsets.end())
98  {
99  collision->SetInitialRelativePose(
100  offsets[name] + collision->InitialRelativePose());
101  }
102  }
103  }
104 }
105 
This plugin enables collisions on an Actor, and optionally applies a scaling factor and pose offset t...
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Load the actor plugin.
GZ_REGISTER_MODEL_PLUGIN(GazeboRosP3D)


volta_simulation
Author(s): Nikhil Venkatesh , Mahendra L Seervi
autogenerated on Tue Mar 1 2022 00:03:47