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>    63               public: 
friend std::ostream &
operator<<(std::ostream &_out,
    66                 _out << _obj.
type << std::endl;
    67                 _out << 
"  Dst: [" << _obj.
destination << 
"]" << std::endl;
    79     public: std::vector<Object> 
drops;
    82     public: physics::ModelPtr 
model;
    85     public: physics::WorldPtr 
world;
    97     public: std::map<std::string, physics::CollisionPtr> 
collisions;
   135     public: transport::NodePtr 
node;
   167   gzmsg << 
"VacuumGripper plugin loaded" << std::endl;
   169   this->dataPtr->attached = 
false;
   170   this->dataPtr->updateRate = common::Time(0, common::Time::SecToNano(0.75));
   176   if (this->dataPtr->world && this->dataPtr->world->GetRunning())
   178     auto mgr = this->dataPtr->world->GetPhysicsEngine()->GetContactManager();
   179     mgr->RemoveFilter(this->Name());
   186   this->dataPtr->model = _model;
   187   this->dataPtr->world = this->dataPtr->model->GetWorld();
   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");
   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__");
   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)
   211     gzerr << 
"Suction cup link [" << suctionCupLinkElem->Get<std::string>()
   216   if (_sdf->HasElement(
"drops"))
   218     sdf::ElementPtr dropsElem = _sdf->GetElement(
"drops");
   220     if (!dropsElem->HasElement(
"drop_region"))
   222       gzerr << 
"VacuumGripperPlugin: Unable to find <drop_region> elements in "   223             << 
"the <drops> section\n";
   227     sdf::ElementPtr dropRegionElem = dropsElem->GetElement(
"drop_region");
   229     if (!dropRegionElem->HasElement(
"min"))
   231       gzerr << 
"VacuumGripperPlugin: Unable to find <min> elements in "   232             << 
"the <drop_region> section\n";
   236     sdf::ElementPtr minElem = dropRegionElem->GetElement(
"min");
   237     gazebo::math::Vector3 
min = dropRegionElem->Get<math::Vector3>(
"min");
   239     if (!dropRegionElem->HasElement(
"max"))
   241       gzerr << 
"VacuumGripperPlugin: Unable to find <max> elements in "   242             << 
"the <drop_region> section\n";
   246     sdf::ElementPtr maxElem = dropRegionElem->GetElement(
"max");
   247     gazebo::math::Vector3 max = dropRegionElem->Get<math::Vector3>(
"max");
   249     this->dataPtr->dropRegion.min = min;
   250     this->dataPtr->dropRegion.max = max;
   252     if (!dropsElem->HasElement(
"object"))
   254       gzerr << 
"VacuumGripperPlugin: Unable to find <object> elements in the "   255             << 
"<drops> section\n";
   259       sdf::ElementPtr objectElem = dropsElem->GetElement(
"object");
   263         if (!objectElem->HasElement(
"type"))
   265           gzerr << 
"VacuumGripperPlugin: Unable to find <type> in object.\n";
   266           objectElem = objectElem->GetNextElement(
"object");
   269         sdf::ElementPtr typeElement = objectElem->GetElement(
"type");
   270         std::string 
type = typeElement->Get<std::string>();
   273         if (!objectElem->HasElement(
"destination"))
   275           gzerr << 
"VacuumGripperPlugin: Unable to find <destination> in "   277           objectElem = objectElem->GetNextElement(
"destination");
   280         sdf::ElementPtr dstElement = objectElem->GetElement(
"destination");
   281         math::Pose 
