SideContactPlugin.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2012-2016 Open Source Robotics Foundation
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 
00018 #include <boost/algorithm/string/replace.hpp>
00019 #include <string>
00020 
00021 #include "SideContactPlugin.hh"
00022 #include <ignition/math/Vector3.hh>
00023 
00024 using namespace gazebo;
00025 GZ_REGISTER_MODEL_PLUGIN(SideContactPlugin)
00026 
00027 
00028 SideContactPlugin::SideContactPlugin() : ModelPlugin()
00029 {
00030 }
00031 
00033 SideContactPlugin::~SideContactPlugin()
00034 {
00035   event::Events::DisconnectWorldUpdateBegin(this->updateConnection);
00036   this->parentSensor.reset();
00037   this->world.reset();
00038 }
00039 
00041 void SideContactPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
00042 {
00043   GZ_ASSERT(_model, "Model pointer is null");
00044 
00045   if (!_sdf->HasElement("contact_sensor_name"))
00046   {
00047     gzerr << "'contact_sensor_name' not specified in SDF\n";
00048   }
00049   this->model = _model;
00050   this->world = this->model->GetWorld();
00051   this->node = transport::NodePtr(new transport::Node());
00052   this->node->Init(this->world->GetName());
00053 
00054   this->contactSensorName = _sdf->Get<std::string>("contact_sensor_name");
00055   bool sensorFound = this->FindContactSensor();
00056   if (!sensorFound || !this->parentSensor)
00057   {
00058     gzerr << "Contact sensor not found: " << this->contactSensorName << "\n";
00059   }
00060 
00061   std::string parentLinkName = this->parentLink->GetScopedName();
00062   std::string defaultCollisionName = parentLinkName + "::__default__";
00063   if (this->parentSensor->GetCollisionCount() != 1)
00064   {
00065     gzerr << "SideContactPlugin requires a single collision to observe contacts for\n";
00066     return;
00067   }
00068 
00069   this->collisionName = this->parentSensor->GetCollisionName(0);
00070   if (this->collisionName == defaultCollisionName)
00071   {
00072     // Use the first collision of the parent link by default
00073     if (this->parentLink->GetCollisions().empty())
00074     {
00075       gzerr << "Couldn't find any collisions for the contact sensor.";
00076       return;
00077     }
00078     unsigned int index = 0;
00079     this->collisionName = this->parentLink->GetCollision(index)->GetScopedName();
00080   }
00081   gzdbg << "[" << this->model->GetName() << "] Watching collisions on: " << this->collisionName << "\n";
00082 
00083   if (_sdf->HasElement("contact_side_normal"))
00084   {
00085     this->sideNormal = _sdf->Get<ignition::math::Vector3d>("contact_side_normal");
00086   }
00087   else
00088   {
00089     this->sideNormal = ignition::math::Vector3d(0, 0, 1);
00090   }
00091 
00092 
00093   // FIXME: how to not hard-code this gazebo prefix?
00094   std::string contactTopic = "/gazebo/" + this->scopedContactSensorName;
00095   boost::replace_all(contactTopic, "::", "/");
00096   this->contactSub =
00097     this->node->Subscribe(contactTopic, &SideContactPlugin::OnContactsReceived, this);
00098 
00099   // Listen to the update event. This event is broadcast every
00100   // simulation iteration.
00101   this->updateConnection = event::Events::ConnectWorldUpdateBegin(
00102     boost::bind(&SideContactPlugin::OnUpdate, this, _1));
00103 }
00104 
00106 bool SideContactPlugin::FindContactSensor()
00107 {
00108   auto sensorManager = sensors::SensorManager::Instance();
00109   auto links = this->model->GetLinks();
00110   for (const auto &link : links)
00111   {
00112     std::string scopedContactSensorName =
00113       this->world->GetName() + "::" + link->GetScopedName() + "::" + this->contactSensorName;
00114     for (unsigned int i = 0; i < link->GetSensorCount(); ++i)
00115     {
00116       if (link->GetSensorName(i) == scopedContactSensorName)
00117       {
00118         this->parentLink = link;
00119         this->scopedContactSensorName = scopedContactSensorName;
00120         this->parentSensor =
00121           std::static_pointer_cast<sensors::ContactSensor>(
00122             sensorManager->GetSensor(scopedContactSensorName));
00123         return this->parentSensor != 0;
00124       }
00125     }
00126   }
00127   return false;
00128 }
00129 
00131 void SideContactPlugin::OnContactsReceived(ConstContactsPtr& _msg)
00132 {
00133   boost::mutex::scoped_lock lock(this->mutex);
00134   this->newestContactsMsg = *_msg;
00135   this->newMsg = true;
00136 }
00137 
00139 void SideContactPlugin::OnUpdate(const common::UpdateInfo &/*_info*/)
00140 {
00141   this->CalculateContactingModels();
00142 }
00143 
00145 void SideContactPlugin::CalculateContactingLinks()
00146 {
00147   if (!this->newMsg)
00148   {
00149     return;
00150   }
00151 
00152   auto parentLinkPose = this->parentLink->GetWorldPose().Ign();
00153   math::Vector3 parentLinkTopNormal = parentLinkPose.Rot().RotateVector(this->sideNormal);
00154 
00155   // Get all the contacts
00156   boost::mutex::scoped_lock lock(this->mutex);
00157   msgs::Contacts contacts = this->newestContactsMsg;
00158   this->contactingLinks.clear();
00159   double factor = 1.0;
00160 
00161   for (int i = 0; i < contacts.contact_size(); ++i)
00162   {
00163     // Get the collision that's not the parent link
00164     std::string collision = contacts.contact(i).collision1();
00165     if (this->collisionName == contacts.contact(i).collision1()) {
00166       collision = contacts.contact(i).collision2();
00167       factor = -1.0; // the frames are reversed for the alignment check
00168     }
00169 
00170     // Only consider links with collision normals aligned with the normal of the link's side
00171     for (int j = 0; j < contacts.contact(i).position_size(); ++j)
00172     {
00173       ignition::math::Vector3d contactNormal = msgs::ConvertIgn(contacts.contact(i).normal(j));
00174       double alignment = factor * parentLinkTopNormal.Dot(contactNormal);
00175       if (alignment > 0.0) {
00176         physics::CollisionPtr collisionPtr =
00177           boost::dynamic_pointer_cast<physics::Collision>(this->world->GetEntity(collision));
00178         if (collisionPtr) { // ensure the collision hasn't been deleted
00179           physics::LinkPtr link = collisionPtr->GetLink();
00180           this->contactingLinks.insert(link);
00181         }
00182       }
00183     }
00184   }
00185   this->newMsg = false;
00186 }
00187 
00189 void SideContactPlugin::CalculateContactingModels()
00190 {
00191   this->CalculateContactingLinks();
00192   this->contactingModels.clear();
00193   for (auto link : this->contactingLinks)
00194   {
00195     physics::ModelPtr model = link->GetModel();
00196     this->contactingModels.insert(model);
00197   }
00198 }


osrf_gear
Author(s):
autogenerated on Mon Sep 5 2016 03:41:33