18 #include <ignition/math/Vector3.hh> 20 #include <gazebo/physics/Actor.hh> 21 #include <gazebo/physics/BoxShape.hh> 22 #include <gazebo/physics/Collision.hh> 23 #include <gazebo/physics/Link.hh> 39 auto actor = boost::dynamic_pointer_cast<physics::Actor>(_model);
42 std::map<std::string, ignition::math::Vector3d> scaling;
43 std::map<std::string, ignition::math::Pose3d> offsets;
46 if (_sdf->HasElement(
"scaling"))
48 auto elem = _sdf->GetElement(
"scaling");
51 if (!elem->HasAttribute(
"collision"))
53 gzwarn <<
"Skipping element without collision attribute" << std::endl;
54 elem = elem->GetNextElement(
"scaling");
57 auto name = elem->Get<std::string>(
"collision");
59 if (elem->HasAttribute(
"scale"))
61 auto scale = elem->Get<ignition::math::Vector3d>(
"scale");
62 scaling[name] = scale;
65 if (elem->HasAttribute(
"pose"))
67 auto pose = elem->Get<ignition::math::Pose3d>(
"pose");
70 elem = elem->GetNextElement(
"scaling");
74 for (
const auto &link : actor->GetLinks())
83 for (
const auto &collision : link->GetCollisions())
85 auto name = collision->GetName();
87 if (scaling.find(name) != scaling.end())
89 auto boxShape = boost::dynamic_pointer_cast<gazebo::physics::BoxShape>(
90 collision->GetShape());
94 boxShape->SetSize(boxShape->Size() * scaling[name]);
97 if (offsets.find(name) != offsets.end())
99 collision->SetInitialRelativePose(
100 offsets[name] + collision->InitialRelativePose());
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.
ActorCollisionsPlugin()
Constructor.
GZ_REGISTER_MODEL_PLUGIN(GazeboRosP3D)