From 585e57b5453d56d8484632808593655630409c86 Mon Sep 17 00:00:00 2001 From: Daniel Christoph <daniel.christoph@informatik.hu-berlin.de> Date: Sun, 26 Jan 2020 15:03:55 +0100 Subject: [PATCH] Update src/sim/plugins/model_push.cc --- src/sim/plugins/model_push.cc | 38 +++++++++++++++++++++++++++++++++++ 1 file changed, 38 insertions(+) create mode 100644 src/sim/plugins/model_push.cc diff --git a/src/sim/plugins/model_push.cc b/src/sim/plugins/model_push.cc new file mode 100644 index 0000000..ca36660 --- /dev/null +++ b/src/sim/plugins/model_push.cc @@ -0,0 +1,38 @@ +#include <functional> +#include <gazebo/gazebo.hh> +#include <gazebo/physics/physics.hh> +#include <gazebo/common/common.hh> +#include <ignition/math/Vector3.hh> + +namespace gazebo +{ + class ModelPush : public ModelPlugin + { + public: void Load(physics::ModelPtr _parent, sdf::ElementPtr /*_sdf*/) + { + // Store the pointer to the model + this->model = _parent; + + // Listen to the update event. This event is broadcast every + // simulation iteration. + this->updateConnection = event::Events::ConnectWorldUpdateBegin( + std::bind(&ModelPush::OnUpdate, this)); + } + + // Called by the world update start event + public: void OnUpdate() + { + // Apply a small linear velocity to the model. + this->model->SetLinearVel(ignition::math::Vector3d(0.3, 0, 0)); + } + + // Pointer to the model + private: physics::ModelPtr model; + + // Pointer to the update event connection + private: event::ConnectionPtr updateConnection; + }; + + // Register this plugin with the simulator + GZ_REGISTER_MODEL_PLUGIN(ModelPush) +} -- GitLab