PopulationPlugin.cc
Go to the documentation of this file.
1 /*
2  * Copyright (C) 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 <algorithm>
19 #include <mutex>
20 #include <ostream>
21 #include <string>
22 #include <vector>
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>
33 #include <sdf/sdf.hh>
34 
36 
37 namespace gazebo
38 {
42  {
44  public: physics::WorldPtr world;
45 
47  public: sdf::ElementPtr sdf;
48 
50  public: class Object
51  {
55  public: bool operator<(const Object &_obj) const
56  {
57  return this->time < _obj.time;
58  }
59 
64  public: friend std::ostream &operator<<(std::ostream &_out,
65  const Object &_obj)
66  {
67  _out << _obj.type << std::endl;
68  _out << " Time: [" << _obj.time << "]" << std::endl;
69  _out << " Pose: [" << _obj.pose << "]" << std::endl;
70  return _out;
71  }
72 
74  public: double time;
75 
77  public: std::string type;
78 
80  public: math::Pose pose;
81  };
82 
84  public: std::vector<Object> objects;
85 
88  public: std::vector<Object> initialObjects;
89 
91  public: event::ConnectionPtr connection;
92 
94  public: common::Time startTime;
95 
98  public: bool loopForever = false;
99 
101  public: physics::EntityPtr frame;
102 
104  public: transport::NodePtr node;
105 
107  public: transport::SubscriberPtr activationSub;
108 
110  public: bool enabled = false;
111 
113  public: std::mutex mutex;
114 
116  public: common::Time elapsedWhenPaused;
117  };
118 }
119 
120 using namespace gazebo;
121 
123 
126  : dataPtr(new PopulationPluginPrivate)
127 {
128 }
129 
132 {
133 }
134 
136 void PopulationPlugin::Load(physics::WorldPtr _world, sdf::ElementPtr _sdf)
137 {
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;
142 
143  // Read the SDF parameters
144  if (_sdf->HasElement("loop_forever"))
145  {
146  sdf::ElementPtr loopElem = _sdf->GetElement("loop_forever");
147  this->dataPtr->loopForever = loopElem->Get<bool>();
148  }
149 
150  if (_sdf->HasElement("frame"))
151  {
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");
156  }
157  if (!this->dataPtr->frame->HasType(physics::Base::LINK) &&
158  !this->dataPtr->frame->HasType(physics::Base::MODEL))
159  {
160  gzthrow("'frame' tag must list the name of a link or model");
161  }
162  }
163 
164  if (!_sdf->HasElement("object_sequence"))
165  {
166  gzerr << "PopulationPlugin: Unable to find <object_sequence> element\n";
167  return;
168  }
169 
170  sdf::ElementPtr sequence = _sdf->GetElement("object_sequence");
171 
172  sdf::ElementPtr objectElem = NULL;
173  if (sequence->HasElement("object"))
174  {
175  objectElem = sequence->GetElement("object");
176  }
177 
178  while (objectElem)
179  {
180  // Parse the time.
181  if (!objectElem->HasElement("time"))
182  {
183  gzerr << "PopulationPlugin: Unable to find <time> in object\n";
184  objectElem = objectElem->GetNextElement("object");
185  continue;
186  }
187  sdf::ElementPtr timeElement = objectElem->GetElement("time");
188  double time = timeElement->Get<double>();
189 
190  // Parse the object type.
191  if (!objectElem->HasElement("type"))
192  {
193  gzerr << "PopulationPlugin: Unable to find <type> in object.\n";
194  objectElem = objectElem->GetNextElement("object");
195  continue;
196  }
197  sdf::ElementPtr typeElement = objectElem->GetElement("type");
198  std::string type = typeElement->Get<std::string>();
199 
200  // Parse the object pose (optional).
201  math::Pose pose;
202  if (objectElem->HasElement("pose"))
203  {
204  sdf::ElementPtr poseElement = objectElem->GetElement("pose");
205  pose = poseElement->Get<math::Pose>();
206  }
207 
208  // Add the object to the collection.
210  this->dataPtr->initialObjects.push_back(obj);
211 
212  objectElem = objectElem->GetNextElement("object");
213  }
214  std::sort(this->dataPtr->initialObjects.begin(),
215  this->dataPtr->initialObjects.end());
216 
217  // Listen on the activation topic, if present. This topic is used for
218  // manual activation.
219  if (_sdf->HasElement("activation_topic"))
220  {
221  // Create and initialize the node.
222  this->dataPtr->node = transport::NodePtr(new transport::Node());
223  this->dataPtr->node->Init();
224 
225  // Subscribe to the activation topic.
226  this->dataPtr->activationSub = this->dataPtr->node->Subscribe(
227  _sdf->Get<std::string>("activation_topic"),
229  }
230  else
231  this->Restart();
232 
233  this->dataPtr->connection = event::Events::ConnectWorldUpdateEnd(
234  boost::bind(&PopulationPlugin::OnUpdate, this));
235 }
236 
239 {
240  if (!this->dataPtr->enabled)
241  return;
242 
243  this->dataPtr->enabled = false;
244  this->dataPtr->elapsedWhenPaused =
245  this->dataPtr->world->GetSimTime() - this->dataPtr->startTime;
246 
247  gzmsg << "Object population paused" << std::endl;
248 }
249 
252 {
253  if (this->dataPtr->enabled)
254  return;
255 
256  this->dataPtr->enabled = true;
257  this->dataPtr->startTime = this->dataPtr->world->GetSimTime() -
258  this->dataPtr->elapsedWhenPaused;
259 
260  gzmsg << "Object population resumed" << std::endl;
261 }
262 
265 {
266  this->dataPtr->enabled = true;
267  this->dataPtr->startTime = this->dataPtr->world->GetSimTime();
268  this->dataPtr->objects = this->dataPtr->initialObjects;
269 
270  gzmsg << "Object population restarted" << std::endl;
271 }
272 
275 {
276  std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
277 
278  this->Publish();
279 
280  if (!this->dataPtr->enabled)
281  return;
282 
283  if (this->dataPtr->objects.empty())
284  {
285  if (this->dataPtr->loopForever)
286  this->Restart();
287  else
288  return;
289  }
290 
291  // Check whether spawn a new object from the list.
292  auto elapsed = this->dataPtr->world->GetSimTime() - this->dataPtr->startTime;
293  if (elapsed.Double() >= this->dataPtr->objects.front().time)
294  {
295  auto obj = this->dataPtr->objects.front();
296  if (this->dataPtr->frame)
297  {
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();
302  }
303  std::string modelName = this->GetHandle() + "|" + obj.type;
304 
305  std::ostringstream newModelStr;
306  newModelStr <<
307  "<sdf version='" << SDF_VERSION << "'>\n"
308  " <include>\n"
309  " <pose>" << obj.pose << "</pose>\n"
310  " <name>" << modelName << "</name>\n"
311  " <uri>model://" << obj.type << "</uri>\n"
312  " </include>\n"
313  "</sdf>\n";
314 
315  gzdbg << "Object spawned: " << modelName << std::endl;
316  this->dataPtr->world->InsertModelString(newModelStr.str());
317  this->dataPtr->objects.erase(this->dataPtr->objects.begin());
318  }
319 }
320 
322 void PopulationPlugin::OnActivation(ConstGzStringPtr &_msg)
323 {
324  std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
325 
326  if (_msg->data() == "restart")
327  this->Restart();
328  else if (_msg->data() == "pause")
329  this->Pause();
330  else if (_msg->data() == "resume")
331  this->Resume();
332  else
333  gzerr << "Unknown activation command [" << _msg->data() << "]" << std::endl;
334 }
335 
338 {
339  return this->dataPtr->enabled;
340 }
341 
344 {
345 }
std::vector< Object > objects
Collection of objects to be spawned.
bool Enabled() const
True when the plugin is enabled or false if it&#39;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&#39;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...
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.


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