23 #include <gazebo/common/Assert.hh>    24 #include <gazebo/common/Console.hh>    25 #include <gazebo/common/Events.hh>    26 #include <gazebo/math/Pose.hh>    27 #include <gazebo/msgs/gz_string.pb.h>    28 #include <gazebo/physics/Link.hh>    29 #include <gazebo/physics/PhysicsTypes.hh>    30 #include <gazebo/physics/World.hh>    31 #include <gazebo/transport/transport.hh>    32 #include <ignition/math/Matrix4.hh>    44     public: physics::WorldPtr 
world;
    47     public: sdf::ElementPtr 
sdf;
    64              public: 
friend std::ostream &
operator<<(std::ostream &_out,
    67                _out << _obj.
type << std::endl;
    68                _out << 
"  Time: [" << _obj.
time << 
"]" << std::endl;
    69                _out << 
"  Pose: [" << _obj.
pose << 
"]" << std::endl;
   104     public: transport::NodePtr 
node;
   138   GZ_ASSERT(_world, 
"PopulationPlugin world pointer is NULL");
   139   GZ_ASSERT(_sdf, 
"PopulationPlugin sdf pointer is NULL");
   140   this->dataPtr->world = _world;
   141   this->dataPtr->sdf = _sdf;
   144   if (_sdf->HasElement(
"loop_forever"))
   146     sdf::ElementPtr loopElem = _sdf->GetElement(
"loop_forever");
   147     this->dataPtr->loopForever = loopElem->Get<
bool>();
   150   if (_sdf->HasElement(
"frame"))
   152     std::string frameName = _sdf->Get<std::string>(
"frame");
   153     this->dataPtr->frame = this->dataPtr->world->GetEntity(frameName);
   154     if (!this->dataPtr->frame) {
   155       gzthrow(std::string(
"The frame '") + frameName + 
"' does not exist");
   157     if (!this->dataPtr->frame->HasType(physics::Base::LINK) &&
   158       !this->dataPtr->frame->HasType(physics::Base::MODEL))
   160       gzthrow(
"'frame' tag must list the name of a link or model");
   164   if (!_sdf->HasElement(
"object_sequence"))
   166     gzerr << 
"PopulationPlugin: Unable to find <object_sequence> element\n";
   170   sdf::ElementPtr sequence = _sdf->GetElement(
"object_sequence");
   172   sdf::ElementPtr objectElem = NULL;
   173   if (sequence->HasElement(
"object"))
   175     objectElem = sequence->GetElement(
"object");
   181     if (!objectElem->HasElement(
"time"))
   183       gzerr << 
"PopulationPlugin: Unable to find <time> in object\n";
   184       objectElem = objectElem->GetNextElement(
"object");
   187     sdf::ElementPtr timeElement = objectElem->GetElement(
"time");
   188     double time = timeElement->Get<
double>();
   191     if (!objectElem->HasElement(
"type"))
   193       gzerr << 
"PopulationPlugin: Unable to find <type> in object.\n";
   194       objectElem = objectElem->GetNextElement(
"object");
   197     sdf::ElementPtr typeElement = objectElem->GetElement(
"type");
   198     std::string 
type = typeElement->Get<std::string>();
   202     if (objectElem->HasElement(
"pose"))
   204       sdf::ElementPtr poseElement = objectElem->GetElement(
"pose");
   205       pose = poseElement->Get<math::Pose>();
   210     this->dataPtr->initialObjects.push_back(obj);
   212     objectElem = objectElem->GetNextElement(
"object");
   214   std::sort(this->dataPtr->initialObjects.begin(),
   215     this->dataPtr->initialObjects.end());
   219   if (_sdf->HasElement(
"activation_topic"))
   222     this->dataPtr->node = transport::NodePtr(
new transport::Node());
   223     this->dataPtr->node->Init();
   226     this->dataPtr->activationSub = this->dataPtr->node->Subscribe(
   227         _sdf->Get<std::string>(
"activation_topic"),
   233   this->dataPtr->connection = event::Events::ConnectWorldUpdateEnd(
   240   if (!this->dataPtr->enabled)
   243   this->dataPtr->enabled = 
false;
   244   this->dataPtr->elapsedWhenPaused =
   245     this->dataPtr->world->GetSimTime() - this->dataPtr->startTime;
   247   gzmsg << 
"Object population paused" << std::endl;
   253   if (this->dataPtr->enabled)
   256   this->dataPtr->enabled = 
true;
   257   this->dataPtr->startTime = this->dataPtr->world->GetSimTime() -
   258     this->dataPtr->elapsedWhenPaused;
   260    gzmsg << 
"Object population resumed" << std::endl;
   266   this->dataPtr->enabled = 
true;
   267   this->dataPtr->startTime = this->dataPtr->world->GetSimTime();
   268   this->dataPtr->objects = this->dataPtr->initialObjects;
   270    gzmsg << 
"Object population restarted" << std::endl;
   276   std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
   280   if (!this->dataPtr->enabled)
   283   if (this->dataPtr->objects.empty())
   285     if (this->dataPtr->loopForever)
   292   auto elapsed = this->dataPtr->world->GetSimTime() - this->dataPtr->startTime;
   293   if (elapsed.Double() >= this->dataPtr->objects.front().time)
   295     auto obj = this->dataPtr->objects.front();
   296     if (this->dataPtr->frame)
   298       auto framePose = this->dataPtr->frame->GetWorldPose().Ign();
   299       ignition::math::Matrix4d transMat(framePose);
   300       ignition::math::Matrix4d pose_local(obj.pose.Ign());
   301       obj.pose = (transMat * pose_local).
Pose();
   303     std::string modelName = this->GetHandle() + 
"|" + obj.type;
   305     std::ostringstream newModelStr;
   307       "<sdf version='" << SDF_VERSION << 
"'>\n"   309       "    <pose>" << obj.pose << 
"</pose>\n"   310       "    <name>" << modelName << 
"</name>\n"   311       "    <uri>model://" << obj.type << 
"</uri>\n"   315     gzdbg << 
"Object spawned: " << modelName << std::endl;
   316     this->dataPtr->world->InsertModelString(newModelStr.str());
   317     this->dataPtr->objects.erase(this->dataPtr->objects.begin());
   324   std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
   326   if (_msg->data() == 
"restart")
   328   else if (_msg->data() == 
"pause")
   330   else if (_msg->data() == 
"resume")
   333     gzerr << 
"Unknown activation command [" << _msg->data() << 
"]" << std::endl;
   339   return this->dataPtr->enabled;
 std::vector< Object > objects
Collection of objects to be spawned. 
bool Enabled() const 
True when the plugin is enabled or false if it's paused. 
physics::WorldPtr world
World pointer. 
common::Time elapsedWhenPaused
Elapsed time since "startTime" when the plugin is paused. 
GZ_REGISTER_WORLD_PLUGIN(ROSPopulationPlugin)
void Pause()
Pause the object population. 
bool operator<(const Object &_obj) const 
Less than operator. 
void Resume()
Resume the object population after a pause. 
common::Time startTime
The time specified in the object is relative to this time. 
void OnActivation(ConstGzStringPtr &_msg)
Callback that receives activation messages. If the <activation_topic> is set in SDF, the plugin won't populate any object until the activation is received. 
bool enabled
If true, the objects will start populating. 
sdf::ElementPtr sdf
SDF pointer. 
virtual ~PopulationPlugin()
Destructor. 
friend std::ostream & operator<<(std::ostream &_out, const Object &_obj)
Stream insertion operator. 
std::vector< Object > initialObjects
Contains the entire collection of objects. This is used for inserting the objects in a cyclic way...
std::string type
Object type. 
double time
Simulation time in which the object should be spawned. 
virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf)
Class to store information about each object to be populated. 
transport::SubscriberPtr activationSub
Subscriber to the activation topic. 
transport::NodePtr node
Node for communication. 
A plugin that allows models to be spawned at a given location in a specific simulation time...
std::mutex mutex
Mutex to avoid race conditions. 
bool loopForever
When true, "objects" will be repopulated when the object queue is empty, creating an infinite supply ...
physics::EntityPtr frame
Link/model that the object poses use as their frame of reference. 
math::Pose pose
Pose in which the object should be placed. 
event::ConnectionPtr connection
Connection event. 
virtual void Publish() const 
Overwrite this method for sending periodic updates with the plugin state. 
void OnUpdate()
Update the plugin. 
virtual void Restart()
Restart the the object population.