VacuumGripperPlugin.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 #ifdef _WIN32
18  // Ensure that Winsock2.h is included before Windows.h, which can get
19  // pulled in by anybody (e.g., Boost).
20  #include <Winsock2.h>
21 #endif
22 
23 #include <memory>
24 #include <mutex>
25 #include <ostream>
26 #include <vector>
27 #include <string>
28 #include <gazebo/common/Events.hh>
29 #include <gazebo/physics/Collision.hh>
30 #include <gazebo/physics/Contact.hh>
31 #include <gazebo/physics/ContactManager.hh>
32 #include <gazebo/physics/Joint.hh>
33 #include <gazebo/physics/Link.hh>
34 #include <gazebo/physics/Model.hh>
35 #include <gazebo/physics/PhysicsEngine.hh>
36 #include <gazebo/physics/World.hh>
37 #include <gazebo/transport/Node.hh>
38 #include <gazebo/transport/Subscriber.hh>
40 #include "osrf_gear/ARIAC.hh"
41 
42 namespace gazebo
43 {
47  {
49  public: class Object
50  {
54  public: bool operator ==(const Object &_obj) const
55  {
56  return this->type == _obj.type;
57  }
58 
63  public: friend std::ostream &operator<<(std::ostream &_out,
64  const Object &_obj)
65  {
66  _out << _obj.type << std::endl;
67  _out << " Dst: [" << _obj.destination << "]" << std::endl;
68  return _out;
69  }
70 
72  public: std::string type;
73 
75  public: math::Pose destination;
76  };
77 
79  public: std::vector<Object> drops;
80 
82  public: physics::ModelPtr model;
83 
85  public: physics::WorldPtr world;
86 
88  public: physics::JointPtr fixedJoint;
89 
91  public: physics::LinkPtr suctionCupLink;
92 
94  public: event::ConnectionPtr connection;
95 
97  public: std::map<std::string, physics::CollisionPtr> collisions;
98 
100  public: std::vector<msgs::Contact> contacts;
101 
103  public: std::mutex mutex;
104 
106  public: bool attached = false;
107 
109  public: common::Time updateRate;
110 
112  public: common::Time prevUpdateTime;
113 
116  public: int posCount;
117 
120  public: int zeroCount;
121 
123  public: unsigned int minContactCount;
124 
126  public: int attachSteps;
127 
129  public: int detachSteps;
130 
132  public: std::string name;
133 
135  public: transport::NodePtr node;
136 
138  public: transport::SubscriberPtr contactSub;
139 
141  public: bool enabled = false;
142 
144  public: bool dropPending = false;
145 
147  public: physics::ModelPtr dropAttachedModel;
148 
151  public: math::Box dropRegion;
152 
155  };
156 }
157 
158 using namespace gazebo;
159 using namespace physics;
160 
162 
165  : dataPtr(new VacuumGripperPluginPrivate)
166 {
167  gzmsg << "VacuumGripper plugin loaded" << std::endl;
168 
169  this->dataPtr->attached = false;
170  this->dataPtr->updateRate = common::Time(0, common::Time::SecToNano(0.75));
171 }
172 
175 {
176  if (this->dataPtr->world && this->dataPtr->world->GetRunning())
177  {
178  auto mgr = this->dataPtr->world->GetPhysicsEngine()->GetContactManager();
179  mgr->RemoveFilter(this->Name());
180  }
181 }
182 
184 void VacuumGripperPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
185 {
186  this->dataPtr->model = _model;
187  this->dataPtr->world = this->dataPtr->model->GetWorld();
188 
189  this->dataPtr->node = transport::NodePtr(new transport::Node());
190  this->dataPtr->node->Init(this->dataPtr->world->GetName());
191  this->dataPtr->name = _sdf->Get<std::string>("name");
192 
193  // Create the joint that will attach the objects to the suction cup
194  this->dataPtr->fixedJoint =
195  this->dataPtr->world->GetPhysicsEngine()->CreateJoint(
196  "fixed", this->dataPtr->model);
197  this->dataPtr->fixedJoint->SetName(this->dataPtr->model->GetName() +
198  "__vacuum_gripper_fixed_joint__");
199 
200  // Read the SDF parameters
201  sdf::ElementPtr graspCheck = _sdf->GetElement("grasp_check");
202  this->dataPtr->minContactCount =
203  graspCheck->Get<unsigned int>("min_contact_count");
204  this->dataPtr->attachSteps = graspCheck->Get<int>("attach_steps");
205  this->dataPtr->detachSteps = graspCheck->Get<int>("detach_steps");
206  sdf::ElementPtr suctionCupLinkElem = _sdf->GetElement("suction_cup_link");
207  this->dataPtr->suctionCupLink =
208  this->dataPtr->model->GetLink(suctionCupLinkElem->Get<std::string>());
209  if (!this->dataPtr->suctionCupLink)
210  {
211  gzerr << "Suction cup link [" << suctionCupLinkElem->Get<std::string>()
212  << "] not found!\n";
213  return;
214  }
215 
216  if (_sdf->HasElement("drops"))
217  {
218  sdf::ElementPtr dropsElem = _sdf->GetElement("drops");
219 
220  if (!dropsElem->HasElement("drop_region"))
221  {
222  gzerr << "VacuumGripperPlugin: Unable to find <drop_region> elements in "
223  << "the <drops> section\n";
224  return;
225  }
226 
227  sdf::ElementPtr dropRegionElem = dropsElem->GetElement("drop_region");
228 
229  if (!dropRegionElem->HasElement("min"))
230  {
231  gzerr << "VacuumGripperPlugin: Unable to find <min> elements in "
232  << "the <drop_region> section\n";
233  return;
234  }
235 
236  sdf::ElementPtr minElem = dropRegionElem->GetElement("min");
237  gazebo::math::Vector3 min = dropRegionElem->Get<math::Vector3>("min");
238 
239  if (!dropRegionElem->HasElement("max"))
240  {
241  gzerr << "VacuumGripperPlugin: Unable to find <max> elements in "
242  << "the <drop_region> section\n";
243  return;
244  }
245 
246  sdf::ElementPtr maxElem = dropRegionElem->GetElement("max");
247  gazebo::math::Vector3 max = dropRegionElem->Get<math::Vector3>("max");
248 
249  this->dataPtr->dropRegion.min = min;
250  this->dataPtr->dropRegion.max = max;
251 
252  if (!dropsElem->HasElement("object"))
253  {
254  gzerr << "VacuumGripperPlugin: Unable to find <object> elements in the "
255  << "<drops> section\n";
256  }
257  else
258  {
259  sdf::ElementPtr objectElem = dropsElem->GetElement("object");
260  while (objectElem)
261  {
262  // Parse the object type.
263  if (!objectElem->HasElement("type"))
264  {
265  gzerr << "VacuumGripperPlugin: Unable to find <type> in object.\n";
266  objectElem = objectElem->GetNextElement("object");
267  continue;
268  }
269  sdf::ElementPtr typeElement = objectElem->GetElement("type");
270  std::string type = typeElement->Get<std::string>();
271 
272  // Parse the destination.
273  if (!objectElem->HasElement("destination"))
274  {
275  gzerr << "VacuumGripperPlugin: Unable to find <destination> in "
276  << "object\n";
277  objectElem = objectElem->GetNextElement("destination");
278  continue;
279  }
280  sdf::ElementPtr dstElement = objectElem->GetElement("destination");
281  math::Pose destination = dstElement->Get<math::Pose>();
282 
283  // Add the object to the set.
284  VacuumGripperPluginPrivate::Object obj = {type, destination};
285  this->dataPtr->drops.push_back(obj);
286 
287  objectElem = objectElem->GetNextElement("object");
288  }
289  }
290  }
291 
292  // Find out the collision elements of the suction cup
293  for (auto j = 0u; j < this->dataPtr->suctionCupLink->GetChildCount(); ++j)
294  {
295  physics::CollisionPtr collision =
296  this->dataPtr->suctionCupLink->GetCollision(j);
297  std::map<std::string, physics::CollisionPtr>::iterator collIter
298  = this->dataPtr->collisions.find(collision->GetScopedName());
299  if (collIter != this->dataPtr->collisions.end())
300  continue;
301 
302  this->dataPtr->collisions[collision->GetScopedName()] = collision;
303  }
304 
305  if (!this->dataPtr->collisions.empty())
306  {
307  // Create a filter to receive collision information
308  auto mgr = this->dataPtr->world->GetPhysicsEngine()->GetContactManager();
309  auto topic = mgr->CreateFilter(this->Name(), this->dataPtr->collisions);
310  if (!this->dataPtr->contactSub)
311  {
312  this->dataPtr->contactSub = this->dataPtr->node->Subscribe(topic,
314  }
315  }
316 
317  this->Reset();
318 
319  this->dataPtr->connection = event::Events::ConnectWorldUpdateEnd(
320  boost::bind(&VacuumGripperPlugin::OnUpdate, this));
321 }
322 
325 {
326  this->dataPtr->prevUpdateTime = common::Time::GetWallTime();
327  this->dataPtr->zeroCount = 0;
328  this->dataPtr->posCount = 0;
329  this->dataPtr->attached = false;
330  this->dataPtr->enabled = false;
331 }
332 
334 std::string VacuumGripperPlugin::Name() const
335 {
336  return this->dataPtr->name;
337 }
338 
341 {
342  return this->dataPtr->enabled;
343 }
344 
347 {
348  return this->dataPtr->attached;
349 }
350 
353 {
354  std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
355  this->dataPtr->enabled = true;
356 }
357 
360 {
361  {
362  std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
363  this->dataPtr->enabled = false;
364  }
365  this->HandleDetach();
366 }
367 
370 {
371  this->Publish();
372 
373  std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
374  if (common::Time::GetWallTime() -
375  this->dataPtr->prevUpdateTime < this->dataPtr->updateRate ||
376  !this->dataPtr->enabled)
377  {
378  return;
379  }
380 
381  // @todo: should package the decision into a function
382  if (this->dataPtr->contacts.size() >= this->dataPtr->minContactCount)
383  {
384  this->dataPtr->posCount++;
385  this->dataPtr->zeroCount = 0;
386  }
387  else
388  {
389  this->dataPtr->zeroCount++;
390  this->dataPtr->posCount = std::max(0, this->dataPtr->posCount-1);
391  }
392 
393  if (this->dataPtr->posCount > this->dataPtr->attachSteps &&
394  !this->dataPtr->attached)
395  {
396  this->HandleAttach();
397  }
398 
399  if (this->dataPtr->attached && this->dataPtr->dropPending)
400  {
401  auto objPose = this->dataPtr->dropAttachedModel->GetWorldPose();
402  if (this->dataPtr->dropRegion.Contains(objPose.pos))
403  {
404  // Drop the object.
405  this->HandleDetach();
406 
407  // Teleport it to the destination.
408  this->dataPtr->dropAttachedModel->SetWorldPose(
409  this->dataPtr->dropCurrentObject.destination);
410 
411  this->dataPtr->dropPending = false;
412  gzdbg << "Object dropped and teleported" << std::endl;
413  }
414  }
415 
416  // else if (this->dataPtr->zeroCount > this->dataPtr->detachSteps &&
417  // this->dataPtr->attached)
418  // {
419  // this->HandleDetach();
420  // }
421 
422  this->dataPtr->contacts.clear();
423  this->dataPtr->prevUpdateTime = common::Time::GetWallTime();
424 }
425 
427 void VacuumGripperPlugin::OnContacts(ConstContactsPtr &_msg)
428 {
429  std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
430  for (int i = 0; i < _msg->contact_size(); ++i)
431  {
432  CollisionPtr collision1 = boost::dynamic_pointer_cast<Collision>(
433  this->dataPtr->world->GetEntity(_msg->contact(i).collision1()));
434  CollisionPtr collision2 = boost::dynamic_pointer_cast<Collision>(
435  this->dataPtr->world->GetEntity(_msg->contact(i).collision2()));
436 
437  if ((collision1 && !collision1->IsStatic()) &&
438  (collision2 && !collision2->IsStatic()))
439  {
440  this->dataPtr->contacts.push_back(_msg->contact(i));
441  }
442  }
443 }
444 
447 {
448  std::map<std::string, physics::CollisionPtr> cc;
449  std::map<std::string, int> contactCounts;
450  std::map<std::string, int>::iterator iter;
451 
452  // This function is only called from the OnUpdate function so
453  // the call to contacts.clear() is not going to happen in
454  // parallel with the reads in the following code, no mutex needed.
455  for (unsigned int i = 0; i < this->dataPtr->contacts.size(); ++i)
456  {
457  std::string name1 = this->dataPtr->contacts[i].collision1();
458  std::string name2 = this->dataPtr->contacts[i].collision2();
459 
460  if (this->dataPtr->collisions.find(name1) ==
461  this->dataPtr->collisions.end())
462  {
463  cc[name1] = boost::dynamic_pointer_cast<Collision>(
464  this->dataPtr->world->GetEntity(name1));
465  contactCounts[name1] += 1;
466  }
467 
468  if (this->dataPtr->collisions.find(name2) ==
469  this->dataPtr->collisions.end())
470  {
471  cc[name2] = boost::dynamic_pointer_cast<Collision>(
472  this->dataPtr->world->GetEntity(name2));
473  contactCounts[name2] += 1;
474  }
475  }
476 
477  iter = contactCounts.begin();
478  while (iter != contactCounts.end())
479  {
480  if (iter->second < 2)
481  contactCounts.erase(iter++);
482  else
483  {
484  if (!this->dataPtr->attached && cc[iter->first])
485  {
486  this->dataPtr->attached = true;
487 
488  this->dataPtr->fixedJoint->Load(this->dataPtr->suctionCupLink,
489  cc[iter->first]->GetLink(), math::Pose());
490  this->dataPtr->fixedJoint->Init();
491 
492  // Check if the object should drop.
493  auto name = cc[iter->first]->GetLink()->GetModel()->GetName();
495  math::Pose dst;
496  VacuumGripperPluginPrivate::Object attachedObj = {type, dst};
497  auto found = std::find(std::begin(this->dataPtr->drops),
498  std::end(this->dataPtr->drops), attachedObj);
499  if (found != std::end(this->dataPtr->drops))
500  {
501  // Save the object that is scheduled for dropping.
502  this->dataPtr->dropCurrentObject = *found;
503 
504  // Remove obj from drops.
505  this->dataPtr->drops.erase(found);
506 
507  this->dataPtr->dropPending = true;
508  this->dataPtr->dropAttachedModel =
509  cc[iter->first]->GetLink()->GetModel();
510 
511  gzdbg << "Drop scheduled" << std::endl;
512  }
513  }
514  ++iter;
515  }
516  }
517 }
518 
521 {
522  this->dataPtr->attached = false;
523  this->dataPtr->fixedJoint->Detach();
524 }
525 
528 {
529 }
common::Time prevUpdateTime
Previous time when the gripper was updated.
transport::SubscriberPtr contactSub
Subscription to contact messages from the physics engine.
unsigned int minContactCount
Minimum number of links touching.
void OnUpdate()
Update the gripper.
physics::JointPtr fixedJoint
A fixed joint to connect the gripper to an object.
event::ConnectionPtr connection
Connection event.
friend std::ostream & operator<<(std::ostream &_out, const Object &_obj)
Stream insertion operator.
math::Box dropRegion
If the attached object is scheduled to be dropped, the drop will occur when the object enters inside ...
physics::LinkPtr suctionCupLink
The suction cup link.
int posCount
Number of iterations the gripper was contacting the same object.
virtual void Publish() const
Overwrite this method for sending periodic updates with the gripper state.
physics::WorldPtr world
Pointer to the world.
bool Attached() const
True if the gripper is attached to another model.
void Disable()
Disable the suction.
common::Time updateRate
Rate at which to update the gripper.
std::vector< Object > drops
Collection of objects to be dropped.
int zeroCount
Number of iterations the gripper was not contacting the same object.
std::mutex mutex
Mutex used to protect reading/writing the sonar message.
bool dropPending
Whether there&#39;s an ongoing drop.
void Enable()
Enable the suction.
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
void HandleDetach()
Detach an object from the gripper.
int attachSteps
Steps touching before engaging fixed joint.
physics::ModelPtr model
Model that contains this gripper.
virtual ~VacuumGripperPlugin()
Destructor.
bool enabled
Whether the suction is enabled or not.
void OnContacts(ConstContactsPtr &_msg)
Callback used when the gripper contacts an object.
void HandleAttach()
Attach an object to the gripper.
bool operator==(const Object &_obj) const
Equality operator, result = this == _obj.
bool attached
True if the gripper has an object.
std::map< std::string, physics::CollisionPtr > collisions
The collisions for the links in the gripper.
physics::ModelPtr dropAttachedModel
Attached model to be dropped.
int min(int a, int b)
math::Pose destination
Destination where the object is teleported after a drop.
transport::NodePtr node
Node for communication.
TrayID_t DetermineModelType(const std::string &modelName)
Determine the type of a gazebo model from its name.
Definition: ARIAC.hh:222
std::string name
Name of the gripper.
bool Enabled() const
Whether the suction of the gripper has been enabled.
virtual void Reset()
Documentation inherited.
Class to store information about each object to be dropped.
GZ_REGISTER_MODEL_PLUGIN(GazeboRosP3D)
std::vector< msgs::Contact > contacts
The current contacts.
std::string Name() const
Return the name of the gripper.
Object dropCurrentObject
The current object scheduled for dropping.
int detachSteps
Steps not touching before disengaging fixed joint.


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