destination = dstElement->Get<math::Pose>();
   285         this->dataPtr->drops.push_back(obj);
   287         objectElem = objectElem->GetNextElement(
"object");
   293   for (
auto j = 0u; j < this->dataPtr->suctionCupLink->GetChildCount(); ++j)
   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())
   302     this->dataPtr->collisions[collision->GetScopedName()] = collision;
   305   if (!this->dataPtr->collisions.empty())
   308     auto mgr = this->dataPtr->world->GetPhysicsEngine()->GetContactManager();
   309     auto topic = mgr->CreateFilter(this->Name(), this->dataPtr->collisions);
   310     if (!this->dataPtr->contactSub)
   312       this->dataPtr->contactSub = this->dataPtr->node->Subscribe(topic,
   319   this->dataPtr->connection = event::Events::ConnectWorldUpdateEnd(
   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;
   336   return this->dataPtr->name;
   342   return this->dataPtr->enabled;
   348   return this->dataPtr->attached;
   354   std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
   355   this->dataPtr->enabled = 
true;
   362     std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
   363     this->dataPtr->enabled = 
false;
   365   this->HandleDetach();
   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)
   382   if (this->dataPtr->contacts.size() >= this->dataPtr->minContactCount)
   384     this->dataPtr->posCount++;
   385     this->dataPtr->zeroCount = 0;
   389     this->dataPtr->zeroCount++;
   390     this->dataPtr->posCount = std::max(0, this->dataPtr->posCount-1);
   393   if (this->dataPtr->posCount > this->dataPtr->attachSteps &&
   394       !this->dataPtr->attached)
   396     this->HandleAttach();
   399   if (this->dataPtr->attached && this->dataPtr->dropPending)
   401     auto objPose = this->dataPtr->dropAttachedModel->GetWorldPose();
   402     if (this->dataPtr->dropRegion.Contains(objPose.pos))
   405       this->HandleDetach();
   408       this->dataPtr->dropAttachedModel->SetWorldPose(
   409         this->dataPtr->dropCurrentObject.destination);
   411       this->dataPtr->dropPending = 
false;
   412       gzdbg << 
"Object dropped and teleported" << std::endl;
   422   this->dataPtr->contacts.clear();
   423   this->dataPtr->prevUpdateTime = common::Time::GetWallTime();
   429   std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
   430   for (
int i = 0; i < _msg->contact_size(); ++i)
   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()));
   437     if ((collision1 && !collision1->IsStatic()) &&
   438         (collision2 && !collision2->IsStatic()))
   440       this->dataPtr->contacts.push_back(_msg->contact(i));
   448   std::map<std::string, physics::CollisionPtr> cc;
   449   std::map<std::string, int> contactCounts;
   450   std::map<std::string, int>::iterator iter;
   455   for (
unsigned int i = 0; i < this->dataPtr->contacts.size(); ++i)
   457     std::string name1 = this->dataPtr->contacts[i].collision1();
   458     std::string name2 = this->dataPtr->contacts[i].collision2();
   460     if (this->dataPtr->collisions.find(name1) ==
   461         this->dataPtr->collisions.end())
   463       cc[name1] = boost::dynamic_pointer_cast<Collision>(
   464           this->dataPtr->world->GetEntity(name1));
   465       contactCounts[name1] += 1;
   468     if (this->dataPtr->collisions.find(name2) ==
   469         this->dataPtr->collisions.end())
   471       cc[name2] = boost::dynamic_pointer_cast<Collision>(
   472           this->dataPtr->world->GetEntity(name2));
   473       contactCounts[name2] += 1;
   477   iter = contactCounts.begin();
   478   while (iter != contactCounts.end())
   480     if (iter->second < 2)
   481       contactCounts.erase(iter++);
   484       if (!this->dataPtr->attached && cc[iter->first])
   486         this->dataPtr->attached = 
true;
   488         this->dataPtr->fixedJoint->Load(this->dataPtr->suctionCupLink,
   489             cc[iter->first]->GetLink(), math::Pose());
   490         this->dataPtr->fixedJoint->Init();
   493         auto name = cc[iter->first]->GetLink()->GetModel()->GetName();
   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))
   502           this->dataPtr->dropCurrentObject = *found;
   505           this->dataPtr->drops.erase(found);
   507           this->dataPtr->dropPending = 
true;
   508           this->dataPtr->dropAttachedModel =
   509             cc[iter->first]->GetLink()->GetModel();
   511           gzdbg << 
"Drop scheduled" << std::endl;
   522   this->dataPtr->attached = 
false;
   523   this->dataPtr->fixedJoint->Detach();
 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. 
std::string type
Object type. 
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'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. 
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. 
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.